MoveIt Pro 6 Released - Runtime and Developer Platform for ROS 2

We’re excited to announce release MoveIt Pro 6 that further enhances the development platform for ROS 2 applications for robot arms on fixed bases, linear rails, and mobile manipulators.

Key New features:

lab_sim_low_res2

New High Fidelity Physics Simulation Engine

Simulate RGBD cameras, 2D and 3D LiDAR, and most importantly force-torque sensors! The simulator enables a variety of end effectors, including robust 2 finger grippers, vacuum and magnetic grippers, and tools that form rigid attachments, for example welding and nailing. Of particular note, MoveIt Pro’s simulator does not require a dedicated GPU (making it easy to use on any laptop or cloud compute). MoveIt Pro now uses this simulator by default instead of Gazebo.

New Motion Planning with MoveIt Pro RRTConnect

Meet our new joint-space planner, Pro RRTConnect. This planner is deterministic, faster to compute, and generates more efficient paths compared to OMPL planners. Its first release supports both free space and Cartesian path planning, and like all MoveIt planners, is hardware agnostic and collision aware.

Force Compliant Controllers

We have added two real-time controllers for force sensitive tasks: a Joint Trajectory Admittance Controller (JTAC) and a Velocity Force Controller (VFC). The JTAC is great for use cases where object localization is not 100% perfect or when interacting with heavy objects, such as grasping motions and opening doors. The VFC is great for use cases where a particular force needs to be exerted over a trajectory, such as sanding and cutting motions.

Whole Body Manipulation with Clearpath + UR

Whole Body Control for Mobile Manipulators

Mobile manipulators present a great opportunity to both free manipulators from fixed bases and to improve their reachability. If you have a robot arm on a base which has too many constraints, too few degrees of freedom (DOF), or not enough reachability to perform a task, whole body planning will enable the base to move in coordination with the arm to resolve redundancy and increase reachability.

Navigation Support

Control your AMR or AGV with two new MoveIt Pro Behaviors: NavigateToPoseAction and NavigateThroughPosesAction. These send the robot base to one or more poses using Nav2’s Behavior Trees.

Arm-Centric Visualization Improvements

We’ve added more intuitive 3D grid visualization, streamlined objective lists, and more intelligent error messaging. This makes it easier to identify points of failure in MoveIt motion planning and manipulation.

PLC Interaction with an IO Controller

We have added an Input/Output Controller that enables triggering ROS-enabled binary IO devices, such as activating vacuum grippers or communicating with PLCs, via behaviors.

Built on Open Source

MoveIt Pro fully embraces the ROS 2 ecosystem, including its build system, package management, message format, middleware, etc. MoveIt Pro is also built on MoveIt open source, following the common open core business model, providing commercial grade, premium real time controllers, planners, IK solvers, etc. We continue to maintain MoveIt open source and contribute to other key libraries including core ROS 2, ROS 2 Control, RobotWebTools, and more.

|960px;x540px;

13 Likes

This all sounds pretty awesome. What’s the reason for not adding these capabilities to Gazebo?

Do you now use the same simulator as nav2?

The simulation looks much like MuJoCo (GitHub - google-deepmind/mujoco: Multi-Joint dynamics with Contact. A general purpose physics simulator., refer e.g. model gallery: Model Gallery - MuJoCo Documentation). Assumming it is, maybe it was easier to integrate it into MoveIt Pro?

@gbiggs I’ll answer that in two parts - (1) why we developed the simulator and (2) why it is not integrated into a simulation framework:
1- We began investigating separate physics and rendering solutions due to performance limitations with the libraries shipped with Gazebo Fortress. Despite a great deal of investment on our part in the gz_ros2_control project last year, we were unable to get 2 finger gripper physics (with a mimic joint) at a sufficient level of reliability with DART physics. On the rendering side, ogre1 and ogre2 were unpredictable as to which would run on a particular customer’s machine, and the complexity there outweighed the benefits. The team actually tracked down and submitted an Ubuntu bug fix for a regression involving Mesa and Ogre 1.9.

2- Part of this was to keep the package size minimal for customer and CI workflows, part of this was due to concerns around leaky framework abstractions making it difficult to optimize physics settings (we have similar challenges in MoveIt with abstractions for sampling versus optimization based planners), but for me the main reason was the state of the documentation ~1 year ago for Fortress. Examples for writing custom plugins (for example, a mock vacuum end effector) were sparse and/or hard to find, in particular due to the timing of a couple things:

  • The migration of answers.gazebosim.org to robotics.stackexchange.com made existing answers hard to find because google had not reindexed. Personally, I worked around this by viewing the Google cache of answers.
  • The re-naming of Ignition to Gazebo also complicated finding relevant search results. When looking at code examples or answers, you’d often have to spend valuable time to determine if it was for what we now call gz-classic or gz-sim.

@peci - This is an in-house simulator designed for companies shipping mobile manipulation applications. That said, we are using Nav2!

@mhubii - Keen eye - indeed the physics backbone is Mujoco (though we have a lot built on top of it, such as tool changing mechanisms and 2F/vacuum/welding end effectors!). We also investigated Bullet featherstone, which we are excited to see is now shipped with gz-sim.

5 Likes

Hi @nathanbrooks the simulator looks really awesome. The reliability issue with DART, was it only for 2 finger gripper problems?

As I recall, the primary issue with DART was using it to model grasping for 2 finger grippers with a mimic joint where stall torque is used to recognize grasp success, e.g. grippers like the Robotiq 2F family. If you instead modeled a gripper with a single actuated a single stationary finger, the physics were much more stable, but not many people manufacture grippers like this. Even then, grasping a cube-like object and then moving the arm usually results in the cube shifting around. I imagine there are probably DART knobs to tune that sort of semi-adversarial contact patch, but gripping simulation is not a primary use case for DART so they are not easy to discover.

1 Like

this is great! Thank you for sharing the detailed insights.