Skip to content

Commit a8ed36e

Browse files
committed
Fixed unresolved symbol runtime error due to not linking to yaml-cpp properly
1 parent 3f2e372 commit a8ed36e

File tree

2 files changed

+7
-5
lines changed

2 files changed

+7
-5
lines changed

mavros_extras/CMakeLists.txt

Lines changed: 7 additions & 4 deletions
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
@@ -153,7 +152,9 @@ ament_target_dependencies(mavros_extras_plugins
153152
tf2_eigen
154153
message_filters
155154
Eigen3
156-
yaml_cpp_vendor
155+
)
156+
target_link_libraries(mavros_extras_plugins
157+
yaml-cpp
157158
)
158159
pluginlib_export_plugin_description_file(mavros mavros_plugins.xml)
159160

@@ -171,9 +172,11 @@ ament_target_dependencies(mavros_extras
171172
sensor_msgs
172173
mavros_msgs
173174
#console_bridge
174-
yaml_cpp_vendor
175175
urdf
176176
)
177+
target_link_libraries(mavros_extras
178+
yaml-cpp
179+
)
177180
rclcpp_components_register_node(mavros_extras PLUGIN "mavros::extras::ServoStatePublisher" EXECUTABLE servo_state_publisher)
178181

179182
install(TARGETS mavros_extras mavros_extras_plugins

mavros_extras/package.xml

Lines changed: 0 additions & 1 deletion
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)