diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index e968516f628..abe32b270cb 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -4,12 +4,11 @@ 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 ) -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,18 +19,23 @@ 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 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) + 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")