Skip to content

Commit

Permalink
Remove LMA kinematics plugin (#2595)
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Dec 12, 2023
1 parent 754d919 commit a787972
Show file tree
Hide file tree
Showing 20 changed files with 1 addition and 1,239 deletions.
2 changes: 0 additions & 2 deletions .dockerignore
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,9 @@
!moveit_planners/ompl/package.xml
!moveit_planners/chomp/chomp_motion_planner/package.xml
!moveit_planners/chomp/chomp_interface/package.xml
!moveit_planners/chomp/chomp_optimizer_adapter/package.xml
!moveit_planners/pilz_industrial_motion_planner_testutils/package.xml
!moveit_planners/pilz_industrial_motion_planner/package.xml
!moveit_planners/moveit_planners/package.xml
!moveit_planners/trajopt/package.xml
!moveit_runtime/package.xml
!moveit/package.xml
!moveit_ros/warehouse/package.xml
Expand Down
1 change: 0 additions & 1 deletion .github/CODEOWNERS.disabled
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,6 @@

/moveit_planners/ompl/ @BryceStevenWilley @mamoll
/moveit_planners/chomp/chomp_interface/ @raghavendersahdev @knorth55 @bmagyar
/moveit_planners/chomp/chomp_optimizer_adapter/ @raghavendersahdev @knorth55 @bmagyar
/moveit_planners/chomp/chomp_motion_planner/ @raghavendersahdev @knorth55 @bmagyar
/moveit_planners/pilz_industrial_motion_planner @jschleicher @ct2034
/moveit_planners/pilz_industrial_motion_planner_testutils/ @jschleicher @ct2034
1 change: 1 addition & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
API changes in MoveIt releases

## ROS Rolling
- [12/2023] LMA kinematics plugin is removed to remove the maintenance work because better alternatives exist like KDL or TracIK
- [10/2023] The planning pipeline now has a vector of planner plugins rather than a single one. Please update the planner plugin parameter e.g. like this:
```diff
- planning_plugin: ompl_interface/OMPLPlanner
Expand Down
5 changes: 0 additions & 5 deletions moveit_kinematics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ include(ConfigExtras.cmake)

set(THIS_PACKAGE_INCLUDE_DIRS
kdl_kinematics_plugin/include
lma_kinematics_plugin/include
srv_kinematics_plugin/include
cached_ik_kinematics_plugin/include
)
Expand All @@ -36,8 +35,6 @@ set(THIS_PACKAGE_LIBRARIES
moveit_cached_ik_kinematics_plugin
kdl_kinematics_parameters
moveit_kdl_kinematics_plugin
lma_kinematics_parameters
moveit_lma_kinematics_plugin
srv_kinematics_parameters
moveit_srv_kinematics_plugin
)
Expand All @@ -58,7 +55,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
)

pluginlib_export_plugin_description_file(moveit_core kdl_kinematics_plugin_description.xml)
pluginlib_export_plugin_description_file(moveit_core lma_kinematics_plugin_description.xml)
pluginlib_export_plugin_description_file(moveit_core srv_kinematics_plugin_description.xml)
pluginlib_export_plugin_description_file(moveit_core cached_ik_kinematics_plugin_description.xml)

Expand All @@ -67,7 +63,6 @@ include_directories(${THIS_PACKAGE_INCLUDE_DIRS})
add_subdirectory(cached_ik_kinematics_plugin)
add_subdirectory(ikfast_kinematics_plugin)
add_subdirectory(kdl_kinematics_plugin)
add_subdirectory(lma_kinematics_plugin)
add_subdirectory(srv_kinematics_plugin)
add_subdirectory(test)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,19 +36,13 @@

#include <moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h>
#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
// compilation error: KDL and LMA kinematics plugins declare same types
//#include <moveit/lma_kinematics_plugin/lma_kinematics_plugin.h>
#include <moveit/srv_kinematics_plugin/srv_kinematics_plugin.h>

#include <pluginlib/class_list_macros.hpp>
// register CachedIKKinematicsPlugin<KDLKinematicsPlugin> as a KinematicsBase implementation
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<kdl_kinematics_plugin::KDLKinematicsPlugin>,
kinematics::KinematicsBase);

// register CachedIKKinematicsPlugin<SrvKinematicsPlugin> as a KinematicsBase implementation
// PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<lma_kinematics_plugin::LMAKinematicsPlugin>,
// kinematics::KinematicsBase);

// register CachedIKKinematicsPlugin<SrvKinematicsPlugin> as a KinematicsBase implementation
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<srv_kinematics_plugin::SrvKinematicsPlugin>,
kinematics::KinematicsBase);
Expand Down
20 changes: 0 additions & 20 deletions moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt

This file was deleted.

This file was deleted.

This file was deleted.

Loading

0 comments on commit a787972

Please sign in to comment.