Skip to main content

6.0.0

· 10 min read

Major Features

New Simulation Engine

MoveIt Pro 6.0 introduces a new simulation engine that includes much higher fidelity physics simulation for manipulation tasks and more performant rendering of camera and depth data. This includes simulation of RGBD cameras, 2D and 3D LiDAR, force-torque sensors, and more! The new simulation engine has low system requirements and does not require a dedicated GPU. Check out the new arm_on_rail_sim configuration in the example workspace to try the new simulator for yourself.

Improved Configuration Parser

This version of Pro includes an overhaul of the parser that is used to construct a robot configuration from your YAML configs, Xacro files, and others. It includes much better error messaging for incorrectly-specified configuration arguments and will inform you when Pro deprecates parameters.

Pro RRTConnect

We have introduced a new joint-space planner (custom RRTConnect implementation), that can be used within MTC Tasks. This planner is deterministic, faster to compute, and more efficient compared to the default OMPL planner. In its initial release, orientation constraints are not supported. It can be used by setting planner_interface="pro_rrt" in your joint-space MTC planning Behaviors (SetupMTCMoveToJointState, SetupMTCMoveToPose, SetupMTCConnectWithTrajectory and SetupMTCMoveToNamedState).

Other New Features

Behavior Changes

  • Adds an optional constraints port to the SetupMTCMoveToPose Behavior for passing a moveit_msgs::msg::Constraints message to your selected planner.
  • The cost function for the SetupMTCMoveAlongFrameAxis Behavior now optimizes for longer Cartesian motions. This change enables MTC motion plans to move into contact. Previously, the planner favored short motions which made it difficult to move into contact.
  • Adds an optional ignore_environment_collisions port to the SetupMTCMoveAlongFrameAxis Behavior to ignore environment collisions during planning.
  • Adds an optional skip_collision_check port to the SetupMTCCurrentState Behavior to skip collision checking of the current robot state.
  • Updates the tip_offset port in the PlanCartesianPath Behavior to take in a 6D offset, i.e. position and orientation, instead of just a 3D position offset. Orientation is taken as roll, pitch, yaw (rad).
  • Adds optional ik_cartesian_space_density and ik_joint_space_density ports to the PlanCartesianPath Behavior that can be used to control the density of the path IK solution before turning it into a trajectory with TOTG.
  • Adds an optional timeout port to the GripperActionCommand Behavior in case the gripper is expected to take a long time to close.

New Behaviors

  • Adds a CropPointsInSphere Behavior.
  • Adds a PlanToJointGoal Behavior that plans between joint states using RRT. Short-cutting and time parameterization are applied to the path to create a trajectory message.
  • Adds a SetupMTCIgnoreCollisionsBetweenObjects Behavior to create an MTC Stage that modifies the planning scene's Allowed Collision Matrix to permit or forbid collision between a set of objects while planning subsequent Stages.
  • Adds a VisualizeMesh Behavior that can be used to visualize custom meshes within the Web UI.
  • Adds a VisualizePath Behavior that can be used to visualize a vector of PoseStamped as a polyline.
  • Add a VisualizePose Behavior. The Behavior publishes a Marker with three lines, one per axis, in red, green, blue at a location/orientation defined by a PoseStamped message.
  • Adds a GenerateCoveragePath Behavior to create a path that covers an area. The area to cover is defined by the origin (bottom-right corner), width, height and stride distance.
  • Adds two Behaviors to run admittance control at a stationary reference point. The GetRobotJointState Behavior extracts a ROS joint state message from a planning scene object. The CreateStationaryTrajectory Behavior creates a stationary trajectory of a specified duration at the provided joint state.

MoveIt Pro UI Changes

  • Increases the grid in the 3D visualization to 5 meters wide and includes useful measurement increments as sub-grids.
  • Removes running the Clear Snapshot Objective on UI bring-up and instead warns you if you have a non-empty Octomap that is now desynchronized from the UI.
  • Sorts favorited Objectives to the top of the Objectives list for easy access.
  • Renames the "Quick Objectives" list to "Favorites" to clarify how they are populated.
  • Adds a button to SubTree nodes to jump straight to the definition of that SubTree in the Objective Builder.
  • Adds an option to flag an Objective as being "SubTree Only" to hide it from the runnable Objectives list.
  • Improves some error messages in SubTree editing workflows.
  • Improves the search engine in the Behaviors list and Objectives list in the UI.
  • Adds an upgrade link to the UI when a new version of MoveIt Pro is available.
  • Errors when validating a user's license will now display in the user interface.

New Controllers

  • Adds a IOController controller to set discrete enable/disabled commands, such as when operating a vacuum gripper. The controller claims all state command interfaces specified by a ROS 2 parameter. The controller creates enable/disable service servers for each claimed interface.

Controller Changes

  • The JTAC and VFC controllers now offer services to re-zero the force-torque sensor readings. This allows logic for re-zeroing the force-torque sensor to be moved out of the hardware interfaces.
  • Enables using the JTAC even if a force/torque sensor is not defined. In this case JTAC will behave similarly to the JTC. It will disable admittance-related features, e.g. stop on force threshold, etc.

Dependency Changes

  • Upgrades the included version of Ubuntu to April 27 and ROS Humble to May 23.
  • Adds the ros2_control CLI to the MoveIt Pro Docker image.
  • Updates the included version of MoveIt Task Constructor.

Documentation Improvements

  • Revamped the MoveIt Pro documentation! 🎉
  • Added additional documentation for common installation questions
  • Added documentation for creating MoveIt Pro MuJoCo configuration based on a MoveIt Pro site config
  • Improved port documentation in some common behaviors
  • Clarified some installation instructions

Other Improvements

  • Reorders the questions in moveit_pro configure to be more intuitive.
  • Improves the help text in the moveit_pro CLI.
  • The moveit_pro CLI will now warn you if you do not have the proper permissions to access the Docker daemon.
  • Reduces the amount of warnings logged by MoveIt on bring-up of MoveIt Pro.
  • Verbose logging now includes timestamps at the beginning and end of running an objective.
  • Improves some licensing-related error messages.
  • Improves the MuJoCo integration to parse command interfaces from position, velocity, and motor tags in MJCF files.
  • Improves the validation logic for MoveIt Pro configuration packages to provide more helpful error messages when the config.yaml is syntactically incorrect.

Bug Fixes

  • Fixes acceleration profile calculation in the VFC.
  • Fixes a bug where larger Objectives might not zoom correctly when the "Fit to View" button is pressed.
  • Fixes a bug where copying and pasting port text could cause unnecessary duplication of behaviors.
  • Fixes a bug where a missing /camera_info topic for an image stream could cause the UI to freeze.
  • Fixes a bug where the waypoint_name dropdown on certain behaviors would not properly respond to clicks.
  • Fixes a bug where output ports would show up as in-out ports in the behavior tree status viewer.
  • Fixes a bug where a deleted objective could re-appear in the UI in the same session as it was deleted.
  • Fixes a bug where refreshing the MoveIt Pro UI would restart the running Objective.
  • Fixes a teleoperation bug where saving a new joint state to an existing waypoint might not succeed.
  • Fixes a bug where adding a port to a SubTree in the Objective Builder would prevent adding more ports to that same SubTree.
  • Fixes a bug where some Supervised Autonomy prompts would remain on-screen after stopping the objective that invoked them.
  • Fixes a bug where exceptionally large or exceptionally small Objectives caused strange tree layout behavior in the UI.
  • Fixes a visual bug with Joint Jog in Firefox.
  • Fixes a bug where the preview for waypoints might not change after the waypoint joint state was updated.
  • Fixes a bug where jogging a joint in Joint Jog did not exit the textual input for joint angles.

Known Issues

  • When using the MoveIt Pro UI, the Behavior sidebar for specifying port values will automatically close if you begin typing a value and then stop typing for ~2 seconds.

Migration Guide

Changes to config.yaml

The following XML tags have been deprecated and should be removed from your config.yaml:

  • hardware:
    • type:
    • ip:
  • optional_feature_params:
  • ui_params:
  • octomap_manager:

Deprecated tags such as ip should be managed directly in their corresponding launch/configuration file. Not all drivers expose or use an IP setting so we removed this and other tags.

As well, internal references are no longer supported. Replace any %>> hardware.type formatting with the desired content. For example:

  • Old:
    • 'name: "%>> hardware.type"'
    • 'use_fake_hardware: "%>> hardware.simulated"'
  • New:
    • 'name: "ur5e"'
    • 'use_fake_hardware: "true"'

Manual migration from use_all_planners port to planner_interface port for MTC free space planning behaviors

  • MTC Behaviors that do motion planning in joint-space no longer define a use_all_planners port. Instead, a new planner_interface port is used to select the planner to be used. The following options are allowed:

    • moveit_default (default): Uses the MoveIt planning pipeline with the RRTConnect implementation of OMPL. Equivalent to the previous use_all_planners=false.
    • moveit_all_planners: Uses the MoveIt planning pipeline with OMPL RRTConnect, OMPL APS, PILZ and STOMP. Equivalent to the previous use_all_planners=true.
    • pro_rrt: Uses the MoveIt Pro RRTConnect planner. Compared to the moveit_default setting, paths are 100% deterministic, are computed 4x faster, and are 30% more optimal in path length. In its initial release, orientation constraints are not supported.

Existing Objectives using MTC planning Behaviors directly or under SubTrees need to be updated to use the new planner_interface port. For example:

<!-- Old -->
<!-- <Action ID="SetupMTCMoveToJointState" use_all_planners="false" /> -->

<!-- New -->
<Action ID="SetupMTCMoveToJointState" planner_interface="moveit_default" />

Affected Behaviors are:

  • SetupMTCMoveToJointState
  • SetupMTCMoveToPose
  • SetupMTCConnectWithTrajectory
  • SetupMTCMoveToNamedState

And Subtrees using those Behaviors, e.g. Move To Waypoint.

Manual migration from tip_offset port type of position only (x;y;z) to position and orientation (x;y;z;roll;pitch;yaw)

  • The PlanCartesianPath Behavior now takes a full 3D position and orientation tip_offset, instead of just position. The tip_offset is now specified as a 6-element vector, using Euler angles (RPY) for the orientation, i.e. x;y;z;roll;pitch;yaw. Existing Objectives need to be updated accordingly, e.g.:
<!-- Old -->
<!-- <Action ID="PlanCartesianPath" tip_offset="0.0;0.0;0.1" /> -->

<!-- New -->
<Action ID="PlanCartesianPath" tip_offset="0.0;0.0;0.1;0.0;0.0;0.0" />

The trajectory_sampling_rate port type of the PlanCartesianPath behavior has changed from double to int

Fields in moveit_studio_vision_msgs::msg::GraspableObject have changed

  • The fields of moveit_studio_vision_msgs::msg::GraspableObject (source) have changed. Any custom Behaviors you have written that use GraspableObject will need to be updated to the new format.