
📘 Introduction
Welcome to the RBQ ROS 2 SDK Manual.
- This guide will help you quickly get started with controlling and visualizing the RBQ robot through ROS 2, both in simulation and on real hardware.
What This SDK Provides
This SDK enables the following key features:
- Robot Control: Execute posture commands, gait switching, and position-based navigation.
- Sensor Feedback Streaming: Continuously stream IMU, foot contact, battery state, and more.
- Vision Data Streaming: Provides visual information from front, rear, and downward-facing cameras for perception and navigation.
- RViz2 Visualization: Visualize robot state and sensors like LiDAR in real-time.
💻 System requirements
Component | Require Setting |
---|---|
Operating System | |
ROS 2 Distro | |
Python Version |
📝 Below instructions assume that the CLI terminal commands are all input in the main directory.
🛠️ Configuration
This package is tested for
Ubuntu 22.04 and ROS 2 Humble
, which can be installed following command.bashbash scripts/install/ros.bash
Source
ROS Humble
bashsource /opt/ros/humble/setup.bash
Initialize and
update ros dependencies
.bashsudo rosdep init && rosdep update
📦 Installation
Go-to the
ros2
directory andinstall ros dependencies
bashcd ros2 rosdep install --from-paths src -y --ignore-src
Build rbq_ros2
packagesbashcolcon build --symlink-install
▶️ Run nodes
Run
rbq_driver
- For a simulation environment, append argument:
-s
.
bashsource ros2/install/local_setup.bash ros2 run rbq_driver rbq_driver
The RBQ driver contains all of the necessary topics for controlling RBQ over ROS 2
rbq_driver process starts the following nodes:
- Robot state publisher
- Sensor feedback publishers (IMU, battery, foot contact)
- Vision data publishers (camera streams from front, rear, and bottom sensors)
- High-level command subscriber
- For a simulation environment, append argument:
Run
rbq_description
bashsource ros2/install/local_setup.bash ros2 launch rbq_description description.launch.py
🧪 Test List Active Topics
source ros2/install/local_setup.bash
ros2 topic list
Examples
- coming soon
State acquisition
🦿 1. Gait State Topics
Gait state refers to the robot's current motion or posture mode.
Transitions between these states are triggered by incoming high-level commands, sensor conditions, or internal logic.

Available Gait States :
State ID | Name | Description |
---|---|---|
-2 | Fall Mode | Triggered upon unexpected loss of balance |
-1 | Control Off | All actuators disabled |
0 | Sitting | Low posture, resting on the ground |
1 | Standing | Neutral posture, ready to walk |
2 | Walk Mode | walking Trot gait |
4 | Stairs Mode | Stair-adaptive gait using camera sensor |
5 | Wave Mode | walking Walk gait |
6 | Run Mode | High-speed gait (if supported) |
The Command topics in the second column are only available when the robot is in the corresponding Gait State. In contrast, Common Command topics and Power Control topics are always available regardless of the gait state.
Gait State | Command topics | Common Command topics | Power control topics |
---|---|---|---|
Control Off | rbq/autoStart | rbq/cmd_highLevel rbq/emergency rbq/staticLock rbq/staticReady rbq/staticGround rbq/switchGamepadPort | rbq/powerLeg rbq/powerVisionPC rbq/powerUsbHub rbq/powerLidar rbq/powerExt52v |
Sitting Mode | rbq/stand rbq/calibrateImu | ||
Standing Mode | rbq/sit rbq/stairs rbq/walk rbq/wave rbq/run rbq/cmd_navigateTo rbq/comEstimationCompensation | ||
Walk Mode (when robot stand by) | rbq/sit rbq/stairs rbq/walk rbq/wave rbq/run | ||
Stairs Mode (when robot stand by) | rbq/stand rbq/walk | ||
Run Mode | rbq/stand rbq/walk | ||
Wave Mode (when robot stand by) | rbq/stand rbq/walk rbq/cmd_navigateTo | ||
Fall Mode | rbq/RecoveryFlex |
📡 2. Low-level State Topics
These topics provide real-time feedback about the robot's internal state, such as posture, sensor readings, and system status.
Topics | Data Structure | Description |
---|---|---|
RobotState | int8 gait_state bool joints_comm_checked bool joints_calibrated bool joints_control_started bool comm_connected sensor_msgs/Imu imu_state sensor_msgs/JointState joint_states rbq_msgs/BatteryState battery_state rbq_msgs/FootState[] foot_states geometry_msgs/VelocityStamped body_velocity_rt_world geometry_msgs/PoseStamped body_pose_rt_world | This message contains robot state information and is published at 50Hz. The ‘BatteryState’ and ‘FootState’ messages are defined for the RBQ10. Other messages are defined by standard ROS message types # GaitState int8 STATE_FALL = -2 int8 STATE_OFF = -1 int8 STATE_SIT = 0 int8 STATE_STAND = 1 int8 STATE_WALK = 2 int8 STATE_AIM = 3 int8 STATE_STAIRS = 4 int8 STATE_WAVE = 5 int8 STATE_RUN = 6 |
BatteryState | string identifier float64 charge_percentage builtin_interfaces/Duration estimated_runtime float64 current float64 voltage float64[] temperatures uint8 status | # Status uint8 STATUS_UNKNOWN = 0 uint8 STATUS_MISSING = 1 uint8 STATUS_CHARGING = 2 uint8 STATUS_DISCHARGING = 3 uint8 STATUS_BOOTING = 4 |
FootState | geometry_msgs/Point foot_position_rt_body geometry_msgs/Point foot_velocity_rt_body uint8 contact | Foot position/velocity with respect to the local body frame. The origin of the body frame is at the center of the robot body, with the front direction as +x, the left direction as +y, and the upward direction as +z. # Contact uint8 CONTACT_UNKNOWN = 0 uint8 CONTACT_MADE = 1 uint8 CONTACT_LOST = 2 Leg num 0 : Right-Hind leg (RH) Leg num 1 : Left-Hind Leg (LH) Leg num 2 : Right-Front Leg (RF) Leg num 3 : Left-Front Leg (LF) |
The msg about state is defined as :
- RobotState
# GaitState
int8 STATE_FALL = -2
int8 STATE_OFF = -1
int8 STATE_SIT = 0
int8 STATE_STAND = 1
int8 STATE_WALK = 2
int8 STATE_AIM = 3
int8 STATE_STAIRS = 4
int8 STATE_WAVE = 5
int8 STATE_RUN = 6
std_msgs/Header header
int8 gait_state
bool joints_comm_checked
bool joints_calibrated
bool joints_control_started
bool comm_connected
sensor_msgs/Imu imu_state
sensor_msgs/JointState joint_states
rbq_msgs/BatteryState battery_state
rbq_msgs/FootState[] foot_states
geometry_msgs/VelocityStamped body_velocity_rt_world
geometry_msgs/PoseStamped body_pose_rt_world
- BatteryState
# Status
uint8 STATUS_UNKNOWN = 0
uint8 STATUS_MISSING = 1
uint8 STATUS_CHARGING = 2
uint8 STATUS_DISCHARGING = 3
uint8 STATUS_BOOTING = 4
std_msgs/Header header
string identifier
float64 charge_percentage
float64 current
float64 voltage
float64[] temperatures
uint8 status
- FootState
# Contact
uint8 CONTACT_UNKNOWN = 0
uint8 CONTACT_MADE = 1
uint8 CONTACT_LOST = 2
geometry_msgs/Point foot_position_rt_body
geometry_msgs/Point foot_velocity_rt_body
uint8 contact
- FootStates
std_msgs/Header header
rbq_msgs/FootState[] foot_states
Robot control
🎮 3. Command Topics
The following topics are used to send high-level and navigation commands to the RBQ robot.
All commands follow standard ROS 2 message types or custom rbq_msgs
definitions.
Command topics are defined as :
topics | description |
---|---|
autoStart | Initialize Joint position and start joint control AutoStart process can be checked by ‘InitState’ topic CAN check -> Find Home -> Control Start flags will be on |
DampingMode | the robot to lower itself by applying damping to its leg joints |
EmergencyOff | forcibly cuts power to the robot's leg joints. This action may cause a shock to the robot. |
Fall_Recovery | The ‘Fall_Recovery topi’c is accepted only when the robot is in Fall mode. It commands the robot to return to sitting mode through specific joint movements. |
rbq/cmd_highLevel { float64 roll float64 pitch float64 yaw float64 vel_x float64 vel_y float64 omega_z float64 delta_body_h float64 delta_foot_h } | The HighLevelCMD topic enables high-level commands to be given to the robot depending on its current gait state • Standing Mode adjusts the robot's body posture in the Standing Mode based on roll, pitch, and yaw (according to ZYX Euler angles). The parameter body_H specifies the height of the robot's body - Range Roll : -25 ~ 25 deg Pitch : -20 ~ 20deg Yaw : -25 ~ 25deg Delta_body_height : -0.15 ~ 0.05 m |
topics | description |
---|---|
rbq/cmd_highLevel { float64 roll float64 pitch float64 yaw float64 vel_x float64 vel_y float64 omega_z float64 delta_body_h float64 foot_h } | • Walk Mode Set movement speed of the robot in the local coordinate system while in the trotting gait state. Vx, Vy represents the forward speed, lateral speed and Wz represents rotational speed. During trotting, delta_body_H is used to set the height of the body from its default body height, foot_H is used to set the foot lifting height, and pitch is used to set the pitch angle of the body.“ Range Vx : - 1.0 ~ 1.2 m/s Vy : - 0.4 ~ 0.4 m/s Wz: -75 ~ 75 des/s Delta_Body_H : -0.15 ~ +0.05 m (default : 0.45) pitch: -15 ~ 15 deg Delta_foot_H : -0.06 ~ + 0.04 m (default : 0.14) • Stairs Mode specifies the robot's forward, lateral, and rotational speeds in the local frame while in stairs mode Range Vx : -0.5 ~ 0.5 m/s Vy : - 0.2 ~ 0.2 m/s Wz: -15 ~ 15 deg/s |
topics | description |
---|---|
rbq/cmd_highLevel { float64 roll float64 pitch float64 yaw float64 vel_x float64 vel_y float64 omega_z float64 delta_body_h float64 delta_foot_h } | • Run Mode specifies the robot's forward, lateral, and rotational speeds in the local frame while in Running mode Range Vx : - 1m/s ~ 1.8 m/s Vy : - 0.6 m/s ~ 0.6 m/s Wz: - 75 deg/s ~ 75 deg/s • Wave Mode specifies the robot's forward, lateral, and rotational speeds in the local frame while in Wave mode Range Vx : - 0.3 m/s ~ 0.3 m/s Vy : - 0.2 m/s ~ 0.2 m/s Wz: -20deg/s ~ 20deg/s |
rbq/cmd_navigateTo { Geometry_msgs::Pose uint8 mode } | This command moves the robot to the position defined by ‘Pose’ type in the current robot local frame, according to the selected ‘approach_mode’. Approach Mode 0 : Rotate to target point -> straight walk -> rotate to target yaw 1 : rotate to target yaw -> diagonal walk to target point 2 : diagonal walk to target point -> rotate to target yaw 3 : rotate to target yaw and diagonal walk to target point simultaneously 4 : Approach mode 3 with wide leg walking |
The msg of High-Level command is defined as :
- HighLevelCommand
std_msgs/Header header
string identifier
float64 roll
float64 pitch
float64 yaw
float64 vel_x
float64 vel_y
float64 omega_z
float64 delta_body_h
float64 delta_foot_h
🖼️ RViz Visualization
Launch RViz2 with GUI
You can simultaneously visualize and send commands to the robot through the GUI on the left side of RViz.
📘 Help
If you encounter problems when using this repository, feel free to open an issue.
🤝 Contributing
Feel free to contribute!
👥 Contributors
This project is provided by the Rainbow-Robotics.
Rainbow-Robotics contributors:
- Gurbann