neo_rox_moveit2¶
Summary¶
neo_rox_moveit_config is a ROS 2 package that provides a MoveIt2 configuration for the EMROX robots from Neobotix. It includes a MoveIt2 configuration package and a launch file to start the MoveIt2 configuration.
As of November 2024, this package includes all the necessary configuration for the robot with EMROX and universal robot combinations.
The package can be found here: https://github.com/neobotix/neo_rox_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 EMROX robot description and the necessary configuration for the UR arm with EMROX providing the necessary cushion for collision avoidance of the arm with the mobile platform.
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¶
To start the MoveIt2 configuration, run the following command:
Real Robot:
ros2 launch neo_rox_moveit2 neo_ur_moveit.launch.py arm_type:=ur10e prefix:=ur10e use_ur_dc:=True
Attention
Please check your UR robot type if it is a DC variant and then set the use_ur_dc variant to True
Mock Hardware:
ros2 launch neo_rox_moveit2 neo_ur_moveit.launch.py rox_type:=argo arm_type:=ur10e prefix:=ur10e use_mock_hardware:=True
Simulation
ros2 launch neo_rox_moveit2 neo_ur_moveit.launch.py rox_type:=diff arm_type:=ur10 prefix:=ur10 gripper_type:=2f_140 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>'):
'rox_type':
Robot type
. Valid choices are: ['', 'argo', 'argo-trio', 'diff', 'trike']
(default: 'argo')
'arm_type':
Arm Types:
Elite Arms: ec66, cs66
Universal Robotics (UR): ur5, ur10, ur5e, ur10e
(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_rox_moveit2')
'use_sim_time':
Make MoveIt to use simulation time.
This is needed for the trajectory planing in simulation.
Defaults to True if `use_gz` is True
(default: 'False')
'prefix':
Prefix of the joint names in controllers configuration.
(same as "arm_type" argument)
(default: '')
'use_ur_dc':
Uses a shorter cabin box. Check with Neobotix, before selecting.
(default: 'False')
'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')
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.