Skip to content

Commit 98c538e

Browse files
committed
Fixed unresolved symbol runtime error due to not linking to yaml-cpp properly
1 parent 4d9fc31 commit 98c538e

File tree

2 files changed

+7
-5
lines changed

2 files changed

+7
-5
lines changed

mavros_extras/CMakeLists.txt

+7-4
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,7 @@ find_package(libmavconn REQUIRED)
3232

3333
find_package(eigen3_cmake_module REQUIRED)
3434
find_package(Eigen3 REQUIRED)
35-
# find_package(yaml_cpp REQUIRED)
36-
find_package(yaml_cpp_vendor REQUIRED)
35+
find_package(yaml-cpp REQUIRED)
3736

3837
## Find GeographicLib
3938
# Append to CMAKE_MODULE_PATH since debian/ubuntu installs
@@ -146,7 +145,9 @@ ament_target_dependencies(mavros_extras_plugins
146145
tf2_eigen
147146
message_filters
148147
Eigen3
149-
yaml_cpp_vendor
148+
)
149+
target_link_libraries(mavros_extras_plugins
150+
yaml-cpp
150151
)
151152
pluginlib_export_plugin_description_file(mavros mavros_plugins.xml)
152153

@@ -164,9 +165,11 @@ ament_target_dependencies(mavros_extras
164165
sensor_msgs
165166
mavros_msgs
166167
#console_bridge
167-
yaml_cpp_vendor
168168
urdf
169169
)
170+
target_link_libraries(mavros_extras
171+
yaml-cpp
172+
)
170173
rclcpp_components_register_node(mavros_extras PLUGIN "mavros::extras::ServoStatePublisher" EXECUTABLE servo_state_publisher)
171174

172175
install(TARGETS mavros_extras mavros_extras_plugins

mavros_extras/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,6 @@
4949
<depend>rcpputils</depend>
5050
<depend>urdf</depend>
5151
<depend>yaml-cpp</depend>
52-
<depend>yaml_cpp_vendor</depend>
5352

5453
<!-- message packages -->
5554
<depend>diagnostic_msgs</depend>

0 commit comments

Comments
 (0)