Skip to content

Commit

Permalink
Fix linking error with cached_ik_kinematics_plugin (#2292)
Browse files Browse the repository at this point in the history
Signed-off-by: Shane Loretz <sloretz@intrinsic.ai>
  • Loading branch information
sloretz authored and henningkayser committed Aug 15, 2023
1 parent 01ccced commit 3b9de9b
Showing 1 changed file with 9 additions and 5 deletions.
14 changes: 9 additions & 5 deletions moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,11 @@ find_package(ur_kinematics QUIET)

This comment has been minimized.

Copy link
@MEHARRAJ

MEHARRAJ Aug 28, 2023

find_package(Your_Dependency REQUIRED)

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

1 comment on commit 3b9de9b

@MEHARRAJ
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i want to get through this

Please sign in to comment.