ROS2 · Arm Control · Gripper Control · Trajectory Interfaces · RViz · Open Source
简体中文 | English | API Reference
Current version: v0.3.0
rebotarm_ros2 is the ROS2 SDK workspace for reBot Arm B601 DM and RS models. It
wraps the current reBotArm_control_py Python control library into ROS2 topics,
services and actions, providing a unified entry point for development, planning,
RViz visualization, gravity compensation and per-motor debugging.
The workspace contains five ROS2 packages:
| Package | Purpose |
|---|---|
rebotarm_msgs |
Custom msg / srv / action interfaces |
rebotarmcontroller |
Driver node package, including reBotArmController |
rebotarm_bringup |
Launch files, configs, URDF and RViz resources |
rebotarm_moveit_config |
MoveIt 2 config, SRDF, ros2_control and RViz config |
rebotarm_moveit_demos |
MoveIt 2 demos, including pick-place and rectangle drawing |
- Publishes arm status:
/rebotarm/joint_states,/rebotarm/arm_status - Provides core services:
enable,disable,set_zero,safe_home - Supports Cartesian targets:
MoveToPoseIKservice,MoveToPoseaction - Supports the standard
control_msgs/action/FollowJointTrajectoryinterface - Supports gripper control:
SetGripperservice,GripperCommandaction - Supports single-joint commands:
JointMitCmd,JointPosVelCmd
| Item | Requirement |
|---|---|
| Arm | reBot Arm B601 DM or RS |
| Communication | DM: USB serial bridge; RS: SocketCAN interface |
| Host | Ubuntu 22.04+, ROS2, Python 3.10+ |
Wiring:
- Connect the USB2CAN serial bridge to the arm CAN bus.
- Connect the gripper motor to the same CAN bus.
- Plug the USB2CAN bridge into the host and check the device name:
ls /dev/ttyACM*For temporary serial access:
sudo chmod 666 /dev/ttyACM0RS uses SocketCAN by default. Bring up the CAN interface before starting the ROS2 driver:
sudo ip link set can0 up type can bitrate 1000000
ip -details link show can0Choose and install the appropriate ROS2 distribution from the official ROS getting started guide.
Preferred upstream repository:
git clone https://github.com/Seeed-Projects/reBotArmController_ROS2.git rebotarm_ros2
cd rebotarm_ros2Current development repository:
git clone https://github.com/EclipseaHime017/reBotArmController_ROS2.git rebotarm_ros2
cd rebotarm_ros2Install motorbridge from the official PyPI index:
python3 -m pip install --user --index-url https://pypi.org/simple motorbridgemkdir -p third_party
git clone https://github.com/vectorBH6/reBotArm_control_py.git third_party/reBotArm_control_pycolcon build --symlink-install
source install/setup.bashVerify installed executables:
ros2 pkg executables rebotarmcontrollerExpected output:
rebotarmcontroller reBotArmController
rebotarmcontroller GravityCompensation
rebotarmcontroller GripperControl
rebotarmcontroller MoveTo
rebotarmcontroller MoveToPose
rebotarm_ros2/
├── README.md
├── README_zh.md
├── API_zh.md
├── PLAN.md
├── instruction.md
└── src/
├── rebotarm_msgs/
│ ├── msg/
│ ├── srv/
│ └── action/
├── rebotarmcontroller/
│ ├── rebotarmcontroller/
│ │ ├── rebotarm_controller.py
│ │ ├── hardware_manager.py
│ │ ├── ros_publishers.py
│ │ ├── ros_services.py
│ │ ├── ros_actions.py
│ │ ├── motor_passthrough.py
│ │ ├── conversions.py
│ │ └── examples/
├── rebotarm_bringup/
│ ├── launch/
│ ├── config/
│ ├── description/
│ └── rviz/
├── rebotarm_moveit_config/
│ ├── config/
│ └── launch/
└── rebotarm_moveit_demos/
├── config/
├── launch/
└── rebotarm_moveit_demos/
Before using the robot, note the following: The arm controller has a high degree of freedom. Before enabling the controller or powering the arm, make sure the workspace is clear of people and obstacles. Review every motion command carefully to avoid accidents. Dangerous operation is strictly prohibited; you are responsible for any consequences.
Start the controller node, robot_state_publisher, and optionally RViz:
ros2 launch rebotarm_bringup bringup.launch.pyreBotArmController connects to real hardware on startup. The default model is
defined by rebotarm_bringup/config/rebotarm_hardware.yaml and is currently
dm.
If you use the RS arm and have not changed default_model, pass model:=rs
explicitly and set channel:=can0.
ros2 launch rebotarm_bringup bringup.launch.py channel:=/dev/ttyACM1
ros2 launch rebotarm_bringup bringup.launch.py model:=rs channel:=can0Enable RViz to visualize the arm motion:
ros2 launch rebotarm_bringup bringup.launch.py use_rviz:=trueUnlike bringup.launch.py, this starts only the controller node. Use it when
you want the minimal hardware control process without robot_state_publisher
or RViz visualization.
ros2 launch rebotarm_bringup driver.launch.pyros2 run rebotarmcontroller reBotArmControllerUnlike driver.launch.py, which passes configuration files from
rebotarm_bringup/config, running the controller directly falls back to the
default SDK arm configuration. For normal use, launching through ROS is
recommended.
Without running an example script, you can call ROS services and actions directly. Start the controller in one terminal:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_bringup bringup.launch.py channel:=/dev/ttyACM0In another terminal:
cd your/path/to/rebotarm_ros2
source install/setup.bash- Enable the arm:
ros2 service call /rebotarm/enable std_srvs/srv/Trigger- Move the TCP to a target pose:
ros2 action send_goal /rebotarm/move_to_pose rebotarm_msgs/action/MoveToPose \
"{target_pose: {position: {x: 0.30, y: 0.0, z: 0.30}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}}, duration: 2.0}"move_to_pose executes through the SDK end-pose controller. The arm control
mode is selected by rebotarm_hardware.yaml: DM defaults to posvel, RS
defaults to mit.
- Close the gripper and return to safe home:
ros2 service call /rebotarm/safe_home std_srvs/srv/Trigger- Disable the arm:
ros2 service call /rebotarm/disable std_srvs/srv/TriggerAll examples assume reBotArmController is already running:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_bringup bringup.launch.py channel:=/dev/ttyACM0Examples are installed as ROS2 executables and can be launched with ros2 run.
Source files:
src/rebotarmcontroller/rebotarmcontroller/examples/move_to.py
src/rebotarmcontroller/rebotarmcontroller/examples/move_to_pose.py
src/rebotarmcontroller/rebotarmcontroller/examples/gravity_compensation.py
src/rebotarmcontroller/rebotarmcontroller/examples/gripper_control.py
Move all 6 joints to absolute joint angles in radians:
ros2 run rebotarmcontroller MoveTo -- \
0.20 -0.20 -0.20 -0.20 0.10 -0.10 \
--duration 8.0Move a single joint:
ros2 run rebotarmcontroller MoveTo -- --joint joint3 --position -0.20 --duration 5.0Move the TCP to a pose:
ros2 run rebotarmcontroller MoveToPose -- --x 0.30 --y 0.0 --z 0.30 --qw 1.0 --duration 2.0ros2 run rebotarmcontroller GravityCompensationThe script calls /rebotarm/enable, starts gravity compensation, then on
Ctrl+C calls /rebotarm/gravity_compensation/stop, /rebotarm/safe_home and
/rebotarm/disable.
ros2 run rebotarmcontroller GripperControlInteractive commands:
o / open open gripper
c / close close gripper
q / quit quit
The full ROS2 API is documented in API_zh.md.
It includes:
- Topics, services and actions with their message types
/rebotarmnamespace, QoS, units and state machine conventions- Custom interfaces such as
JointMitCmd,JointPosVelCmd,ArmStatusandMoveToPose - Examples for TCP motion, gripper control, gravity compensation and raw commands
- Integration notes for higher-level applications and multi-arm setups
rebotarm_bringup/config/ provides default driver configuration:
| File | Description |
|---|---|
rebotarm_hardware.yaml |
ROS2 hardware selection and overrides for DM / RS SDK configs |
driver_params.yaml |
ROS parameter example |
Common launch parameters:
| Parameter | Default | Description |
|---|---|---|
hardware_config |
built-in rebotarm_hardware.yaml |
ROS2 hardware config path |
model |
empty string | Use default_model when empty; set dm or rs explicitly |
channel |
empty string | Use YAML value when empty; override communication channel when set |
joint_state_rate |
100.0 |
Publish rate for /rebotarm/joint_states |
cmd_arbitration |
reject |
Low-level command arbitration during arm trajectory execution |
arm_namespace |
rebotarm |
ROS namespace prefix |
frame_id |
base_link |
Base frame ID reserved for TF, perception and planning |
ee_frame_id |
end_link |
End-effector frame ID reserved for TF, perception and planning |
use_rviz |
false |
Start bringup RViz |
disable_after_safe_home |
true |
Controls whether motors are disabled after safe home completes |
Model defaults in rebotarm_hardware.yaml:
| Model | Default channel | Arm mode | Gripper limits |
|---|---|---|---|
dm |
/dev/ttyACM0 |
posvel |
open -5.0, close 0.0 |
rs |
can0 |
mit |
open 5.0, close 0.0 |
MoveIt 2 is the motion planning framework used here for inverse kinematics, collision checking, trajectory planning and execution. The demos are separated into their own package so application flows stay isolated from the base driver. For more details, see the official MoveIt 2 Documentation.
MoveIt-related content is split into two packages:
| Package | Purpose |
|---|---|
rebotarm_moveit_config |
Robot model, SRDF, kinematics, joint limits, controller and RViz config |
rebotarm_moveit_demos |
Application demos based on MoveIt 2 |
The MoveIt environment uses simulated hardware through ros2_control and
move_group for planning and execution. It is intended for validating the
model, IK, trajectory planning and demo flow in RViz.
This repository also supports real hardware. Before connecting real hardware, make sure the arm zero configuration, joint directions, joint limits, velocity limits and gripper range are all correct, or keep the default repository configuration.
Make sure the ROS2 environment is available first. You can install packages for
the currently sourced ROS distribution through ROS_DISTRO:
sudo apt update
sudo apt install -y \
ros-${ROS_DISTRO}-moveit \
ros-${ROS_DISTRO}-moveit-configs-utils \
ros-${ROS_DISTRO}-moveit-kinematics \
ros-${ROS_DISTRO}-moveit-planners-ompl \
ros-${ROS_DISTRO}-moveit-simple-controller-manager \
ros-${ROS_DISTRO}-ros2-control \
ros-${ROS_DISTRO}-ros2-controllers \
ros-${ROS_DISTRO}-xacroThe MoveIt config and demos are included in this workspace. After installing dependencies, rebuild the workspace:
cd your/path/to/rebotarm_ros2
colcon build --symlink-install
source install/setup.bashVerify the MoveIt packages and demo entry points:
ros2 pkg list | grep rebotarm_moveit
ros2 pkg executables rebotarm_moveit_demosExpected entries include:
rebotarm_moveit_demos draw_square
rebotarm_moveit_demos pick_place
MoveIt planning can be used through the RViz GUI or through ROS nodes, in both simulation and real scenes.
MoveIt uses the ros2_control virtual hardware interface for RViz simulation:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_moveit_config demo.launch.pyFor the RS arm, pass model:=rs when the default model has not been changed:
ros2 launch rebotarm_moveit_config demo.launch.py model:=rsBy default this starts:
move_grouprobot_state_publisherros2_control_nodejoint_state_broadcasterrebotarm_controllergripper_controller- RViz with the MoveIt MotionPlanning plugin
RViz opens automatically and loads the robot URDF model. You can control motion through the panel on the left side of the GUI.
For the real robot, first start the controller with the hardware interface instead of the virtual controller, then start the hardware MoveIt environment:
ros2 launch rebotarm_bringup driver.launch.pyIn another terminal:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_moveit_config hardware.launch.pyTo repeat: before running any demo on real hardware, make sure the workspace is clear of people and obstacles, verify the planned path in RViz, and be ready to stop the controller at any time.
Start the MoveIt environment first, then run in another terminal:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_moveit_demos draw_square.launch.pydraw_square moves gripper_tcp through the four corners of a coplanar rectangle.
Default parameters:
src/rebotarm_moveit_demos/config/draw_square.yaml
src/rebotarm_moveit_demos/config/draw_square_rs.yaml
Common parameters:
| Parameter | Description |
|---|---|
start_point |
Joint reset position before the demo starts |
rectangle_center |
Rectangle center in base_link |
rectangle_width / rectangle_height |
Rectangle dimensions in meters |
tcp_rpy |
TCP orientation, defaulting to a downward-facing gripper |
tcp_yaw_offsets |
Alternative IK yaw values used to avoid large joint6 wraps |
Start the MoveIt environment first, then run in another terminal:
cd your/path/to/rebotarm_ros2
source install/setup.bash
ros2 launch rebotarm_moveit_demos pick_place.launch.pyDefault parameters:
src/rebotarm_moveit_demos/config/pick_place.yaml
src/rebotarm_moveit_demos/config/pick_place_rs.yaml
Common parameters:
| Parameter | Description |
|---|---|
ready_point |
Ready joint position used before and after pick/place |
pick_position |
Object bottom-center position in base_link |
pick_tcp_rpy / place_tcp_rpy |
TCP orientation for pick and place |
object_dimensions |
Planning-scene object dimensions in meters |
max_gripper_width |
Maximum total gripper opening, default 0.09m |
open_gripper_position / grasp_gripper_position / closed_gripper_position |
Simulated single-side gripper joint positions |
hardware_open_gripper_position / hardware_closed_gripper_position |
Hardware gripper motor open/close positions |
| File | Description |
|---|---|
rebotarm_moveit_config/config/rebotarm.urdf.xacro |
Robot model used by MoveIt |
rebotarm_moveit_config/config/rebotarm.srdf |
MoveIt groups, end effector and default states |
rebotarm_moveit_config/config/rebotarm_rs.urdf.xacro |
RS robot model used by MoveIt |
rebotarm_moveit_config/config/rebotarm_rs.srdf |
RS MoveIt groups and collision semantics |
rebotarm_moveit_config/config/kinematics.yaml |
IK solver configuration |
rebotarm_moveit_config/config/joint_limits.yaml |
Joint limits used by MoveIt planning |
rebotarm_moveit_config/config/moveit_controllers.yaml |
Shared DM/RS MoveIt trajectory execution controller config |
rebotarm_moveit_config/config/ros2_controllers.yaml |
Shared DM/RS ros2_control controller config |
rebotarm_moveit_config/config/initial_positions.yaml |
Initial joint positions for simulated hardware |
rebotarm_moveit_demos/config/draw_square.yaml |
Draw-square demo parameters |
rebotarm_moveit_demos/config/draw_square_rs.yaml |
RS draw-square demo parameters |
rebotarm_moveit_demos/config/pick_place.yaml |
Pick-place demo parameters |
rebotarm_moveit_demos/config/pick_place_rs.yaml |
RS pick-place demo parameters |
The ROS2 environment is not available in the current shell, or ROS2 is not installed. Install ROS2 first, then source the matching distribution once per terminal session:
source /opt/ros/humble/setup.bashIf you use Jazzy, replace humble with jazzy.
To load ROS2 automatically in new terminals, add the source command to
~/.bashrc:
echo "source /opt/ros/humble/setup.bash" >> ~/.bashrcIf ros2 run or ros2 launch cannot find a package or executable, the
workspace overlay is usually not sourced in the current terminal. Rebuild if
needed, then source the workspace:
cd your/path/to/rebotarm_ros2
colcon build --symlink-install
source install/setup.bashYou can verify installed entry points with:
ros2 pkg executables rebotarmcontroller
ros2 pkg executables rebotarm_moveit_demosIf startup reports:
open serial port /dev/ttyACM0 failed: No such file or directory
Check the actual device:
ls /dev/ttyACM*Then override channel:
ros2 launch rebotarm_bringup bringup.launch.py channel:=/dev/ttyACM1For RS, check that the SocketCAN interface is up:
ip -details link show can0
sudo ip link set can0 up type can bitrate 1000000
ros2 launch rebotarm_bringup bringup.launch.py model:=rs channel:=can0If the serial device exists but cannot be opened:
sudo usermod -a -G dialout $USERLog out and log back in for the group change to take effect.
Check that URDF mesh paths use:
package://rebotarm_bringup/description/...
If the terminal shows:
[RTPS_TRANSPORT_SHM Error] Failed init_port fastrtps_port7002: open_and_lock_file failed
This is usually caused by stale FastDDS shared-memory lock files after ROS2 processes exited unexpectedly. If services and actions still respond, it usually does not affect control. To clean it up, stop ROS2 processes first, then run:
pkill -f ros2
pkill -f reBotArmController
rm -f /dev/shm/fastrtps_port*To temporarily avoid shared-memory transport before launching ROS2:
export FASTDDS_BUILTIN_TRANSPORTS=UDPv4