diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 9f000181c73..c8702b3ce1e 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -218,7 +218,7 @@ install( ) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) -ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} orocos_kdl_vendor) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) # Plugin exports pluginlib_export_plugin_description_file(moveit_core collision_detector_fcl_description.xml) diff --git a/moveit_core/package.xml b/moveit_core/package.xml index f7b8aed0264..2b73331cc2e 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -65,7 +65,7 @@ moveit_resources_pr2_description angles tf2_kdl - orocos_kdl_vendor + orocos_kdl ament_cmake_gtest ament_index_cpp diff --git a/moveit_kinematics/CMakeLists.txt b/moveit_kinematics/CMakeLists.txt index f72877c82fd..9f327cef8b7 100644 --- a/moveit_kinematics/CMakeLists.txt +++ b/moveit_kinematics/CMakeLists.txt @@ -67,7 +67,7 @@ install( ) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) -ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} orocos_kdl_vendor) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) diff --git a/moveit_kinematics/package.xml b/moveit_kinematics/package.xml index cd415faf75a..5eba3262df8 100644 --- a/moveit_kinematics/package.xml +++ b/moveit_kinematics/package.xml @@ -30,7 +30,7 @@ eigen tf2 tf2_kdl - orocos_kdl_vendor + orocos_kdl moveit_msgs diff --git a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt index 57ec3424c61..9230657fcf9 100644 --- a/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt +++ b/moveit_planners/pilz_industrial_motion_planner/CMakeLists.txt @@ -193,7 +193,7 @@ ament_export_include_directories( include ) ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET) -ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} orocos_kdl_vendor) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) if(BUILD_TESTING) # Include Tests diff --git a/moveit_planners/pilz_industrial_motion_planner/package.xml b/moveit_planners/pilz_industrial_motion_planner/package.xml index 9bc95b61f3e..15f350171f8 100644 --- a/moveit_planners/pilz_industrial_motion_planner/package.xml +++ b/moveit_planners/pilz_industrial_motion_planner/package.xml @@ -28,7 +28,7 @@ moveit_core moveit_ros_planning moveit_ros_move_group - orocos_kdl_vendor + orocos_kdl pluginlib rclcpp tf2