From 4c901b25ab5c8d4b44aebcc997412cdfcdd5dbe6 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 10 Aug 2023 23:35:08 +0000 Subject: [PATCH 1/2] Fix linking error with cached_ik_kinematics_plugin Signed-off-by: Shane Loretz --- .../cached_ik_kinematics_plugin/CMakeLists.txt | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index e968516f628..92a065455e8 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -9,7 +9,6 @@ ament_target_dependencies(moveit_cached_ik_kinematics_base moveit_core moveit_msgs ) -target_link_libraries(moveit_cached_ik_kinematics_base moveit_cached_ik_kinematics_plugin) if(trac_ik_kinematics_plugin_FOUND) include_directories(${trac_ik_kinematics_plugin_INCLUDE_DIRS}) @@ -20,6 +19,10 @@ generate_parameter_library( include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_parameters.yaml # path to input yaml file ) +target_link_libraries(moveit_cached_ik_kinematics_base + cached_ik_kinematics_parameters + moveit_kdl_kinematics_plugin) + add_library(moveit_cached_ik_kinematics_plugin SHARED src/cached_ik_kinematics_plugin.cpp) set_target_properties(moveit_cached_ik_kinematics_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") ament_target_dependencies(moveit_cached_ik_kinematics_plugin @@ -31,7 +34,8 @@ ament_target_dependencies(moveit_cached_ik_kinematics_plugin target_link_libraries(moveit_cached_ik_kinematics_plugin cached_ik_kinematics_parameters moveit_kdl_kinematics_plugin - moveit_srv_kinematics_plugin) + moveit_srv_kinematics_plugin + moveit_cached_ik_kinematics_base) if(trac_ik_kinematics_plugin_FOUND) target_link_libraries(moveit_cached_ik_kinematics_plugin ${trac_ik_kinematics_plugin_LIBRARIES}) set_target_properties(moveit_cached_ik_kinematics_plugin PROPERTIES COMPILE_DEFINITIONS "CACHED_IK_KINEMATICS_TRAC_IK") From 68a6ee278c905936e469fc7e6f9deb2e5f0772ea Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 11 Aug 2023 17:24:19 +0000 Subject: [PATCH 2/2] Add PUBLIC/PRIVATE keywords Signed-off-by: Shane Loretz --- .../cached_ik_kinematics_plugin/CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index 92a065455e8..abe32b270cb 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -4,7 +4,7 @@ find_package(ur_kinematics QUIET) add_library(moveit_cached_ik_kinematics_base SHARED src/ik_cache.cpp) set_target_properties(moveit_cached_ik_kinematics_base PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -ament_target_dependencies(moveit_cached_ik_kinematics_base +ament_target_dependencies(moveit_cached_ik_kinematics_base PUBLIC rclcpp moveit_core moveit_msgs @@ -19,19 +19,19 @@ generate_parameter_library( include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_parameters.yaml # path to input yaml file ) -target_link_libraries(moveit_cached_ik_kinematics_base +target_link_libraries(moveit_cached_ik_kinematics_base PUBLIC cached_ik_kinematics_parameters moveit_kdl_kinematics_plugin) add_library(moveit_cached_ik_kinematics_plugin SHARED src/cached_ik_kinematics_plugin.cpp) set_target_properties(moveit_cached_ik_kinematics_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -ament_target_dependencies(moveit_cached_ik_kinematics_plugin +ament_target_dependencies(moveit_cached_ik_kinematics_plugin PUBLIC rclcpp moveit_core moveit_msgs rsl ) -target_link_libraries(moveit_cached_ik_kinematics_plugin +target_link_libraries(moveit_cached_ik_kinematics_plugin PRIVATE cached_ik_kinematics_parameters moveit_kdl_kinematics_plugin moveit_srv_kinematics_plugin