Skip to content

Latest commit

 

History

History
103 lines (96 loc) · 11.2 KB

MIGRATION.md

File metadata and controls

103 lines (96 loc) · 11.2 KB

Migration Notes

API changes in MoveIt releases

ROS Rolling

  • [12/2023] trajectory_processing::Path and trajectory_processing::Trajectory APIs have been updated to prevent misuse. The constructors have been replaced by builder methods so that errors can be communicated. Paths and trajectories now need to be created with Path::Create() and Trajectory::Create(). These methods now return an std::optional that needs to be checked for a valid value. Trajectory no longer has the isValid() method. If it's invalid, Trajectory::Create() will return std::nullopt. Finally, Path now takes the list of input waypoints as std::vector, instead of std::list.
  • [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:
- planning_plugin: ompl_interface/OMPLPlanner
+ planning_plugins:
+   - ompl_interface/OMPLPlanner
  • [10/2023] Planning request adapters are now separated into PlanRequest (preprocessing) and PlanResponse (postprocessing) adapters. The adapters are configured with ROS parameter vectors (vector order corresponds to execution order). Please update your pipeline configurations for example like this:
- request_adapters: >-
-     default_planner_request_adapters/AddTimeOptimalParameterization
-     default_planner_request_adapters/ResolveConstraintFrames
-     default_planner_request_adapters/FixWorkspaceBounds
-     default_planner_request_adapters/FixStartStateBounds
-     default_planner_request_adapters/FixStartStateCollision
-     default_planner_request_adapters/FixStartStatePathConstraints
+ # The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
+ request_adapters:
+   - default_planning_request_adapters/ResolveConstraintFrames
+   - default_planning_request_adapters/ValidateWorkspaceBounds
+   - default_planning_request_adapters/CheckStartStateBounds
+   - default_planning_request_adapters/CheckStartStateCollision
+ response_adapters:
+   - default_planning_response_adapters/AddTimeOptimalParameterization
+   - default_planning_response_adapters/ValidateSolution
+   - default_planning_response_adapters/DisplayMotionPath
  • [2021] lockSceneRead() and lockSceneWrite() are now protected member functions, for internal use only. To lock the planning scene, use LockedPlanningSceneRO or LockedPlanningSceneRW:
      planning_scene_monitor::LockedPlanningSceneRO ls(planning_scene_monitor);
      moveit::core::RobotModelConstPtr model = ls->getRobotModel();
  • [2021] ServoServer was renamed to ServoNode
  • [2021] CollisionObject messages are now defined with a Pose, and shapes and subframes are defined relative to the object's pose. This makes it easier to place objects with subframes and multiple shapes in the scene. This causes several changes:
    • getFrameTransform() now returns this pose instead of the first shape's pose.
    • The Rviz plugin's manipulation tab now uses the object's pose instead of the shape pose to evaluate if object's are in the region of interest.
    • Planning scene geometry text files (.scene) have changed format. Loading old files is still supported. You can add a line 0 0 0 0 0 0 1 under each line with an asterisk to upgrade old files.
  • [2021] Add API for passing RNG to setToRandomPositionsNearBy
  • [2021] Static member variable interface of the CollisionDetectorAllocatorTemplate for the string NAME was replaced with a virtual method getName.
  • [2021] Enhance RDFLoader to load from string parameter OR string topic (and add the ability to publish a string topic).

ROS Noetic

  • RobotModel no longer overrides empty URDF collision geometry by matching the visual geometry of the link.
  • Planned trajectories are slow by default. The default values of the velocity_scaling_factor and acceleration_scaling_factor can now be customized and default to 0.1 instead of 1.0. The values can be changed by setting the parameters default_acceleration_scaling_factor and default_velocity_scaling_factor in the joint_limits.yaml of your robot's moveit_config package. Consider setting them to values between 0.2 and 0.6, to allow for significant speedup/slowdown of your application. Additionally, you can always change the factors per request with the corresponding methods in the move_group_interface, the MoveGroupCommander or in the Rviz interface. (1890)
  • Extended the return value of MoveitCommander.MoveGroup.plan() from trajectory to a tuple of (success, trajectory, planning_time, error_code) to better match the C++ MoveGroupInterface (790)
  • moveit_rviz.launch, generated by MSA, provides an argument rviz_config to configure the rviz config to be used. The old boolean config argument was dropped. (1397)
  • Moved the example package moveit_controller_manager_example into moveit_tutorials
  • Requests to get_planning_scene service without explicitly setting "components" now return full scene
  • moveit_ros_planning no longer depends on moveit_ros_perception
  • CollisionRobot and CollisionWorld are combined into a single CollisionEnv class. This applies for all derived collision checkers as FCL, ALL_VALID, HYBRID and DISTANCE_FIELD. Consequently, getCollisionRobot[Unpadded] / getCollisionWorld functions are replaced through a getCollisionEnv in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of CollisionRobot and CollisionWorld. Note that calling checkRobotCollision of the CollisionEnv does not take a CollisionRobot as an argument anymore as it is implicitly contained in the CollisionEnv.
  • RobotTrajectory provides a copy constructor that allows a shallow (default) and deep copy of waypoints
  • Replace the redundant namespaces robot_state:: and robot_model:: with the actual namespace moveit::core::. The additional namespaces will disappear in the future (ROS2).
  • Moved the library moveit_cpp to moveit_ros_planning. The classes are now in namespace moveit_cpp, access via moveit::planning_interface is deprecated.
  • The joint states of passive joints must be published in ROS and the CurrentStateMonitor will now wait for them as well. Their semantics dictate that they cannot be actively controlled, but they must be known to use the full robot state in collision checks. (moveit/moveit#2663)
  • Removed deprecated header moveit/macros/deprecation.h. Use [[deprecated]] instead.
  • All uses of MOVEIT_CLASS_FORWARD et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase).
  • In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. <ns>/move_group/display_planned_path instead of /move_group/display_planned_path).
  • RobotState::attachBody() now takes a unique_ptr instead of an owning raw pointer.
  • Moved the class MoveItErrorCode from both moveit_ros_planning and moveit_ros_planning_interface to moveit_core. The class now is in namespace moveit::core, access via moveit::planning_interface or moveit_cpp::PlanningComponent is deprecated.
  • End-effector markers in rviz are shown only if the eef's parent group is active and the parent link is part of that group. Before, these conditions were OR-connected. You might need to define additional end-effectors.
  • Removed ConstraintSampler::project() as there was no real difference to sample().
  • Removed TrajectoryExecutionManager::pushAndExecute() and the code associated to it. The code was unused and broken.

ROS Melodic

  • Migration to tf2 API.
  • Replaced Eigen::Affine3d with Eigen::Isometry3d, which is computationally more efficient. Simply find-replace occurrences of Affine3d: find . -iname "*.[hc]*" -print0 | xargs -0 sed -i 's#Affine3#Isometry3#g'
  • The move_group capability ExecuteTrajectoryServiceCapability has been removed in favor of the improved ExecuteTrajectoryActionCapability capability. Since Indigo, both capabilities were supported. If you still load default capabilities in your config/launch/move_group.launch, you can just remove them from the capabilities parameter. The correct default capabilities will be loaded automatically.
  • Deprecated method CurrentStateMonitor::waitForCurrentState(double wait_time) was finally removed.
  • Renamed RobotState::getCollisionBodyTransforms to getCollisionBodyTransform as it returns a single transform only.
  • Removed deprecated class MoveGroup (was renamed to MoveGroupInterface).
  • KinematicsBase: Deprecated members tip_frame_, search_discretization_. Use tip_frames_ and redundant_joint_discretization_ instead.
  • KinematicsBase: Deprecated initialize(robot_description, ...) in favour of initialize(robot_model, ...). Adapt your kinematics plugin to directly receive a RobotModel. See the KDL plugin for an example.
  • IK: Removed notion of IK attempts and redundant random seeding in RobotState::setFromIK(). Number of attempts is limited by timeout only. (#1288) Remove parameters kinematics_solver_attempts from your kinematics.yaml config files.
  • RDFLoader / RobotModelLoader: removed TinyXML-based API (moveit/moveit#1254)
  • Deprecated EndEffectorInteractionStyle got removed from RobotInteraction (moveit/moveit#1287) Use the corresponding InteractionStyle definitions instead

ROS Kinetic

  • In the C++ MoveGroupInterface class the plan() method returns a MoveItErrorCode object and not a boolean. static_cast<bool>(mgi.plan()) can be used to achieve the old behavior.
  • CurrentStateMonitor::waitForCurrentState(double wait_time) has been renamed to waitForCompleteState to better reflect the actual semantics. Additionally a new method waitForCurrentState(const ros::Time t = ros::Time::now()) was added that actually waits until all joint updates are newer than t.
  • To avoid deadlocks, the PlanningSceneMonitor listens to its own EventQueue, monitored by an additional spinner thread. Providing a custom NodeHandle, a user can control which EventQueue and processing thread is used instead. Providing a default NodeHandle, the old behavior (using the global EventQueue) can be restored, which is however not recommended.