Skip to content

Commit

Permalink
Fix linking error with cached_ik_kinematics_plugin
Browse files Browse the repository at this point in the history
Signed-off-by: Shane Loretz <sloretz@intrinsic.ai>
  • Loading branch information
sloretz committed Aug 10, 2023
1 parent 92ca89d commit 4c901b2
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt
Expand Up @@ -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})
Expand All @@ -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
Expand All @@ -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")
Expand Down

0 comments on commit 4c901b2

Please sign in to comment.