From d88d19fb2a1539f1dc21f37a15ad1ce1454b6400 Mon Sep 17 00:00:00 2001 From: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> Date: Sat, 1 Feb 2025 16:33:23 -0500 Subject: [PATCH] Add missing target dependencies to eigen_stl_containers (#3295) * Add missing target dependencies to eigen_stl_containers * Another one --- moveit_core/collision_detection/CMakeLists.txt | 1 + moveit_core/distance_field/CMakeLists.txt | 1 + moveit_core/robot_model/CMakeLists.txt | 1 + moveit_core/robot_state/CMakeLists.txt | 10 ++++++++-- 4 files changed, 11 insertions(+), 2 deletions(-) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index cd90e4d5c5..e3f8fd2120 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -18,6 +18,7 @@ generate_export_header(moveit_collision_detection) ament_target_dependencies( moveit_collision_detection + eigen_stl_containers pluginlib rclcpp rmw_implementation diff --git a/moveit_core/distance_field/CMakeLists.txt b/moveit_core/distance_field/CMakeLists.txt index c70886f12f..165d82a7aa 100644 --- a/moveit_core/distance_field/CMakeLists.txt +++ b/moveit_core/distance_field/CMakeLists.txt @@ -12,6 +12,7 @@ set_target_properties(moveit_distance_field ament_target_dependencies( moveit_distance_field Boost + eigen_stl_containers urdfdom urdfdom_headers visualization_msgs diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index 1a1c59fb49..2886ed4f0a 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -33,6 +33,7 @@ ament_target_dependencies( angles moveit_msgs Eigen3 + eigen_stl_containers geometric_shapes urdf urdfdom_headers diff --git a/moveit_core/robot_state/CMakeLists.txt b/moveit_core/robot_state/CMakeLists.txt index fad8b36830..840e6ba4e7 100644 --- a/moveit_core/robot_state/CMakeLists.txt +++ b/moveit_core/robot_state/CMakeLists.txt @@ -7,8 +7,14 @@ target_include_directories( $) set_target_properties(moveit_robot_state PROPERTIES VERSION ${${PROJECT_NAME}_VERSION}) -ament_target_dependencies(moveit_robot_state urdf tf2_geometry_msgs - geometric_shapes urdfdom_headers Boost) +ament_target_dependencies( + moveit_robot_state + eigen_stl_containers + urdf + tf2_geometry_msgs + geometric_shapes + urdfdom_headers + Boost) target_link_libraries(moveit_robot_state moveit_robot_model moveit_kinematics_base moveit_transforms)