Skip to content

R1 Lite Software Introduction

Environment Dependency

  1. Hardware Dependency: R1 Lite Computing Unit
  2. OS Dependency: Ubuntu 20.04 LTS (Install dual systems on a PC without using a virtual machine.)
  3. Middleware Dependency: ROS Noetic

Software Version Changelog

This is the initial software release for the R1 Lite. For future version updates, you can check the R1 Lite Software Version Update Log to obtain the latest SDK package and update information.

First-Time Operation Guide

Refer to the Galaxea R1 Lite Unboxing and Startup Guide and follow the instructions to operate the R1 Lite.

Software Interface

Driver Interface

Arms Driver Interface

This interface is used for the robot arm control and status feedback ROS package, which defines multiple topics for publishing and subscribing to the arm's status, control commands, and associated error codes.

Below are detailed descriptions of each topic and its corresponding message types:

Topic Name I/O Description Message Type
/hdas/feedback_arm_left Output Joint feedback of left arm sensor_msgs::JointState
/hdas/feedback_arm_right Output Joint feedback of right arm sensor_msgs::JointState
/hdas/feedback_gripper_left Output Gripper stroke of left gripper sensor_msgs::JointState
/hdas/feedback_gripper_right Output Gripper stroke of right gripper sensor_msgs::JointState
/hdas/feedback_status_arm_left Output Status of left arm hdas_msg::feedback_status
/hdas/feedback_status_arm_right Output Status of right arm hdas_msg::feedback_status
/hdas/feedback_status_gripper_left Output Status of left gripper hdas_msg::feedback_status
/hdas/feedback_status_gripper_right Output Status of right gripper hdas_msg::feedback_status
/motion_control/control_arm_left Input Motor control of left arm hdas_msg::motor_control
/motion_control/control_arm_right Input Motor control of right arm hdas_msg::motor_control
/motion_control/control_gripper_left Input Motor control of left gripper hdas_msg::motor_control
/motion_control/control_gripper_right Input Motor control of right gripper hdas_msg::motor_control
/motion_control/position_control_gripper_left Input Position control of left gripper std_msgs::Float32
/motion_control/position_control_gripper_right Input Position control of right gripper std_msgs::Float32

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/feedback_arm_left header Standard header
position [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position, gripper_position]
velocity [Joint1_velocity, Joint2_velocity, Joint3_velocity, Joint4_velocity, Joint5_velocity, Joint6_velocity, gripper_velocity]
effort [Joint1_effort, Joint2_effort, Joint3_effort, Joint4_effort, Joint5_effort, Joint6_effort, gripper_effort]
/hdas/feedback_arm_right header Standard header
position [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position, gripper_position]
velocity [Joint1_velocity, Joint2_velocity, Joint3_velocity, Joint4_velocity, Joint5_velocity, Joint6_velocity, gripper_velocity]
effort [Joint1_effort, Joint2_effort, Joint3_effort, Joint4_effort, Joint5_effort, Joint6_effort, gripper_effort]
/hdas/feedback_gripper_left header Standard header
position [gripper_stroke]
velocity Not used
effort Not used
/hdas/feedback_gripper_right header Standard header
position [gripper_stroke]
velocity Not used
effort Not used
/hdas/feedback_status_arm_left header Standard header
name_id Joint name
errors Contains error code and error description
/hdas/feedback_status_arm_right header Standard header
name_id Joint name
errors Contains error code and error description
/hdas/feedback_status_gripper_left header Standard header
name_id Joint name
errors Contains error code and error description
/hdas/feedback_status_gripper_right header Standard header
name_id Joint name
errors Contains error code and error description
/motion_control/control_arm_left
(Servo Mode)
header Standard header
name -
p_des [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position]
v_des [Joint1_velocity_max_limit, Joint2_velocity_max_limit, Joint3_velocity_max_limit, Joint4_velocity_max_limit, Joint5_velocity_max_limit, Joint6_velocity_max_limit]
t_ff [Joint1_effort_max_limit, Joint2_effort_max_limit, Joint3_effort_max_limit, Joint4_effort_max_limit, Joint5_effort_max_limit, Joint6_effort_max_limit]
mode -
/motion_control/control_arm_left
(Torque-Position-Mix Control Mode)
header Standard header
name -
p_des [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position]
v_des [Joint1_velocity, Joint2_velocity, Joint3_velocity, Joint4_velocity, Joint5_velocity, Joint6_velocity]
kp [Joint1_kp, Joint2_kp, Joint3_kp, Joint4_kp, Joint5_kp, Joint6_kp]
kd [Joint1_kd, Joint2_kd, Joint3_kd, Joint4_kd, Joint5_kd, Joint6_kd]
t_ff [Joint1_effort, Joint2_effort, Joint3_effort, Joint4_effort, Joint5_effort, Joint6_effort]
mode -
/motion_control/control_arm_right
(Servo Mode)
header Standard header
name -
p_des [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position]
v_des [Joint1_velocity_max_limit, Joint2_velocity_max_limit, Joint3_velocity_max_limit, Joint4_velocity_max_limit, Joint5_velocity_max_limit, Joint6_velocity_max_limit]
t_ff [Joint1_effort_max_limit, Joint2_effort_max_limit, Joint3_effort_max_limit, Joint4_effort_max_limit, Joint5_effort_max_limit, Joint6_effort_max_limit]
mode -
/motion_control/control_arm_right
(Torque-Position-Mix Control Mode)
header Standard header
name -
p_des [Joint1_position, Joint2_position, Joint3_position, Joint4_position, Joint5_position, Joint6_position]
v_des [Joint1_velocity, Joint2_velocity, Joint3_velocity, Joint4_velocity, Joint5_velocity, Joint6_velocity]
kp [Joint1_kp, Joint2_kp, Joint3_kp, Joint4_kp, Joint5_kp, Joint6_kp]
kd [Joint1_kd, Joint2_kd, Joint3_kd, Joint4_kd, Joint5_kd, Joint6_kd]
t_ff [Joint1_effort, Joint2_effort, Joint3_effort, Joint4_effort, Joint5_effort, Joint6_effort]
mode -
/motion_control/control_gripper_left header Standard header
name -
p_des [gripper_position]
v_des [gripper_velocity]
kp [gripper_kp]
kd [gripper_kd]
t_ff [gripper_effort]
mode -
/motion_control/control_gripper_right header Standard header
name -
p_des [gripper_position]
v_des [gripper_velocity]
kp [gripper_kp]
kd [gripper_kd]
t_ff [gripper_effort]
mode -
/motion_control/position_control_gripper_left header Standard header
data desired_gripper_stroke, range (0 to 100) mm
/motion_control/position_control_gripper_right header Standard header
data desired_gripper_stroke, range (0 to 100) mm

Torso Driver Interface

This interface is used for the torso control and status feedback ROS package, which defines multiple topics for publishing and subscribing to the status of the torso motors and control commands. Below are detailed descriptions of each topic and its corresponding message types:

Topic Name I/O Description Message Type
/hdas/feedback_torso Output Joint feedback of torso sensor_msgs/JointState
/hdas/feedback_status_torso Output Torso motor status feedback hdas_msg::feedback_status
/motion_control/control_torso Input Motor control of torso hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/feedback_torso header Standard header
position [joint1_position, joint2_position, joint3_position, 0]
velocity [joint1_velocity, joint2_velocity, joint3_velocity, 0]
effort [joint1_velocity, joint2_velocity, joint3_velocity, 0]
/hdas/feedback_status_torso header Standard header
name_id Joint name
errors Contains error code and error description
/motion_control/control_torso header Standard header
name -
p_des [Joint1_position, Joint2_position, Joint3_position, 0]
v_des [Joint1_velocity, Joint2_velocity, Joint3_velocity, 0]
kp [Joint1_kp, Joint2_kp, Joint3_kp, 0]
kd [Joint1_kd, Joint2_kd, Joint3_kd, 0]
t_ff [Joint1_effort, Joint2_effort, Joint3_effort, 0]
mode -

Chassis Driver Interface

This interface is used for the chassis status feedback ROS package, which defines multiple topics to report the status of the chassis' motors. Below are detailed descriptions of each topic and its associated message types:

Topic Name I/O Description Message Type
/hdas/feedback_chassis Output Feedback of chassis sensor_msgs::JointState
/hdas/feedback_status_chassis Output Status of chassis hdas_msg::feedback_status
/motion_control/control_chassis Input Motor control of chassis hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/feedback_chassis header Standard header
position [angle_front_left, angle_front_right, angle_rear]
velocity [linear_velocity_front_left, linear_velocity_front_right, linear_velocity_rear 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 header
name_id Joint name
errors Contains error code and error description
/motion_control/control_chassis header Standard header
name -
p_des [angle_front_left, angle_front_right, angle_rear]
v_des [linear_velocity_front_left, linear_velocity_front_right, linear_velocity_rear]
kp -
kd -
t_ff -
mode -

Camera Interface

Topic Name I/O Description Message Type
/hdas/camera_wrist_left/color/image_raw/compressed Output Compressed Image from left wrist camera sensor_msgs::CompressedImage
/hdas/camera_wrist_right/color/image_raw/compressed Output Compressed Image from right wrist camera sensor_msgs::CompressedImage
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw Output Depth Image from left wrist camera sensor_msgs::Image
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw Output Depth Image from right wrist camera sensor_msgs::Image

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/camera_wrist_left/color/image_raw/compressed header Standard header
format JPEG
data Image data
/hdas/camera_wrist_right/color/image_raw/compressed header Standard header
format JPEG
data Image data
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw header Standard header
height Depend on settings
width Depend on settings
encoding 16UC1
is_bigendian 0
step Depend on settings
data Image data
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw header Standard header
height Depend on settings
width Depend on settings
encoding 16UC1
is_bigendian 0
step Depend on settings
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

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/imu_chassis header Standard header
orientation.x quaternion x
orientation.y quaternion y
orientation.z quaternion z
orientation.w quaternion w
angular_velocity.x Groyscope angular velocity x
angular_velocity.y Groyscope angular velocity y
angular_velocity.z Groyscope 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 header
orientation.x quaternion x
orientation.y quaternion y
orientation.z quaternion z
orientation.w quaternion w
angular_velocity.x Groyscope angular velocity x
angular_velocity.y Groyscope angular velocity y
angular_velocity.z Groyscope 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 information hdas_msg::bms

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/hdas/bms header Standard header
voltage Voltage in V
current Current in A
capital Capital in %

Remote Controller Interface

Topic Name I/O Description Message Type
/controller Output Signal from remote controller hdas_msg::controller_signal_stamped

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/controller header Standard header
data.left_x_axis X axis of left joystick
data.left_y_axis Y axis of left joystick
data.right_x_axis X axis of right joystick
data.right_y_axis Y axis of right joystick
mode 2: Chassis control via controller
5: ECU takes over

Motion Control Interface

  • 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, which is divided into pose control for the left arm and the right arm.
  • Torso Speed 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 manage the R1 Lite chassis, allowing simultaneous 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 launched using a command.

# Choose one of the following two launch files to start. The core difference lies in the joint speed limit parameters.
source ~/work/galaxea/install/setup.bash
roslaunch mobiman r1_lite_jointTrackerdemo.launch                # Normal Mode         
roslaunch mobiman r1_lite_jointTrackerdemo_fast.launch           # High-Follow Mode

The interface is shown below.

Topic Name I/O Description Message Type
/motion_target/target_joint_state_arm_left Input Target position of each left arm joint sensor_msgs::JointState
/motion_target/target_joint_state_arm_right Input Target position of each right arm joint sensor_msgs::JointState
/hdas/feedback_arm_left Input Feedback of left arm motor sensor_msgs::JointState
/hdas/feedback_arm_right Input Feedback of right arm motor sensor_msgs::JointState
/hdas/feedback_torso Input Feedback of torso motor sensor_msgs::JointState
/motion_control/control_arm_left Output Control of left arm motor hdas_msg::motor_control
/motion_control/control_arm_right Output Control of right arm motor hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/motion_target/target_joint_state_arm_left
/motion_target/target_joint_state_arm_right
header Standard ROS header
position This is a vector of six elements. 6 joint target positions for each joint.
velocity This is a vector of six elements. Standing for max velocity of each joint during movement.
/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

R1 Arm Pose Control is a ROS package for controlling arm movement to the target end-effector (ee) frame. It can be launched using the following command:

source ~/work/galaxea/install/setup.bash
roslaunch mobiman R1_Lite_left_arm_relaxed_ik.launch  #MPC control of the left arm 
roslaunch mobiman R1_Lite_right_arm_relaxed_ik.launch #MPC control of the right arm 

The interface is shown below.

Topic Name I/O Description Message Type
/motion_target/target_pose_arm_left Input Target end-effector pose of the left arm Geometry_msgs::PoseStamped
/motion_target/target_pose_arm_right Input Target end-effector pose of the right arm Geometry_msgs::PoseStamped
/hdas/feedback_arm_left Input Feedback of arm joint Sensor_msgs::JointState
/hdas/feedback_arm_right Input Feedback of arm joint Sensor_msgs::JointState
/motion_control/control_arm_left Output Control of left arm motor hdas_msg::motor_control
/motion_control/control_arm_right Output Control of right arm motor hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/motion_target/target_pose_arm_left
/motion_target/target_pose_arm_right
header Standard Header
pose.position.x Shift in x-direction
pose.position.y Shift in y-direction
pose.position.z Shift in z-direction
pose.orientation.x Orientation quaternion
pose.orientation.y Orientation quaternion
pose.orientation.z Orientation quaternion
pose.orientation.w Orientation 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.

Torso Speed Control

Torso Speed Control is a ROS package for controlling torso movement to the target floating base frame. It can be launched using the following command:

source ~/work/galaxea/install/setup.bash
roslaunch mobiman torso_speed_control_example.launch

The interface is shown as follows:

Topic Name I/O Description Message Type
/motion_target/target_joint_state_torso Input Target Joint position of each joint of torso Sensor_msgs::JointState
/hdas/feedback_torso Input Feedback of torso joint Sensor_msgs::JointState
/motion_control/control_torso Output Control of torso motor hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/motion_target/target_speed_torso target_speed.v_x = msg->linear.x Linear velocity in the x direction of the torso in Cartesian space;
Range: [-0.2, 0.2] m/s
Constraint: -0.1 ≤ x ≤ 0.2
target_speed.v_z = msg->linear.z Linear velocity in the z direction of the torso in Cartesian space;
Range: [-0.2, 0.2] m/s
Constraint: -0.1 ≤ x ≤ 0.7
target_speed.v_pitch = msg->twist.angular.y Pitch angular velocity of the torso in Cartesian space
target_speed.v_yaw = msg->twist.angular.z Yaw angular velocity of the torso in Cartesian space
/hdas/feedback_torso - Refer to the Torso Driver Interface

Chassis Control

R1 Chassis Control is the node that controls the R1 chassis using vector control, allowing you to send speed commands in three directions simultaneously: x, y, and w. It can be launched using a command.

source ~/work/galaxea/install/setup.bash
roslaunch mobiman r1_lite_chassis_control_w_o_eepose.launch

This launch file will bring up one node: r1_lite_chassis_control_node. The r1_lite_chassis_control_node is responsible for R1 Lite chassis speed control.

The interface is shown below:

Topic Name I/O Description Message Type
/motion_target/target_speed_chassis Input The target velocity of the chassis, including vx, vy, and omega. geometry_msgs::Twist
/motion_target/chassis_acc_limit Input The acceleration limits of the chassis, with maximum values of 2.5, 1.0, and 1.0 respectively. geometry_msgs::Twist
/motion_target/brake_mode Input Issue a command to determine whether the chassis enters brake mode. If in brake mode, when the speed is 0, the chassis will lock itself by rotating the wheels to a certain angle. std_msgs::Bool
/hdas/feedback_chassis Input The R1 Lite chassis control subscribes to this topic to control the target velocity of the chassis. sensor_msgs::JointState
/motion_control/control_chassis Output The R1 Lite chassis control publishes this topic to control the motors. hdas_msg::motor_control

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Description
/motion_target/target_speed_chassis header Standard ROS header
linear control of linear speed
.x linear_speed of x, range (-1.5 to 1.5) m/s
.y linear_speed of y, range (-1.5 to 1.5) m/s
angular control of yaw rate
.z control of angular speed, range (-3 to 3) rad/s
/motion_target/chassis_acc_limit header Standard ROS header
linear Acc limit of linear speed
.x Acc limit of x, range (-2.5 to 2.5) m/s²
.y Acc limit of y, range (-1.0 to 1.0) m/s²
angular control of yaw rate
.z Acc limit of angular speed, range (-3 to 3) rad/s²
/motion_target/brake_mode data Bool
True for entering brake mode;
False for quitting brake mode.
/hdas/feedback_chassis - Refer to HDAS msg Description
/motion_control/control_chassis - Refer to HDAS msg Description