R1 Lite Software Introduction
Environment Dependencies
- Hardware Dependency: R1 Lite Computing Unit
- Operating System Dependency: Ubuntu 22.04 LTS
- Middleware Dependency: ROS Humble
Software Version Log
Visit Galaxea R1 Lite Software Version Update Log to get the latest SDK package and update information.
First-Time Operation Guide
Visit Galaxea R1 Lite Unboxing and Startup Guide and follow the instructions to operate Galaxea R1 Lite.
Start the SDK
Currently, two startup modes are supported: separate startup and one-click startup.
For your safety, it is recommended to use the separate startup method.
Operation instructions are as follows:
Module Name | Included Components | Path | Launch File |
---|---|---|---|
HDAS | Arms Driver Torso Driver Chassis Driver IMU Driver BMS Driver |
{sdk_path}/install/HDAS/share/HDAS/launch | r1lite.py |
camera_driver | Head Camera Interface | {sdk_path}/install/camera_driver/share/camera_driver/launch | run.py |
realsense2_camera | Wrist Camera Interface | {sdk_path}/install/realsense2_camera/share/realsense2_camera/launch | rs_multi_camera_3.0_launch.py |
mobiman | Arm Control Chassis Control Torso Control Gripper Control End Effector Pose Interface |
{sdk_path}/install/mobiman/share/mobiman/launch | r1_lite_jointTrackerdemo_fast_launch.py r1_lite_chassis_control_w_o_eepose_launch.py torso_control_r1_lite.launch.py r1_gripperController_launch.py r1_lite_eepose_launch.py |
robot_monitor | Robot Monitor Interface | {sdk_path}/install/system_monitor_node/share/system_monitor_node/launch | robot_monitor.py |
data collection | Data Collection | {sdk_path}/install/data_collection/share/data_collection/launch | data_collection_launch.py |
robot diagnosis system | rds_ros | {sdk_path}/install/rds_ros/share/rds_ros/launch | monitor.py |
Separate Startup
All nodes can be launched with the following command template. Configuration method:
Note: Before launching nodes, please ensure the CAN driver is properly configured.
bash ~/can.bash
# You may need to enter the password again: 1
# If the error "RTNETLINK answers: Device or resource busy" occurs, it usually means the device you are trying to configure (such as a network interface or CAN transceiver) has already been configured and is currently running.
Node startup command:
source {sdk_path}/install/setup.bash
ros2 launch <Package Name> <Launch File>
# Example
ros2 launch HDAS r1lite.py
One-Click Startup
Note: Executing the following command will start all drivers and motion control interfaces.
cd {sdk_path}/install/startup_config/share/startup_config/script/
./robot_startup.sh boot ../session.d/ATCStandard/R1LITEBody.d
Software Interfaces
Currently, Galaxea R1 Lite consists of 6 main parts: arm joint control, arm pose control, gripper control, torso velocity control, torso joint control, and chassis control.
The entire software package is abbreviated as “mobiman,” meaning mobile manipulation.
Driver Interfaces
Arm Driver Interface
This interface is a ROS software package for robotic arm control and state feedback. It defines multiple topics for publishing and subscribing to arm state, control commands, and related error codes.
The following describes each topic and its corresponding message type in detail:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/feedback_arm_left | Output | Left Arm Joint Feedback | sensor_msgs::JointState |
/hdas/feedback_arm_right | Output | Right Arm Joint Feedback | sensor_msgs::JointState |
/hdas/feedback_gripper_left | Output | Left Gripper Stroke | sensor_msgs::JointState |
/hdas/feedback_gripper_right | Output | Right Gripper Stroke | sensor_msgs::JointState |
/hdas/feedback_status_arm_left | Output | Left Arm Status Feedback | hdas_msg::feedback_status |
/hdas/feedback_status_arm_right | Output | Right Arm Status Feedback | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_left | Output | Left Gripper Status Feedback | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_right | Output | Right Gripper Status Feedback | hdas_msg::feedback_status |
/motion_control/control_arm_left | Input | Left Arm Motor Control | hdas_msg::motor_control |
/motion_control/control_arm_right | Input | Right Arm Motor Control | hdas_msg::motor_control |
/motion_control/control_gripper_left | Input | Left Gripper Motor Control | hdas_msg::motor_control |
/motion_control/control_gripper_right | Input | Right Gripper Motor Control | hdas_msg::motor_control |
The specific fields of the above topics and their detailed descriptions are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/hdas/feedback_arm_left | header | Standard message header |
position | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
velocity | [Joint 1 velocity, Joint 2 velocity, Joint 3 velocity, Joint 4 velocity, Joint 5 velocity, Joint 6 velocity, Gripper joint velocity] | |
effort | [Joint 1 torque, Joint 2 torque, Joint 3 torque, Joint 4 torque, Joint 5 torque, Joint 6 torque, Gripper joint torque] | |
/hdas/feedback_arm_right | header | Standard message header |
position | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
velocity | [Joint 1 velocity, Joint 2 velocity, Joint 3 velocity, Joint 4 velocity, Joint 5 velocity, Joint 6 velocity, Gripper joint velocity] | |
effort | [Joint 1 torque, Joint 2 torque, Joint 3 torque, Joint 4 torque, Joint 5 torque, Joint 6 torque, Gripper joint torque] | |
/hdas/feedback_gripper_left | header | Standard message header |
position | Gripper stroke (0–100 mm) | |
velocity | Not used | |
effort | Not used | |
/hdas/feedback_gripper_right | header | Standard message header |
position | Gripper stroke (0–100 mm) | |
velocity | Not used | |
effort | Not used | |
/hdas/feedback_status_arm_left | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding error descriptions | |
/hdas/feedback_status_arm_right | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding descriptions | |
/hdas/feedback_status_gripper_left | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding descriptions | |
/hdas/feedback_status_gripper_right | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding descriptions | |
/motion_control/control_arm_left(MIT) | header | Standard message header |
name | - | |
p_des | [Joint1 position, Joint2 position, Joint3 position, Joint4 position, Joint5 position, Joint6 position, Gripper joint position] | |
v_des | [Joint1 velocity, Joint2 velocity, Joint3 velocity, Joint4 velocity, Joint5 velocity, Joint6 velocity, Gripper joint velocity] | |
kp | [Joint1 kp, Joint2 kp, Joint3 kp, Joint4 kp, Joint5 kp, Joint6 kp, Gripper joint kp] | |
kd | [Joint1 kd, Joint2 kd, Joint3 kd, Joint4 kd, Joint5 kd, Joint6 kd, Gripper joint kd] | |
t_ff | [Joint1 torque, Joint2 torque, Joint3 torque, Joint4 torque, Joint5 torque, Joint6 torque, Gripper joint torque] | |
mode | - | |
/motion_control/control_arm_left(PID) | header | Standard message header |
name | - | |
p_des | [Joint1 position, Joint2 position, Joint3 position, Joint4 position, Joint5 position, Joint6 position, Gripper joint position] | |
v_des | - | |
t_ff | - | |
mode | - | |
/motion_control/control_arm_right(MIT) | header | Standard message header |
name | - | |
p_des | [Joint1 position, Joint2 position, Joint3 position, Joint4 position, Joint5 position, Joint6 position, Gripper joint position] | |
v_des | [Joint1 velocity, Joint2 velocity, Joint3 velocity, Joint4 velocity, Joint5 velocity, Joint6 velocity, Gripper joint velocity] | |
kp | [Joint1 kp, Joint2 kp, Joint3 kp, Joint4 kp, Joint5 kp, Joint6 kp, Gripper joint kp] | |
kd | [Joint1 kd, Joint2 kd, Joint3 kd, Joint4 kd, Joint5 kd, Joint6 kd, Gripper joint kd] | |
t_ff | [Joint1 torque, Joint2 torque, Joint3 torque, Joint4 torque, Joint5 torque, Joint6 torque, Gripper joint torque] | |
mode | - | |
/motion_control/control_arm_right(PID) | header | Standard message header |
name | - | |
p_des | [Joint1 position, Joint2 position, Joint3 position, Joint4 position, Joint5 position, Joint6 position, Gripper joint position] | |
v_des | [Joint1 max velocity limit, Joint2 max velocity limit, Joint3 max velocity limit, Joint4 max velocity limit, Joint5 max velocity limit, Joint6 max velocity limit, Gripper joint max velocity limit] | |
t_ff | [Joint1 max torque limit, Joint2 max torque limit, Joint3 max torque limit, Joint4 max torque limit, Joint5 max torque limit, Joint6 max torque limit, Gripper joint max torque limit] | |
mode | - | |
/motion_control/control_gripper_left | header | Standard message header |
name | - | |
p_des | Gripper motor position | |
v_des | Gripper motor velocity | |
kp | Gripper motor kp | |
kd | Gripper motor kd | |
t_ff | Gripper torque | |
mode | - | |
/motion_control/control_gripper_right | header | Standard message header |
name | - | |
p_des | Gripper motor position | |
v_des | Gripper motor velocity | |
kp | Gripper motor kp | |
kd | Gripper motor kd | |
t_ff | Gripper torque | |
mode | - | |
/motion_control/position_control_gripper_left | header | Standard message header |
data | Expected gripper stroke (0-100mm) | |
/motion_control/position_control_gripper_right | header | Standard message header |
data | Expected gripper stroke (0-100mm) |
Robot Arm Joint Motor Control Interface
1. MIT Torque-Position Hybrid Control Mode Architecture
The motor output torque formula calculates the reference torque Tref
for the current loop as follows:
\(K_p(p_d - p_e) + K_d(v_d - v_e)+t_{ff} = T_{ref}\)
Where:
- Kp
, Kd
are the proportional gains for position and velocity.
- p_des
, v_des
are the desired position and velocity.
- t_ff
is the feedforward torque.
- p_e
is the encoder feedback position, v_e
is the motor speed obtained by differentiation.
- Inputs:
Kp
,Kd
,p_des
,v_des
,t_ff
. Feedbackp_e
andv_e
do not need manual input.
Tips:
- Feedforward torque: This is a required value. Position and velocity terms cannot compensate for large torque errors, so feedforward torque should at least compensate for the arm's self-weight.
- Recommended gains: For A1X motors, the recommended kp
and kd
values are:
A1X_kp = [140.0, 200.0, 120.0, 80.0, 80.0, 80.0]
A1X_kd = [10.0, 30.0, 5.0, 10.0, 10.0, 10.0]
2. PID Servo Control Mode Architecture
The servo control mode uses a three-loop PID control (position loop, velocity loop, current loop) with an integral term, reducing steady-state error. To maintain interface consistency, the control data format is the same as MIT mode.
Where:
- p_des
: desired angle (rad)
- v_des
: meaningless
- k_p
, k_d
: meaningless
- t_ff
: meaningless
Torso Control Interface
This interface is used for torso control and status feedback via ROS. It defines multiple topics for publishing and subscribing to torso motor states and commands.
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/feedback_torso | Output | Torso joint feedback | sensor_msgs::JointState |
/hdas/feedback_status_torso | Output | Torso status feedback | hdas_msg::feedback_status |
/motion_control/control_torso | Input | Torso motor control | hdas_msg::motor_control |
Topic Name | Field | Description |
---|---|---|
/hdas/feedback_torso | header | Standard message header |
position | [Joint1 position, Joint2 position, Joint3 position, 0] | |
velocity | [Joint1 velocity, Joint2 velocity, Joint3 velocity, 0] | |
effort | [Joint1 torque, Joint2 torque, Joint3 torque, 0] | |
/hdas/feedback_status_torso | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding descriptions | |
/motion_control/control_torso | header | Standard message header |
name | - | |
p_des | [Joint1 position, Joint2 position, Joint3 position, 0] | |
v_des | [Joint1 max velocity, Joint2 max velocity, Joint3 max velocity, 0] | |
kp | [-, -, -, -] | |
kd | [-, -, -, -] | |
t_ff | [-, -, -, -] | |
mode | - |
Chassis Drive Interface
This interface is used for ROS-based chassis state feedback and defines multiple topics to report the status of chassis motors. The detailed message types for each topic are as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/feedback_chassis | Output | Chassis hub and steering motor feedback | sensor_msgs::JointState |
/hdas/feedback_status_chassis | Output | Chassis status feedback | hdas_msg::feedback_status |
/motion_control/control_chassis | Input | Chassis hub and steering motor control | hdas_msg::motor_control |
The detailed fields of the above topics are as follows:
Topic Name | Field | Description |
---|---|---|
/hdas/feedback_chassis | header | Standard message header |
position | [Front left wheel angle, Front right wheel angle, Rear wheel angle] | |
velocity | [Front left wheel linear velocity, Front right wheel linear velocity, Rear wheel linear velocity] [0.0, 0.0, 0.0] |
|
effort | [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] | |
/hdas/feedback_status_chassis | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding descriptions | |
/motion_control/control_chassis | header | Standard message header |
name | - | |
p_des | [Front left wheel angle, Front right wheel angle, Rear wheel angle] | |
v_des | [Front left wheel linear velocity, Front right wheel linear velocity, Rear wheel linear velocity] | |
kp | - | |
kd | - | |
t_ff | - | |
mode | - |
Camera Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/camera_wrist_left/color/image_raw/compressed | Output | Left wrist camera RGB compressed image | sensor_msgs::CompressedImage |
/hdas/camera_wrist_right/color/image_raw/compressed | Output | Right wrist camera RGB compressed image | sensor_msgs::CompressedImage |
/hdas/camera_head/left_raw/image_raw_color/compressed | Output | Head left camera RGB compressed image | sensor_msgs::CompressedImage |
/hdas/camera_head/right_raw/image_raw_color/compressed | Output | Head right camera RGB compressed image | sensor_msgs::CompressedImage |
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw | Output | Left wrist camera depth image | sensor_msgs::Image |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | Output | Right wrist camera depth image | sensor_msgs::Image |
Camera Topic Fields and Details
Topic Name | Field | Description |
---|---|---|
/hdas/camera_wrist_left/color/image_raw/compressed | header | Standard message header |
format | JPEG | |
data | Image data | |
/hdas/camera_wrist_right/color/image_raw/compressed | header | Standard message header |
format | JPEG | |
data | Image data | |
/hdas/camera_head/left_raw/image_raw_color/compressed | header | Standard message header |
format | JPEG format | |
data | Image data | |
/hdas/camera_head/right_raw/image_raw_color/compressed | header | Standard message header |
format | JPEG format | |
data | Image data | |
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw | header | Standard message header |
height | Depends on configuration | |
width | Depends on configuration | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | Depends on configuration | |
data | Image data | |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | header | Standard message header |
height | Depends on configuration | |
width | Depends on configuration | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | Depends on configuration | |
data | Image data |
IMU Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/imu_chassis | Output | Chassis IMU feedback | sensor_msgs::Imu |
/hdas/imu_torso | Output | Torso IMU feedback | sensor_msgs::Imu |
IMU Fields Detail
Topic Name | Field | Description |
---|---|---|
/hdas/imu_chassis | header | Standard message header |
orientation.x | Quaternion x | |
orientation.y | Quaternion y | |
orientation.z | Quaternion z | |
orientation.w | Quaternion w | |
angular_velocity.x | Gyroscope angular velocity x | |
angular_velocity.y | Gyroscope angular velocity y | |
angular_velocity.z | Gyroscope angular velocity z | |
linear_acceleration.x | Linear acceleration x | |
linear_acceleration.y | Linear acceleration y | |
linear_acceleration.z | Linear acceleration z | |
/hdas/imu_torso | header | Standard message header |
orientation.x | Quaternion x | |
orientation.y | Quaternion y | |
orientation.z | Quaternion z | |
orientation.w | Quaternion w | |
angular_velocity.x | Gyroscope angular velocity x | |
angular_velocity.y | Gyroscope angular velocity y | |
angular_velocity.z | Gyroscope angular velocity z | |
linear_acceleration.x | Linear acceleration x | |
linear_acceleration.y | Linear acceleration y | |
linear_acceleration.z | Linear acceleration z |
BMS Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/bms | Output | Battery BMS message | hdas_msg::bms |
Topic Name | Field | Description |
---|---|---|
/hdas/bms | header | Standard message header |
voltage | Voltage (V) | |
current | Current (A) | |
capital | Remaining capacity (%) |
Controller Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/controller | Output | Controller signal | hdas_msg::controller_signal_stamped |
The detailed fields and descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/controller | header | Standard message header |
data.left_x_axis | Left joystick X-axis | |
data.left_y_axis | Left joystick Y-axis | |
data.right_x_axis | Right joystick X-axis | |
data.right_y_axis | Right joystick Y-axis | |
mode | 2: Controller control (chassis) 5: PC control (chassis) |
Motion Control Interfaces
- Arm Joint Control: This node is responsible for controlling each joint of the arm.
- Arm Pose Control: This node is responsible for controlling the arm to move to the target end-effector (ee) coordinate frame, divided into left and right arm pose control.
- Torso Velocity Control: This node is responsible for controlling the torso to move to the target floating base coordinate frame.
- Chassis Control: This node uses vector control to drive the R1 Lite chassis and can simultaneously send velocity commands in three directions: x, y, and w.
Arm Joint Control
The arm joint control node is responsible for controlling each joint of the arm, with a total of 6 joints.
It can be started using the following commands:
# Before calling the following interfaces, please make sure FDCAN communication and HDAS node have been started (refer to the separate startup section for instructions)
# Choose one of the following two launch files to start, essentially differing in joint velocity limit parameters
ros2 launch mobiman r1_lite_jointTrackerdemo_launch.py # (Normal mode)
ros2 launch mobiman r1_lite_jointTrackerdemo_fast_launch.py # (High-following mode)
Interface information is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_joint_state_arm_left | Input | Target positions of left arm joints | sensor_msgs::JointState |
/motion_target/target_joint_state_arm_right | Input | Target positions of right arm joints | sensor_msgs::JointState |
/hdas/feedback_arm_left | Input | Left arm joint feedback | sensor_msgs::JointState |
/hdas/feedback_arm_right | Input | Right arm joint feedback | sensor_msgs::JointState |
/motion_control/control_arm_left | Output | Left arm motor control | hdas_msg::motor_control |
/motion_control/control_arm_right | Output | Right arm motor control | hdas_msg::motor_control |
The detailed fields and descriptions for the above topics are as follows:
Topic Name | Field | Description |
---|---|---|
/motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
header | Standard message header |
position | A vector containing six elements representing the target positions of each joint. | |
velocity | A vector containing six elements representing the maximum velocity of each joint during motion. | |
/hdas/feedback_arm_left | - | Please refer to the arm driver interface |
/hdas/feedback_arm_right | - | Please refer to the arm driver interface |
/motion_control/control_arm_left | - | Please refer to the arm driver interface |
/motion_control/control_arm_right | - | Please refer to the arm driver interface |
Arm Pose Control
The arm pose control package is an ROS package used to control the arm's movement to a target end-effector (EE) coordinate frame. It primarily consists of two launch files, one for controlling the left arm's pose and the other for controlling the right arm's pose. It can be launched using the following command:
# Before calling the following APIs, please ensure that the FDCAN communication, HDAS node, and robotic arm joint control node are all activated.
# For instructions on how to activate FDCAN communication and the HDAS node, please refer to the separate activation section. For instructions on activating the robotic arm joint control node, please refer to the robotic arm control section.
ros2 launch mobiman r1_lite_left_arm_relaxed_ik_launch.py
#Open a new terminal window
ros2 launch mobiman r1_lite_right_arm_relaxed_ik_launch.py
# Input: Target attitude calculation
/motion_target/target_pose_arm_left
/motion_target/target_pose_arm_right
# Output: The calculated target joint angles
/motion_target/target_joint_state_arm_left
/motion_target/target_joint_state_arm_right
Use the following command to start the arm pose feedback node:
Interface information is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_pose_arm_left | Input | Target pose of the left arm end-effector | Geometry_msgs::PoseStamped |
/motion_target/target_pose_arm_right | Input | Target pose of the right arm end-effector | Geometry_msgs::PoseStamped |
/hdas/feedback_arm_left | Input | Left arm joint feedback | Sensor_msgs::JointState |
/hdas/feedback_arm_right | Input | Right arm joint feedback | Sensor_msgs::JointState |
/motion_control/control_arm_left | Output | Left arm motor control | hdas_msg::motor_control |
/motion_control/control_arm_right | Output | Right arm motor control | hdas_msg::motor_control |
/motion_control/pose_ee_arm_left | Output | Actual pose of the left arm end-effector | Geometry_msgs::PoseStamped |
/motion_control/pose_ee_arm_right | Output | Actual pose of the right arm end-effector | Geometry_msgs::PoseStamped |
The detailed fields and descriptions for the above topics are as follows:
Topic Name | Field | Description |
---|---|---|
/motion_target/pose_ee_arm_left /motion_target/pose_ee_arm_right |
header | Standard message header |
pose.position.x | X-axis offset | |
pose.position.y | Y-axis offset | |
pose.position.z | Z-axis offset | |
pose.orientation.x | Rotation quaternion | |
pose.orientation.y | Rotation quaternion | |
pose.orientation.z | Rotation quaternion | |
pose.orientation.w | Rotation quaternion | |
/hdas/feedback_arm_left | - | Please refer to the arm driver interface |
/hdas/feedback_arm_right | - | Please refer to the arm driver interface |
/motion_control/control_arm_left | - | Please refer to the arm driver interface |
/motion_control/control_arm_right | - | Please refer to the arm driver interface |
/motion_control/pose_ee_arm_left /motion_control/pose_ee_arm_right |
header | Standard message header |
pose.position.x | X-axis offset | |
pose.position.y | Y-axis offset | |
pose.position.z | Z-axis offset | |
pose.orientation.x | Rotation quaternion | |
pose.orientation.y | Rotation quaternion | |
pose.orientation.z | Rotation quaternion | |
pose.orientation.w | Rotation quaternion |
Gripper Control
The gripper control package is a ROS package used to control the end-effector gripper. It can be started using the following command:
# Before calling the following APIs, please ensure that FDCAN communication and the HDAS node are already started (refer to the separate section on how to start them).
ros2 launch mobiman r1_gripperController_launch.py robot_type:=R1LITE
Note: This startup file will launch R1_Gripper_Controller
, not R1_Pro_Gripper_Controller
.
Interface Information:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_position_gripper_left | Input | Target position of the left gripper | sensor_msgs::JointState |
/motion_target/target_position_gripper_right | Input | Target position of the right gripper | sensor_msgs::JointState |
/motion_control/control_gripper_left | Output | Left gripper motor control | hdas_msg::motor_control |
/motion_control/control_gripper_right | Output | Right gripper motor control | hdas_msg::motor_control |
The specific fields and their descriptions for the above topics are as follows:
Topic Name | Field | Description |
---|---|---|
/motion_target/target_position_gripper_left /motion_target/target_position_gripper_right |
position | Represents the target position of the left and right grippers [0, 100], where 0 is fully closed and 100 is fully open. |
/motion_control/control_gripper_left /motion_control/control_gripper_right |
- | Please refer to the arm driver interface |
Torso Velocity Control
The torso velocity control is an ROS package used to control the torso's movement to a target floating base coordinate frame. It can be launched using the following command:
# Before using this interface, please ensure that FDCAN communication and the HDAS node are already running (refer to the separate startup section for instructions).
ros2 launch mobiman torso_control_r1_lite.launch.py
Interface information is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_speed_torso | Input | Target speed in the floating base frame | Geometry_msgs::TwistStamped |
/hdas/feedback_torso | Input | Torso joint feedback | Sensor_msgs::JointState |
/motion_control/control_torso | Output | Torso joint control | hdas_msg::motor_control |
The detailed fields for the above topics are as follows:
Topic Name | Field | Description |
---|---|---|
/motion_target/target_speed_torso | target_speed.v_x = msg->linear.x | Torso linear velocity along X in Cartesian space, [-0.2, 0.2] m/s; -0.1 ≤ x ≤ 0.2 |
target_speed.v_z = msg->linear.z | Torso linear velocity along Z in Cartesian space, [-0.2, 0.2] m/s; 0.1 ≤ z ≤ 0.7 |
|
target_speed.v_pitch = msg->twist.angular.y | Torso pitch angular velocity in Cartesian space | |
target_speed.v_yaw = msg->twist.angular.z | Torso yaw angular velocity in Cartesian space | |
/hdas/feedback_torso | - | Please refer to the torso drive interface |
/motion_control/control_torso | - | Please refer to the torso drive interface |
As shown in the diagram, this control node represents the velocity control of torsolink3
relative to base_link
, with the direction aligned with the base_link
frame.
`

v_x
is the velocity of the torso frame along the x-axis relative tobase_link
(maximum speed is 0.1 m/s). A positive value indicates forward movement relative tobase_link
, and a negative value indicates backward movement.v_z
is the velocity of the torso frame along the z-axis relative tobase_link
(maximum speed is 0.1 m/s). A positive value indicates upward movement relative tobase_link
, and a negative value indicates downward movement.w_pitch
is the angular velocity of the torso frame along the y-axis relative tobase_link
(maximum speed is 0.3 rad/s), following the right-hand rule.w_yaw
is the angular velocity of the torso frame along the z-axis relative tobase_link
(maximum speed is 0.3 rad/s), also following the right-hand rule.
Torso Joint Control
The torso joint control node is responsible for controlling each joint of the torso, which has a total of 3 joints. It can be started using the following command:
# Please choose one of the following launch files to start. The only difference is the joint speed limit parameter.
# Before calling the following interface, please ensure that FDCAN communication and HDAS nodes are running (refer to the separate startup section for instructions).
ros2 launch mobiman r1_lite_jointTrackerdemo_fast_launch.py # (High-speed tracking mode) (default)
ros2 launch mobiman r1_lite_jointTrackerdemo_launch.py # (Normal mode)
Important Note: Although the torso velocity control node and the torso joint control node can be started simultaneously, the torso velocity control signals and the torso joint control signals cannot be used together. Doing so will cause joint conflicts and pose a safety risk.
# That is, the following two topics cannot be used together when both the torso velocity control node and the torso joint control node are running; only one can be used at a time. Otherwise, it will cause joint conflicts and pose a safety risk.
/motion_target/target_speed_torso
/motion_target/target_joint_state_torso
Interface information is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_joint_state_torso | Input | Target positions of torso joints | Sensor_msgs::JointState |
/hdas/feedback_torso | Input | Feedback of torso joints | Sensor_msgs::JointState |
/motion_control/control_torso | Output | Torso motor control | hdas_msg::motor_control |
The detailed fields and descriptions for the above topics are as follows:
Message Name | Field | Description |
---|---|---|
/motion_target/target_joint_state_torso | header | Standard message header |
position | A vector containing six elements representing the target positions of each joint. | |
velocity | A vector containing six elements representing the maximum velocity of each joint during motion. | |
/hdas/feedback_torso | - | Please refer to the arm driver interface |
/motion_control/control_torso | - | Please refer to the arm driver interface |
Chassis Control
The chassis control node uses vector control to control the R1 Lite chassis, allowing simultaneous control of three movement directions: x, y, and w. It can be started using the following command:
#Before calling the following APIs, please ensure that FDCAN communication and the HDAS node are already started (refer to the separate section on how to start them).
ros2 launch mobiman r1_lite_chassis_control_w_o_eepose_launch.py
This file will launch a node: r1_lite_chassis_control_node
, which is responsible for controlling the velocity of the R1 Lite chassis. Its interface is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_speed_chassis | Input | Target velocity of the chassis, including vx, vy, and omega | geometry_msgs::Twist |
/motion_target/chassis_acc_limit | Input | Acceleration limits of the chassis; maximum values are 2.5, 1.0, 1.0 for vx, vy, and omega respectively | geometry_msgs::Twist |
/motion_target/brake_mode | Input | Command to enable or disable the chassis brake mode. If in brake mode, when the velocity is zero, the chassis will lock itself by slightly rotating the wheels. |
std_msgs::Bool |
/hdas/feedback_chassis | Input | The R1 Lite chassis controller subscribes to this topic to control the chassis target velocity. | sensor_msgs::JointState |
/motion_control/control_chassis | Output | The R1 Lite chassis controller publishes to this topic to control the motors. | hdas_msg::motor_control |
The detailed fields and descriptions for the above topics are shown in the table below:
Message Name | Field | Description |
---|---|---|
/motion_target/target_speed_chassis | header | Standard ROS message header |
linear | Linear velocity | |
.x | Linear velocity x, range (-1.5, 1.5) m/s | |
.y | Linear velocity y, range (-1.5, 1.5) m/s | |
angular | Angular velocity | |
.z | Angular velocity z, range (-3, 3) rad/s | |
/motion_target/chassis_acc_limit | header | Standard ROS message header |
linear | Linear acceleration limits | |
.x | Acceleration limit x, range (-2.5, 2.5) m/s² | |
.y | Acceleration limit y, range (-1.0, 1.0) m/s² | |
angular | Angular acceleration limits | |
.z | Angular acceleration limit z, range (-3, 3) rad/s² | |
/motion_target/brake_mode | data | Boolean value Enter brake mode: True Exit brake mode: False |
/hdas/feedback_chassis | - | Refer to the chassis driver interface |
/motion_control/control_chassis | - | Refer to the chassis driver interface |