Skip to content

Commit 4c901b2

Browse files
committed
Fix linking error with cached_ik_kinematics_plugin
Signed-off-by: Shane Loretz <[email protected]>
1 parent 92ca89d commit 4c901b2

File tree

1 file changed

+6
-2
lines changed

1 file changed

+6
-2
lines changed

moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@ ament_target_dependencies(moveit_cached_ik_kinematics_base
99
moveit_core
1010
moveit_msgs
1111
)
12-
target_link_libraries(moveit_cached_ik_kinematics_base moveit_cached_ik_kinematics_plugin)
1312

1413
if(trac_ik_kinematics_plugin_FOUND)
1514
include_directories(${trac_ik_kinematics_plugin_INCLUDE_DIRS})
@@ -20,6 +19,10 @@ generate_parameter_library(
2019
include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_parameters.yaml # path to input yaml file
2120
)
2221

22+
target_link_libraries(moveit_cached_ik_kinematics_base
23+
cached_ik_kinematics_parameters
24+
moveit_kdl_kinematics_plugin)
25+
2326
add_library(moveit_cached_ik_kinematics_plugin SHARED src/cached_ik_kinematics_plugin.cpp)
2427
set_target_properties(moveit_cached_ik_kinematics_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
2528
ament_target_dependencies(moveit_cached_ik_kinematics_plugin
@@ -31,7 +34,8 @@ ament_target_dependencies(moveit_cached_ik_kinematics_plugin
3134
target_link_libraries(moveit_cached_ik_kinematics_plugin
3235
cached_ik_kinematics_parameters
3336
moveit_kdl_kinematics_plugin
34-
moveit_srv_kinematics_plugin)
37+
moveit_srv_kinematics_plugin
38+
moveit_cached_ik_kinematics_base)
3539
if(trac_ik_kinematics_plugin_FOUND)
3640
target_link_libraries(moveit_cached_ik_kinematics_plugin ${trac_ik_kinematics_plugin_LIBRARIES})
3741
set_target_properties(moveit_cached_ik_kinematics_plugin PROPERTIES COMPILE_DEFINITIONS "CACHED_IK_KINEMATICS_TRAC_IK")

0 commit comments

Comments
 (0)