From 6da19102ef3ee8a650772712abec63e0bb27ec73 Mon Sep 17 00:00:00 2001 From: Evan Palmer Date: Fri, 13 Sep 2024 17:41:39 -0700 Subject: [PATCH 1/2] Resolved build error with yaml-cpp --- mavros_extras/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/mavros_extras/CMakeLists.txt b/mavros_extras/CMakeLists.txt index dc0fd0cbb..8e52b6f27 100644 --- a/mavros_extras/CMakeLists.txt +++ b/mavros_extras/CMakeLists.txt @@ -32,7 +32,7 @@ find_package(libmavconn REQUIRED) find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) -# find_package(yaml_cpp REQUIRED) +find_package(yaml-cpp REQUIRED) find_package(yaml_cpp_vendor REQUIRED) ## Find GeographicLib @@ -132,6 +132,7 @@ add_library(mavros_extras_plugins SHARED src/plugins/wheel_odometry.cpp # [[[end]]] (checksum: 1f8cd51fa90b89b27ee35d276b5f8c83) ) +target_link_libraries(mavros_extras_plugins yaml-cpp::yaml-cpp) ament_target_dependencies(mavros_extras_plugins angles geometry_msgs @@ -164,6 +165,7 @@ add_library(mavros_extras SHARED src/lib/servo_state_publisher.cpp # [[[end]]] (checksum: a3ce43c71c567f697861bcbcd0f25aa3) ) +target_link_libraries(mavros_extras yaml-cpp::yaml-cpp) ament_target_dependencies(mavros_extras rclcpp rclcpp_components From 5884e2f5010cc811398d92eddede9b0c7454e68a Mon Sep 17 00:00:00 2001 From: Evan Palmer Date: Fri, 13 Sep 2024 17:55:15 -0700 Subject: [PATCH 2/2] Resolved build yaml-cpp build error --- mavros_extras/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavros_extras/CMakeLists.txt b/mavros_extras/CMakeLists.txt index 8e52b6f27..309d08220 100644 --- a/mavros_extras/CMakeLists.txt +++ b/mavros_extras/CMakeLists.txt @@ -213,4 +213,4 @@ ament_export_dependencies(Eigen3) #ament_export_targets(mavros_node) ament_package() -# vim: ts=2 sw=2 et: +# vim: ts=2 sw=2 et: \ No newline at end of file