neo_ur_moveit_config

Summary

neo_ur_moveit_config is a ROS 2 package that provides a MoveIt2 configuration for the MMO (MPO with arms) robots from Neobotix. It includes a MoveIt2 configuration package and a launch file to start the MoveIt2 configuration.

As of May 2025, this package includes all the necessary configuration for the robot with MPO-700, MPO-500 with UR5, UR10, UR5e and UR10e combinations.

Coming soon:

  • mpo_700 + Elite arms
  • mpo_500 + Elite arms

The package can be found here: https://github.com/neobotix/neo_mpo_moveit2

Note

This package was heavily adapted from the ur_moveit_config.

The major difference from the original package is the addition of the Neobotix MMO robot description and the necessary configuration for the UR arm with MPO-700 providing the necessary cushion for collision avoidance of the arm with the mobile platform.

../_images/mpo_700_moveit.png

Prerequisites

In case of a real robot, please refer Starting with ROS 2 on the Robot. For simulation please refer Starting with ROS 2 on Modern Gazebo.

Launch

Warning

Some of the arguments might not be available for Iron and lower versions of ROS 2 Distro. Please look at the launch arguments by running the launch command with the –show-arguments

To start the MoveIt2 configuration, run the following command:

Real Robot:

ros2 launch neo_ur_moveit_config neo_ur_moveit.launch.py robot_type:=mpo_700 arm_type:=ur10 prefix:=ur10

Mock Hardware:

ros2 launch neo_ur_moveit_config neo_ur_moveit.launch.py robot_type:=mpo_700 arm_type:=ur10 prefix:=ur10 use_mock_arm:=True

Simulated Robot:

ros2 launch neo_ur_moveit_config neo_ur_moveit.launch.py robot_type:=mpo_700 arm_type:=ur10 prefix:=ur10 use_gz:=True

Note

The prefix launch argument must be explicitly set in the MoveIt launch command, even though its value is the same as arm_type.

here are the available launch arguments:

Arguments (pass arguments as '<name>:=<value>'):

'robot_type':
    Robot Types
. Valid choices are: ['', 'mpo_700', 'mpo_500']
    (default: 'mpo_700')

'arm_type':
    Arm Types - Supported Robots [mpo-700, mpo-500]
. Valid choices are: ['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66']
    (default: '')

'gripper_type':
    Gripper Types - Supported Robots [mpo-700, mpo-500]
. Valid choices are: ['', '2f_140', '2f_85', 'epick']
    (default: '')

'moveit_config_package':
    MoveIt config package with robot SRDF/XACRO files. Usually the argument
 is not set, it enables use of a custom moveit config.
    (default: 'neo_ur_moveit_config')

'use_sim_time':
    Make MoveIt to use simulation time.
 This is needed for the trajectory planing in simulation.
    (default: 'False')

'prefix':
    Prefix of the joint names in controllers configuration.
 (same as "arm_type" argument)
    (default: '')

'use_gz':
    Whether to enable Gazebo simulation.
    (default: 'False')

'use_mock_hardware':
    Indicate whether robot is running with mock hardware mirroring command to its states.
    (default: 'False')

'launch_rviz':
    Launch RViz?
    (default: 'True')

Note

In order to send goals to the gripper from RViz. It is essential to change the planning group in the motion planning plugin to gripper under the planning tab (Applicable only for humble version).

For versions later than Humble, there is no seperate planning group for the Robotiq gripper. It is expected to use the ROS 2 actions provided by the Robotiq Gripper ROS Node for sending commands to the gripper. An example is as follows:

ros2 action send_goal /robotiq_gripper/robotiq_gripper_controller/gripper_cmd control_msgs/action/GripperCommand "{command: {position: 0.5, max_effort: 30.0}}"

The launch file will start the MoveIt2 configuration and the RViz visualization tool. The RViz window will show the robot model and the MoveIt2 plugin for motion planning.

Please refer to MoveIt2 documentation for more detailed information about planning and execution of motion for the robot arms.