neo_mpo_700-2

../_images/MPO_700_docs.gif
../_images/MMO_700_docs.gif

Summary

The neo_mpo_700-2 package provides configuration and launch files for the MPO-700 omnidirectional mobile platform. It manages the kinematics and bundles all necessary ROS 2 files to run the Neobotix MPO-700 for both real-world applications and simulations, including support for real and mock arms and grippers when configured as the MMO-700 mobile manipulator variant.

Launch

To bring up the robot drivers and hardware components, execute the following command in a terminal:

ros2 launch neo_mpo_700-2 bringup.launch.py

Launch Arguments

To view a detailed description of all available launch arguments, run:

ros2 launch neo_mpo_700-2 bringup.launch.py --show-arguments

Note

As of July 2023, namespacing support is partially available for MPO-700.

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

'robot_namespace':
    Top-level namespace
    (default: '')

'imu_enable':
    Enable IMU - Options: True/False
    (default: 'False')

'd435_enable':
    Enable Realsense - Options: True/False
    (default: 'False')

'scanner_type':
    Type of laser scanner to use. Valid choices are: ['', 'sick_s300', 'sick_microscan3']
    (default: 'sick_s300')

'disable_scanners':
    Disable Scanner - Options: True/False
    (default: 'False')

'use_docking_adapter':
    Enable docking adapter - Options: True/False
    (default: 'False')

'arm_type':
    Arm Types
    . Valid choices are: ['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66']
    (default: '')

'use_ur_dc':
    Set this argument to True if you have an UR arm with DC variant
    (default: 'False')

'gripper_type':
    Enables gripper and it's controllers. Valid choices are: ['', '2f_140', '2f_85', 'epick']
    (default: '')

'use_mock_arm':
    Mock arm and gripper (if available)
    (default: 'False')

'initial_controller_arm':
    Initial controller for the arm
    . Valid choices are: ['', 'joint_trajectory_controller', 'scaled_joint_trajectory_controller']
    (default: 'scaled_joint_trajectory_controller')

'robot_ip':
    IP address of the robot arm.
    (default: '192.168.1.102')

'controllers_file':
    YAML file with the arm controllers configuration.
    (default: '/home/pradheep/jazzy_ws/install/neo_mpo_700-2/share/neo_mpo_700-2/configs/ur/ur_controllers.yaml')

Nodes

The following table lists the nodes launched by the bringup.launch.py file, along with links to their detailed documentation.

Node Name See Package
relayboard_v2_node neo_relayboard_v2-2
neo_omnidrive_node neo_kinematics_omnidrive2
neo_omnidrive_socketcan neo_kinematics_omnidrive2
lidar_1 / lidar_2 neo_sick_s300-2
lidar_1_filter / lidar_2_filter neo_sick_s300-2
neo_teleop_node neo_teleop2

Note

For a list of services and topics, please refer to the documentation for the nodes mentioned above.

RQT-Graph

../_images/mpo_700_rosgraph.png