Skip to content

Commit

Permalink
Fix linking error with cached_ik_kinematics_plugin (backport #2292) (#…
Browse files Browse the repository at this point in the history
…2300)

* Fix linking error with cached_ik_kinematics_plugin

Signed-off-by: Shane Loretz <sloretz@intrinsic.ai>
(cherry picked from commit 4c901b2)

* Add PUBLIC/PRIVATE keywords

Signed-off-by: Shane Loretz <sloretz@intrinsic.ai>
(cherry picked from commit 68a6ee2)

---------

Co-authored-by: Shane Loretz <sloretz@intrinsic.ai>
  • Loading branch information
mergify[bot] and sloretz committed Aug 15, 2023
1 parent b0f0f68 commit 0fbe48c
Showing 1 changed file with 9 additions and 5 deletions.
14 changes: 9 additions & 5 deletions moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt
Expand Up @@ -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})
Expand All @@ -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")
Expand Down

0 comments on commit 0fbe48c

Please sign in to comment.