Skip to main content

ROSbot XL with OpenMANIPULATOR-X

About

To further extend the capabilities of your ROSbot XL, you can pair it with OpenMANIPULATOR-X. In this basic demo, you will learn how to integrate them, and at the end of this tutorial you will be able to control the manipulator using a gamepad and MotionPlanning RViz plugin. In the clip below you can see the final result.

How to get it?

If you don't have OpenMANIPULATOR-X, you can get it together with ROSbot XL in our online store.



Two key components of this setup are ros2_control and MoveIt 2.

ros2_control is used for controlling Dynamixel servos (you can find the code in this repository). It provides a position command interface, with position and velocity feedback, which can be combined with the JointTrajectoryController to execute planned motions.

MoveIt 2 is responsible for preparing motion plans, based on the desired end effector position. It can be controlled in RViz by simply dragging the marker, with a gamepad using servo mode or through the ROS 2 API. Code for MoveIt 2 integration is in the rosbot_xl_manipulation_ros repository.

Preparations

Mounting

First you need to mount and connect your manipulator, please refer to our dedicated guide. The recommended configuration, that is later used in this tutorial, is pictured below.

mountingmounting
Changing the mounting place of the manipulator

This is a more advanced step, if you're not familiar with MoveIt, please continue with the recommended setup.

If you would like to mount the manipulator elsewhere, there will be some adjustments necessary:

  • change position of the manipulator in the rosbot_xl_manipulation.urdf.xacro
  • regenerate collision matrix using ros2 launch rosbot_xl_manipulation_moveit setup_assistant.launch.py (Self-Collisions tab)

Connection

Now add the following symlink to the /etc/udev/rules.d/10-local.rules udev rules file:

ACTION=="add", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6014", SYMLINK+="ttyMANIPULATOR"

And connect the manipulator to the SBC or Digital Board (make sure to also reboot the SBC so that symlink will be applied).

Antenna

The antenna in the upward position limits the movement of the manipulator - taking into account collision boxes, the distance between them is really small and collision detection is triggered frequently. For a better experience, it is recommended to rotate your antenna by 90 degrees, as pictured below.

antennaantenna

Of course, if you prefer some other configuration, you can simply adjust the ANTENNA_ROTATION_ANGLE env variable.

Setup

Prerequisites

Before we begin, there are a few things you'll need to have set up on your computer. First, you'll need to install Docker Engine and Docker Compose by following the official installation guide. This project has been tested on the following setup:

$ docker compose version
Docker Compose version v2.12.2
$
$ docker --version
Docker version 20.10.21, build baeda1f

Repository Setup

First it will be necessary to get the Github repository on both your PC and robot. You can do it by cloning the repo to your PC and using the ./sync_with_rosbot.sh to synchronize it to the ROSbot (any subsequent changes will be also synchronized):

git clone https://github.com/husarion/rosbot-xl-manipulation.git
cd rosbot-xl-manipulation
export ROSBOT_ADDR=10.5.10.123 # Replace with your own ROSbot's IP or Husarnet hostname
./sync_with_rosbot.sh $ROSBOT_ADDR

Now pull the images on both your PC and ROSbot:

ROSbot:

cd rosbot-xl-manipulation
docker compose -f compose.rosbot.yaml pull

Similarly, on your PC:

cd rosbot-xl-manipulation
docker compose -f compose.pc.yaml pull

Flashing the ROSbot's Firmware

To make sure that you run the correct version of the firmware, flash the one provided in the docker image. To do it execute the following commands in the ROSbot's shell:

docker stop rosbot-xl microros 2>/dev/null || true && \
docker run --rm -it --privileged \
--mount type=bind,source=/dev/ttyUSBDB,target=/dev/ttyUSBDB \
husarion/rosbot-xl-manipulation:humble \
flash-firmware.py -p /dev/ttyUSBDB

Choosing the Network (DDS) Config

Edit the net.env file and uncomment one of the configs:

net.env
# =======================================
# Network config options (uncomment one)
# =======================================

# 1. Fast DDS + LAN
# RMW_IMPLEMENTATION=rmw_fastrtps_cpp

# 2. Cyclone DDS + LAN
# RMW_IMPLEMENTATION=rmw_cyclonedds_cpp

# 3. Fast DDS + VPN
# RMW_IMPLEMENTATION=rmw_fastrtps_cpp
# FASTRTPS_DEFAULT_PROFILES_FILE=/husarnet-fastdds.xml

# 4. Cyclone DDS + VPN
RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
FASTRTPS_DEFAULT_PROFILES_FILE=/husarnet-fastdds.xml
CYCLONEDDS_URI=file:///husarnet-cyclonedds.xml
VPN connection

If you choose to use the VPN option, both your ROSbot XL and laptop must be connected to the same Husarnet network. If they are not, follow this guide: Connecting ROSbot and Laptop over the Internet (VPN).

Verifying Hardware Configuration

To ensure proper hardware configuration, check the content of the .env file:

# =======================================
# Hardware config
# =======================================

MANIPULATOR_SERIAL=/dev/ttyMANIPULATOR
MANIPULATOR_BAUDRATE=1000000

ANTENNA_ROTATION_ANGLE=-1.57

# MECANUM=True
MECANUM=False

The default options should be suitable.

Manipulator baudrate

Set MANIPULATOR_BAUDRATE according to the baud rate that is set in servos (by default this value should be set to 1000000, you can check/change this value in the Dynamixel Wizard 2.0).

Running demo

Before you start containers on your ROSbot XL, please note that it will enable the torque of the manipulator. The manipulator stays in the position that it was launched in, so first lift it, so it won't be in collision with the robot (as any movement won't be allowed in this state). If you forgot about it and started the manipulator in a collision state, please follow the Resetting the manipulator step.

After lifting the manipulator you can launch the controller on your robot:

docker compose -f compose.rosbot.yaml up

Now you can let go of the manipulator - torque should be already enabled. As a next step launch RViz and gamepad on your PC (gamepad should be connected to your PC):

xhost +local:docker && \
docker compose -f compose.pc.yaml up

And that's all! You will now be able to control ROSbot XL and OpenMANIPULATOR-X with a gamepad or RViz. For control details please refer to the next sections.

Gamepad Control

First make sure that gamepad is in the Direct Input Mode (switch in front with letters D and X, select D). Gamepad controls are defined in the config directory in the joy_servo.yaml (manipulator) and joy2twist.yaml (ROSbot XL). Feel free to adjust them to your preference, below you can find a summary of default controls:

  • RB - manipulator's dead man's switch (has to be pressed while executing other manipulator commands)
  • LB - ROSbot control dead man's switch (with this button pressed you can control ROSbot XL, for specific commands please refer to the documentation of the joy2twist node)
  • Start - return the manipulator to the Home position
  • Left Joy - move end effector in X/Y directions
  • Right Joy - move the end effector in the Z direction (Up/Down) and change the Pitch angle (Left/Right)
  • Left/Right arrow - move joint1 of the manipulator
  • Up/Down arrow - move joint2 of the manipulator
  • X/B - move joint3 of the manipulator
  • Y/A - move joint4 of the manipulator
  • RT - open/close gripper

The cartesian coordinate frame was defined to be in the link2 - that's why the Y direction is actually yaw rotation. This configuration was chosen due to better ease of use, but it can be also adjusted in the servo.yaml config.

You may have noticed that the movement of the manipulator is slow, and the full capabilities of the manipulator are not fully utilized. This is a safety precaution to ensure that the collision checker effectively prevents the manipulator from bumping into the robot. The dynamic limits of the manipulator have been tuned in order to provide a reliable collision prevention mechanism. While this setup should cover most situations, there is still a possibility of accidental contact with the robot or its sensors. Therefore, we advise you to remain aware of this potential risk when operating the manipulator.

Troubleshooting
  • Gripper does not move - it could be caused by the wrong initial position. Turn off the torque as described in the Resetting the manipulator. Now manually rotate the hub of the manipulator servo 180 degrees (if the connecting rod of the left finger was below the right finger's one, the hub should be rotated so that it is above). Now once again launch controllers.
  • Manipulator stopped moving - it can be too close to collision or singularity (you can verify it by examining console logs). The easiest solution to this problem is to return the manipulator to the Home position (Start button).
  • Manipulator stopped moving and Start button does not work - if the manipulator still won't move, it could be already in the collision (you can verify it by examining console logs). In this case, follow the Resetting the manipulator step and return it manually to some valid position.

Rviz control

It is also possible to control the manipulator in the RViz using the MotionPlanning plugin. You can move the end effector by dragging the green marker and then click the Plan & Execute button to make the manipulator execute the motion. You may notice that the end effector doesn't follow the marker exactly, and to get Z rotation you have to use the blue ring - this is due to insufficient degrees of freedom of the manipulator, which causes some of the configurations to not be achievable.

rviz-control

Troubleshooting

If you're not able to move the end effector in the Rviz, make sure that you have enabled the Approx IK Solutions option.

If the manipulator moves really slowly, change Velocity Scaling and Accel. Scaling to 1.0.

Resetting the manipulator

In some situations it may be necessary to manually move the manipulator out of an invalid configuration. To do it, first you will have to disable the torque of the manipulator, for example using the service. On your ROSbot XL execute:

docker exec -it rosbot_xl_manipulation bash

And call the service (hold the manipulator while doing it, as it disables the torque and the manipulator can fall).

ros2 service call /controller_manager/set_hardware_component_state \
controller_manager_msgs/srv/SetHardwareComponentState \
"{name: 'manipulator', target_state: {id: 0, label: 'inactive'}}"

Now you can manually move the manipulator to the desired position. After repositioning the manipulator, it's crucial to restart the containers to ensure that the controller's state is properly reset.

It is important to avoid using the service mentioned earlier to enable torque after repositioning the manipulator. The controller saves the previous position and will attempt to return to it when torque is enabled. This can be potentially dangerous, as it disregards any collisions or obstacles. Therefore, restarting the containers is essential to ensure safe operation.

Gazebo simulation

gazebo

Prerequisites

The compose.sim.gazebo.yaml file in this project uses Nvidia Container Runtime, so please install the Nvidia Container Toolkit before moving forward.

To run the Gazebo simulation of the ROSbot XL with OpenMANIPULATOR-X first connect the gamepad to your PC, then navigate to your rosbot-xl-manipulation directory and execute:

xhost +local:docker && \
docker compose -f compose.sim.gazebo.yaml up

Now you will be able to control the robot and manipulator using a gamepad or RViz, just like in the case of the real robot.

Summary

In this tutorial you learned how to combine OpenMANIPULATOR-X with your ROSbot XL and control it using a gamepad. This is only a simple demonstration, and MoveIt is a much more powerful tool. By composing a scene and adding sensors, it can plan complex movements that will avoid obstacles, not only self-collisions. Feel free to use this example as a basis for your next, more advanced project!


by Maciej Stępień, Husarion

Do you need any support with completing this project or have any difficulties with software or hardware? Feel free to describe your thoughts on our community forum: https://community.husarion.com/ or to contact our support: support@husarion.com