Skip to content

missing

📘 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

ComponentRequire 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.

    bash
    bash scripts/install/ros.bash
  • Source ROS Humble

    bash
    source /opt/ros/humble/setup.bash
  • Initialize and update ros dependencies.

    bash
    sudo rosdep init && rosdep update

📦 Installation

  • Go-to the ros2 directory and install ros dependencies

    bash
    cd ros2
    rosdep install --from-paths src -y --ignore-src
  • Build rbq_ros2 packages

    bash
    colcon build --symlink-install

▶️ Run nodes

  • Run rbq_driver

    • For a simulation environment, append argument: -s.
    bash
    source 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
  • Run rbq_description

    bash
    source ros2/install/local_setup.bash
    ros2 launch rbq_description description.launch.py

🧪 Test List Active Topics

bash
source ros2/install/local_setup.bash
ros2 topic list

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.


missing

Available Gait States :

State IDNameDescription
-2Fall ModeTriggered upon unexpected loss of balance
-1Control OffAll actuators disabled
0SittingLow posture, resting on the ground
1StandingNeutral posture, ready to walk
2Walk Modewalking Trot gait
3Aim ModeAiming posture for targeting
4Stairs ModeStair-adaptive gait using camera sensor
5Wave Modewalking Walk gait
6Run ModeHigh-speed gait (if supported)
30RL TrotReinforcement Learning Trot gait
31RL Front WalkReinforcement Learning Front Walk gait
33RL Left WalkReinforcement Learning Left Walk gait
34RL Right WalkReinforcement Learning Right Walk gait
35RL BoundReinforcement Learning Bound gait
36RL PaceReinforcement Learning Pace gait
37RL PronkReinforcement Learning Pronk gait
38-41RL 3LegReinforcement Learning 3-Leg gaits (HR, HL, FR, FL)
42RL Trot VisionReinforcement Learning Trot with Vision
45RL Trot RunReinforcement Learning Trot Run gait
46RL SilentReinforcement Learning Silent gait

The Available Commands in the second column show which commands can be used in each gait state. In contrast, Common Commands and Power Control are always available regardless of the gait state.

Note: All gait transitions use the unified rbq/motion/switchGait topic with specific gait_id values.
Check Gait State table above for available gait_id values at "Available Gait States"

Gait StateAvailable CommandsCommon CommandsPower Control
Control Offrbq/motion/autoStartrbq/powerControl/setPortState

# PDU Port ID
int8 PDU_PORT_48V_LEG = 0x00
int8 PDU_PORT_48V_ADD = 0x01
int8 PDU_PORT_48V_EXT = 0x02
int8 PDU_PORT_12V_VisionPC = 0x10
int8 PDU_PORT_12V_COMM = 0x11
int8 PDU_PORT_12V_Lidar = 0x12
int8 PDU_PORT_12V_CCTV = 0x13
int8 PDU_PORT_12V_THER = 0x14
int8 PDU_PORT_12V_IRLed = 0x15
int8 PDU_PORT_12V_Speaker = 0x16
int8 PDU_PORT_5V_CAMERAS = 0x20
int8 PDU_PORT_5V_AUDIO_SIDE_CAM_USBHUB = 0x21
Sitting Moderbq/motion/canCheck
rbq/motion/switchGait
(gait_id: 0-46)

rbq/motion/cmd_highLevel

rbq/motion/emergency

rbq/motion/staticLock
rbq/motion/staticReady
rbq/motion/staticGround

rbq/gamepad/switchControlMode
(true:HighLevel Mode,
false:JoyStick Mode)
Standing Mode rbq/motion/cmd_navigateTo
rbq/stateEstimation/comEstimationCompensation
Walk Mode -
Stairs Mode -
Run Mode -
Wave Moderbq/motion/cmd_navigateTo
RL Mode -
Fall Moderbq/motion/recoveryFlex
rbq/motion/switchGait (gait_id: 1)

📡 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.

TopicsData StructureDescription
rbq/status/robot_statusstd_msgs/Header header
bool con_start
bool ready_pos
bool ground_pos
bool force_con
bool ext_joy
bool is_standing
bool can_check
bool find_home
int8 gait_id
bool is_fall
int8 docking_state
bool imu_success
This message contains robot status information and is published at 50Hz. Contains motor control status, position states, communication status, gait information, and docking state.
Check Gait State table above for available gait_id values at "Available Gait States"

# Docking States
int8 DOCKING_MAX_FAIL_CNT_REACHED = -6
int8 DOCKING_MARKER_POS_INVALID_ROTATION = -5
int8 DOCKING_MARKER_POS_INVALID_TOO_FAR = -4
int8 DOCKING_MARKER_POS_INVALID_WRONG_DIR = -3
int8 DOCKING_MARKER_NOT_FOUND = -2
int8 DOCKING_FAILED = -1
int8 DOCKING_OPERATION_MODE = 0
int8 DOCKING_APPROACH_OFFSET = 1
int8 DOCKING_APPROACH = 2
int8 DOCKING_APPROACH_WIDE = 3
int8 DOCKING_SIT_DOWN = 4
int8 DOCKING_SUCCESS = 5
int8 DOCKING_SUCCESS_CHARGING = 6
int8 DOCKING_SUCCESS_NO_CHARGING = 7
rbq/powerControl/battery_statusstd_msgs/Header header
string identifier
float64 charge_percentage
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
rbq/stateEstimation/footStatesstd_msgs/Header header
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.

All arrays contain 4 elements (one for each leg).

# Contact
uint8 CONTACT_UNKNOWN = 0
uint8 CONTACT_MADE = 1
uint8 CONTACT_LOST = 2

# Leg number
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)
rbq/joint/joint_statusstd_msgs/Header header
bool[] connected
int8[] temperature
int8[] motor_temp
bool[] status_fet
bool[] status_run
bool[] status_init
bool[] status_mod
bool[] status_non_ctr
bool[] status_bat
bool[] status_calib
bool[] status_mt_err
bool[] status_jam
bool[] status_cur
bool[] status_big
bool[] status_inp
bool[] status_flt
bool[] status_tmp
bool[] status_ps1
bool[] status_ps2
bool[] status_rsvd
float32[] position_ref
float32[] position_enc
float32[] velocity
float32[] torque_ref
float32[] current
float32[] kp
float32[] kd
int32[] owner
This message contains detailed joint information including connection status, temperature, motor status flags, and control data. Published at 50Hz for each joint.

The msg about state is defined as :

  • RobotStatus
bash
# DOCKING_STATE
int8 DOCKING_MAX_FAIL_CNT_REACHED = -6           # (ABORT SEQENCE) MAX Docking retry count rechead (10 times)
int8 DOCKING_MARKER_POS_INVALID_ROTATION  = -5   # (ABORT SEQENCE) Marker rotation angle is more than +-40 degree
int8 DOCKING_MARKER_POS_INVALID_TOO_FAR   = -4   # (ABORT SEQENCE) Marker is too far more than 5m
int8 DOCKING_MARKER_POS_INVALID_WRONG_DIR = -3   # (ABORT SEQENCE) Marker is detected on front side of robot
int8 DOCKING_MARKER_NOT_FOUND = -2               # (ABORT SEQENCE) Marker not found
int8 DOCKING_FAILED           = -1               # docking failed --> Auto retry
int8 DOCKING_OPERATION_MODE   = 0                # robot is on normal operation
int8 DOCKING_APPROACH_OFFSET  = 1                # 1st reach to charger by offset
int8 DOCKING_APPROACH         = 2                # 2nd reach to charger
int8 DOCKING_APPROACH_WIDE    = 3                # 3rd reach to charger with wide stance
int8 DOCKING_SIT_DOWN         = 4                # sitting down to charger
int8 DOCKING_SUCCESS          = 5                # docking success : charger connected
int8 DOCKING_SUCCESS_CHARGING = 6                # docking success : charging
int8 DOCKING_SUCCESS_NO_CHARGING = 7             # docking success : no_charging

# gait_state constants
int8 STATE_FALL                = -2    # Fall Mode - Triggered upon unexpected loss of balance
int8 STATE_OFF                 = -1    # Control Off - All actuators disabled
int8 STATE_SIT                 = 0     # Sitting - Low posture, resting on the ground
int8 STATE_STAND               = 1     # Standing - Neutral posture, ready to walk
int8 STATE_WALK                = 2     # Walk Mode - walking Trot gait
int8 STATE_AIM                 = 3     # Aim Mode - Aiming posture for targeting
int8 STATE_STAIRS              = 4     # Stairs Mode - Stair-adaptive gait using camera sensor
int8 STATE_WAVE                = 5     # Wave Mode - walking Walk gait
int8 STATE_RUN                 = 6     # Run Mode - High-speed gait (if supported)
int8 STATE_RL_TROT             = 30    # RL Trot - Reinforcement Learning Trot gait
int8 STATE_RL_FRONT_WALK       = 31    # RL Front Walk - Reinforcement Learning Front Walk gait
int8 STATE_RL_LEFT_WALK        = 33    # RL Left Walk - Reinforcement Learning Left Walk gait
int8 STATE_RL_RIGHT_WALK       = 34    # RL Right Walk - Reinforcement Learning Right Walk gait
int8 STATE_RL_BOUND            = 35    # RL Bound - Reinforcement Learning Bound gait
int8 STATE_RL_PACE             = 36    # RL Pace - Reinforcement Learning Pace gait
int8 STATE_RL_PRONK            = 37    # RL Pronk - Reinforcement Learning Pronk gait
int8 STATE_RL_3LEG_HR          = 38    # RL 3Leg HR - Reinforcement Learning 3-Leg gait (Hind Right)
int8 STATE_RL_3LEG_HL          = 39    # RL 3Leg HL - Reinforcement Learning 3-Leg gait (Hind Left)
int8 STATE_RL_3LEG_FR          = 40    # RL 3Leg FR - Reinforcement Learning 3-Leg gait (Front Right)
int8 STATE_RL_3LEG_FL          = 41    # RL 3Leg FL - Reinforcement Learning 3-Leg gait (Front Left)
int8 STATE_RL_TROT_VISION      = 42    # RL Trot Vision - Reinforcement Learning Trot with Vision
int8 STATE_RL_TROT_RUN         = 45    # RL Trot Run - Reinforcement Learning Trot Run gait
int8 STATE_RL_SILENT           = 46    # RL Silent - Reinforcement Learning Silent gait

std_msgs/Header header
bool con_start          # Motor control enabled (1 = enabled, 0 = not enabled)
bool ready_pos          # Robot is in ready position (1 = ready, 0 = not ready)
bool ground_pos         # Robot is in ground/sitting position (1 = sitting, 0 = not sitting)
bool force_con          # Force control mode enabled (1 = enabled, 0 = disabled)
bool ext_joy            # External joystick connected (1 = connected, 0 = not connected)
bool is_standing        # Robot is standing (1 = standing, 0 = not standing)
bool can_check          # CAN communication check (1 = success, 0 = failure)
bool find_home          # Encoder homing status (1 = success, 0 = failure)
int8 gait_id            # Current gait mode identifier (returns value defined GAIT_STATE enum)
bool is_fall            # Fall detection status (1 = robot has fallen, 0 = normal)
int8 docking_state      # Docking process status (returns value defined in DOCKING_STATE enum)
bool imu_success        # IMU connection status (1 = success, 0 = failure)
  • JointStatus
bash
std_msgs/Header header

# Joint Detail Information
# Connection and Temperature Status
bool[] connected          # Joint connection status (true = connected, false = disconnected)
int8[] temperature        # Board temperature in Celsius
int8[] motor_temp         # Motor temperature in Celsius

# Motor Status Flags
bool[] status_fet         # FET (Field Effect Transistor) status (true = ON, false = OFF)
bool[] status_run         # Motor running status (true = running, false = stopped)
bool[] status_init        # Initialization status (true = initialized, false = not initialized)
bool[] status_mod         # Control mode status (true = position control, false = torque control)
bool[] status_non_ctr     # Nonius count error (true = error, false = normal)
bool[] status_bat         # Battery status (true = low battery, false = normal)
bool[] status_calib       # Calibration status (true = in calibration mode, false = normal)
bool[] status_mt_err      # Motor error status (true = error, false = normal)
bool[] status_jam         # JAM error status (true = jammed, false = normal)
bool[] status_cur         # Over current error (true = over current, false = normal)
bool[] status_big         # Big position error (true = large error, false = normal)
bool[] status_inp         # Input error (true = input error, false = normal)
bool[] status_flt         # FET driver fault error (true = fault, false = normal)
bool[] status_tmp         # Temperature error (true = over temperature, false = normal)
bool[] status_ps1         # Position limit error - lower bound (true = limit reached, false = normal)
bool[] status_ps2         # Position limit error - upper bound (true = limit reached, false = normal)
bool[] status_rsvd        # Reserved status bit

# Control Data
float32[] position_ref    # Reference position in radians
float32[] position_enc    # Encoder position in radians
float32[] velocity        # Joint velocity in rad/s
float32[] torque_ref      # Reference torque in Nm
float32[] current         # Motor current in Amperes
float32[] kp              # Proportional gain (P gain)
float32[] kd              # Derivative gain (D gain)
int32[] owner             # Joint owner ID (which controller owns this joint)
  • BatteryState
bash
# 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
  • FootStates
bash
# Contact constants
uint8 CONTACT_UNKNOWN = 0
uint8 CONTACT_MADE = 1
uint8 CONTACT_LOST = 2

std_msgs/Header header

# Arrays for 4 legs (FL, FR, RL, RR)
geometry_msgs/Point[] foot_position_rt_body    # Foot position relative to body frame (4 elements)
geometry_msgs/Point[] foot_velocity_rt_body    # Foot velocity relative to body frame (4 elements)
uint8[] contact                                 # Contact state for each foot (4 elements)

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 ROS2 message types or custom rbq_msgs definitions.

Command topics are defined as :

TopicsDescription
rbq/motion/autoStartInitialize Joint position and start joint control
AutoStart process can be checked by 'RobotStatus' topic
CAN check -> Find Home -> Control Start flags will be on
rbq/motion/emergencyEmergency stop - forcibly cuts power to the robot's leg joints. This action may cause a shock to the robot.
rbq/motion/switchGaitSwitch robot gait mode using gait_id parameter. Check Gait State table above for available gait_id values at "Available Gait States".
rbq/motion/recoveryFlex
rbq/motion/switchGait (gait_id: 1)
The 'recoveryFlex' topic is accepted only when the robot is in Fall mode. It commands the robot to return to sitting mode through specific joint movements.
Alternatively, you can use 'switchGait' topic with gait_id: 1 (Standing) to recover from Fall mode.
rbq/motion/switchControlModeEnable or disable HighLevel Command mode. When set to `true`, HighLevel Command mode is enabled and the robot accepts commands from `rbq/motion/cmd_highLevel` topic. When set to `false`, Joystick control mode is enabled instead.

📍IMPORTANT: To actually move the robot via HighLevelCommand, set rbq/gamepad/switchControlMode to true first.
(true : HighLevel Mode , false : JoyStick Mode)

High-level command topics are defined as :

TopicsData StructureDescription
rbq/motion/cmd_highLevelstd_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
int8 gait_state
bool gait_transition
High-level command topic for robot control based on current gait state.
(Check Gait State table and gait_id values at "Available Gait States")

• Standing Mode: Adjusts robot body posture based on roll, pitch, yaw (ZYX Euler angles) , The parameter body_H specifies the height of the robot's body
Range: Roll: -25~25°, Pitch: -20~20°, Yaw: -25~25°, Delta_body_h: -0.15~0.05m

• 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.2m/s, Vy: -0.4~0.4m/s, Wz: -75~75°/s
Delta_body_h: -0.15~+0.05m, Delta_foot_h: -0.06~+0.04m

• Stairs Mode: Forward, lateral, rotational speeds for stairs navigation
Range: Vx: -0.5~0.5m/s, Vy: -0.2~0.2m/s, Wz: -15~15°/s

• Run Mode: Forward, lateral, rotational speeds for High-speed movement control
Range: Vx: -1.0~1.8m/s, Vy: -0.6~0.6m/s, Wz: -75~75°/s

• Wave Mode: Forward, lateral, rotational speeds for Slow movement control
Range: Vx: -0.3~0.3m/s, Vy: -0.2~0.2m/s, Wz: -20~20°/s

• RL TROT Mode: Reinforcement Learning Trot gait with enhanced speed control
Range: Vx: -1.5~2.0m/s, Vy: -1.0~1.0m/s, Wz: -1.8~1.8rad/s

• RL TROT VISION Mode: Reinforcement Learning Trot with Vision integration
Range: Vx: -1.5~2.0m/s, Vy: -1.0~1.0m/s, Wz: -1.8~1.8rad/s
rbq/motion/cmd_navigateTogeometry_msgs/Pose pose
uint8 mode
Navigation command to move robot to specified position:

# Approach Modes:
0: Rotate to target → straight walk → rotate to target yaw
1: Rotate to target yaw → diagonal walk to target
2: Diagonal walk to target → rotate to target yaw
3: Rotate to target yaw and diagonal walk simultaneously
4: Approach mode 3 with wide leg walking

The msg of High-Level command is defined as :

  • HighLevelCommand
bash
std_msgs/Header header         # ROS message header with timestamp and frame_id
string identifier              # Command identifier for tracking/logging purposes
float64 roll                   # Body roll angle in degrees (ZYX Euler angles)
float64 pitch                  # Body pitch angle in degrees (ZYX Euler angles)  
float64 yaw                    # Body yaw angle in degrees (ZYX Euler angles)
float64 vel_x                  # Linear velocity in X direction (m/s)
float64 vel_y                  # Linear velocity in Y direction (m/s)
float64 omega_z                # Angular velocity around Z axis (rad/s)
float64 delta_body_h           # Body height adjustment from default (m)
float64 delta_foot_h           # Foot height adjustment from default (m)
int8	gait_state             # Target gait state (use constants defined above)
bool	gait_transition        # Enable(true)/disable(false) gait transition during command execution

💡 Example: Standing mode with custom pose (roll: 15°, pitch: 30°, yaw: 20°)

bash
ros2 topic pub --once rbq/motion/cmd_highLevel rbq_msgs/msg/HighLevelCommand \
'{header: {stamp: {sec: 0, nanosec: 0}, frame_id: "base"}, identifier: "standing_pose", roll: 15.0, pitch: 30.0, yaw: 20.0, vel_x: 0.0, vel_y: 0.0, omega_z: 0.0, delta_body_h: 0.0, delta_foot_h: 0.0, gait_state: 1, gait_transition: false}'

Other Topics

📷 4. Vision Topics


  • PTZ Camera Control Topics
TopicDescription
rbq/ptzCamera/setPanTiltZoomPTZ camera control command using Float32MultiArray
[pan, tilt, zoom]

💡 example:

bash
ros2 topic pub --once rbq/ptzCamera/setPanTiltZoom std_msgs/msg/Float32MultiArray "{data: [0.0, 0.0, 1.0]}"

  • Camera Sensor Topics

Camera sensors provide RGB, IR, and depth images from multiple positions around the robot. Images are published in both raw and compressed formats with corresponding camera calibration information.

📍 Hardware Information: For detailed camera specifications, FOV, and transformation matrices, refer to the Visual Sensors Hardware Manual.

CameraImage TypeFormatTopic Name
Bottom (0-3)IRRawrbq/vision/sensor_bottom_0/ir
rbq/vision/sensor_bottom_1/ir
rbq/vision/sensor_bottom_2/ir
rbq/vision/sensor_bottom_3/ir
Compressedrbq/vision/sensor_bottom_0/ir/compressed
rbq/vision/sensor_bottom_1/ir/compressed
rbq/vision/sensor_bottom_2/ir/compressed
rbq/vision/sensor_bottom_3/ir/compressed
Camera Inforbq/vision/sensor_bottom_0/ir/camera_info
rbq/vision/sensor_bottom_1/ir/camera_info
rbq/vision/sensor_bottom_2/ir/camera_info
rbq/vision/sensor_bottom_3/ir/camera_info
DepthRawrbq/vision/sensor_bottom_0/depth
rbq/vision/sensor_bottom_1/depth
rbq/vision/sensor_bottom_2/depth
rbq/vision/sensor_bottom_3/depth
Compressedrbq/vision/sensor_bottom_0/depth/compressed
rbq/vision/sensor_bottom_1/depth/compressed
rbq/vision/sensor_bottom_2/depth/compressed
rbq/vision/sensor_bottom_3/depth/compressed
Camera Inforbq/vision/sensor_bottom_0/depth/camera_info
rbq/vision/sensor_bottom_1/depth/camera_info
rbq/vision/sensor_bottom_2/depth/camera_info
rbq/vision/sensor_bottom_3/depth/camera_info
Front/RearRGBRawrbq/vision/sensor_front/rgb
rbq/vision/sensor_rear/rgb
Compressedrbq/vision/sensor_front/rgb/compressed
rbq/vision/sensor_rear/rgb/compressed
Camera Inforbq/vision/sensor_front/rgb/camera_info
rbq/vision/sensor_rear/rgb/camera_info
IRRawrbq/vision/sensor_front/ir
rbq/vision/sensor_rear/ir
Compressedrbq/vision/sensor_front/ir/compressed
rbq/vision/sensor_rear/ir/compressed
Camera Inforbq/vision/sensor_front/ir/camera_info
rbq/vision/sensor_rear/ir/camera_info
DepthRawrbq/vision/sensor_front/depth
rbq/vision/sensor_rear/depth
Compressedrbq/vision/sensor_front/depth/compressed
rbq/vision/sensor_rear/depth/compressed
Camera Inforbq/vision/sensor_front/depth/camera_info
rbq/vision/sensor_rear/depth/camera_info

🖼️ 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.

Go to your workspace directory first:

bash
cd <your workspace>/RBQ

Then launch RViz:

bash
source ros2/install/local_setup.bash
ros2 launch rbq_description description.launch.py

missing


📘 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

  • Jinwon Seo

This user manual is intended for RBQ users.