R1 Lite Software Introduction
Environment Dependencies
- Hardware Dependency: R1 Lite Computing Unit
- Operating System Dependency: Ubuntu 20.04 LTS
- Middleware Dependency: ROS Noetic
Software Version Log
Visit the Galaxea R1 Lite Software Version Change Log to view the latest SDK package and update information.
First-Time Operation Guide
Visit the Galaxea R1 Lite Unboxing and Startup Guide and follow the instructions to operate the Galaxea R1 Lite.
Starting the SDK
Currently, two methods are supported for starting the software interfaces: Separate Launch and One-Click Launch. For your safety, it is recommended to use the Separate Launch method to start the SDK.
The operation guide is as follows:
Module Name | Included Components | Path | Launch File |
---|---|---|---|
HDAS | Arms Driver Torso Driver Chassis Driver IMU Driver BMS Driver |
{sdk_path}/install/share/HDAS/launch | r1lite.launch |
camera_driver | Head Camera Interface | {sdk_path}/install/share/camera_driver/launch | run.launch |
realsense2_camera | Wrist Camera Interface | {sdk_path}/install/share/realsense2_camera/launch | rs_multiple_devices.launch |
mobiman | Arm Control Chassis Control Torso Control Gripper Control End Effector Pose Interface |
{sdk_path}/install/share/mobiman/launch | r1_lite_jointTrackerdemo_fast.launch r1_lite_chassis_control.launch torso_control_r1_lite.launch r1_gripperController.launch r1_lite_eepose.launch |
robot_monitor | Robot Monitor Interface | {sdk_path}/install/share/system_monitor_node/launch | robot_monitor.launch |
data collection | Data Collection | {sdk_path}/install/share/data_collection/launch | data_collection.launch |
robot diagnosis system | rds_ros | {sdk_path}/install/share/rds_ros/launch | Rds.launch |
Separate Launch
All nodes can be started using the following command template. The configuration method is as follows:
Note: Before starting the nodes, please confirm that the CAN driver has been correctly configured.
bash ~/can.bash
# You may need to enter the password again: 1
# If the error message "RTNETLINK answers: Device or resource busy" appears, it usually means the device you are trying to configure (such as a network interface or CAN transceiver) is already configured and running.
The startup commands for each node are as follows:
source {sdk_path}/install/setup.bash
roslaunch <Package Name> <Launch File>
# Example
roslaunch HDAS r1lite.launch
One-Click Launch
Note: Executing the following command will start all drivers and motion control interfaces.
cd {sdk_path}/install/share/startup_config/script/
./robot_startup.sh boot ../session.d/ATCStandard/R1LITEBody.d
Software Interfaces
The current 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 referred to as "mobiman", representing Mobile Manipulation.
Driver Interfaces
Arm Driver Interface
This interface is a ROS package for robotic arm control and status feedback. It defines multiple topics for publishing and subscribing to arm status, control commands, and related error codes. Detailed descriptions of each topic and its corresponding message type are as follows:
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 Travel | sensor_msgs::JointState |
/hdas/feedback_gripper_right | Output | Right Gripper Travel | 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 and their detailed descriptions for the above topics are shown in the following table:
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 speed, Joint 2 speed, Joint 3 speed, Joint 4 speed, Joint 5 speed, Joint 6 speed, Gripper joint speed] | |
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 speed, Joint 2 speed, Joint 3 speed, Joint 4 speed, Joint 5 speed, Joint 6 speed, Gripper joint speed] | |
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-100mm) | |
velocity | Not in use for now. | |
effort | Not in use for now. | |
/hdas/feedback_gripper_right | header | Standard message header |
position | Gripper stroke (0-100mm) | |
velocity | Not in use for now. | |
effort | Not in use for now. | |
/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 error descriptions | |
/hdas/feedback_status_gripper_left | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding error descriptions | |
/hdas/feedback_status_gripper_right | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding error descriptions | |
/motion_control/control_arm_left(MIT) | header | Standard message header |
name | - | |
p_des | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
v_des | [Joint 1 speed, Joint 2 speed, Joint 3 speed, Joint 4 speed, Joint 5 speed, Joint 6 speed, Gripper joint speed] | |
kp | [Joint 1 kp, Joint 2 kp, Joint 3 kp, Joint 4 kp, Joint 5 kp, Joint 6 kp, Gripper joint kp] | |
kd | [Joint 1 (kd), Joint 2 (kd), Joint 3 (kd), Joint 4 (kd), Joint 5 (kd), Joint 6 (kd), Gripper joint (kd)] | |
t_ff | [Joint 1 torque, Joint 2 torque, Joint 3 torque, Joint 4 torque, Joint 5 torque, Joint 6 torque, Gripper joint torque] | |
mode | - | |
/motion_control/control_arm_left(PID) | header | Standard message header |
name | - | |
p_des | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
v_des | - | |
t_ff | - | |
mode | - | |
/motion_control/control_arm_right(MIT) | header | Standard message header |
name | - | |
p_des | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
v_des | [Joint 1 speed, Joint 2 speed, Joint 3 speed, Joint 4 speed, Joint 5 speed, Joint 6 speed, Gripper joint speed] | |
kp | [Joint 1 kp, Joint 2 kp, Joint 3 kp, Joint 4 kp, Joint 5 kp, Joint 6 kp, Gripper joint kp] | |
kd | [Joint 1 (kd), Joint 2 (kd), Joint 3 (kd), Joint 4 (kd), Joint 5 (kd), Joint 6 (kd), Gripper joint (kd)] | |
t_ff | [Joint 1 torque, Joint 2 torque, Joint 3 torque, Joint 4 torque, Joint 5 torque, Joint 6 torque, Gripper joint torque] | |
mode | - | |
/motion_control/control_arm_right(PID) | header | Standard message header |
name | - | |
p_des | [Joint 1 position, Joint 2 position, Joint 3 position, Joint 4 position, Joint 5 position, Joint 6 position, Gripper joint position] | |
v_des | [Joint 1 torque, Joint 2 torque, Joint 3 torque, Joint 4 torque, Joint 5 torque, Joint 6 torque, Gripper joint torque] | |
t_ff | [Maximum speed limit for joint 1, Maximum speed limit for joint 2, Maximum speed limit for joint 3, Maximum speed limit for joint 4, Maximum speed limit for joint 5, Maximum speed limit for joint 6, Maximum speed limit for gripper joint] | |
mode | - | |
/motion_control/control_gripper_left | header | Standard message header |
name | - | |
p_des | Gripper motor position | |
v_des | Gripper motor speed | |
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 speed | |
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 travel distance (0-100mm) | |
/motion_control/position_control_gripper_right | header | Standard message header |
data | Expected gripper travel distance (0-100mm) |
Description of the control interface for robotic arm joint motors
1. MIT-Force-Position Hybrid Control ArchitectureThe motor output torque formula is used to calculate the torque value Tref
that the current loop control system should track.The formula is as follows:
\(K_p(p_d - p_e) + K_d(v_d - v_e)+t_{ff} = T_{ref}\)
其中:
Kp
,Kd
This represents the proportional component of the position gain and velocity gain;
p_des
and v_des
represent the desired position and velocity;
t_ff
represents the feedforward torque.
p_e
represents the position feedback from the encoder, and v_e
represents the motor speed calculated by differentiation.
- The input parameters include:
Kp
,Kd
,pd
,vd
, andt_ff
. The feedback parameterspe
andve
do not need to be entered manually.
Usage Tips:
- Feedforward Torque: This value is mandatory. Since the position and velocity terms cannot compensate for excessive torque errors, the feedforward torque should at least compensate for the weight of the robotic arm itself.
- Recommended Gain Settings: The following are the recommended kp
and kd
values for the A1X motor; please adjust these values with caution.
`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 system (position loop, velocity loop, and current loop). This mode incorporates an integral term, resulting in smaller steady-state errors. To maintain interface consistency, the control data format is the same as the MIT interface.
其中:
p_des
:Represents the target angle (rad);
v_des
:Not used;
k_p
,k_d
:Not used;
t_ff
:Not used;
Torso Drive Interface
This interface is a ROS package used for torso control and providing status feedback. It defines multiple topics for publishing and subscribing to the status and control commands of torso motors. Below is a detailed description of each topic and its corresponding message type:
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 |
The specific fields and detailed descriptions for the topics above are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/hdas/feedback_torso | header | Standard message header |
position | [Joint 1 Position, Joint 2 Position, Joint 3 Position, 0] | |
velocity | [Joint 1 Velocity, Joint 2 Velocity, Joint 3 Velocity, 0] | |
effort | [Joint 1 Effort, Joint 2 Effort, Joint 3 Effort, 0] | |
/hdas/feedback_status_torso | header | Standard message header |
name_id | Joint name | |
errors | Contains error codes and corresponding error descriptions | |
/motion_control/control_torso | header | Standard message header |
name | - | |
p_des | [Joint 1 Position, Joint 2 Position, Joint 3 Position, 0] | |
v_des | [Joint 1 Max Velocity, Joint 2 Max Velocity, Joint 3 Max Velocity, 0] | |
kp | [-, -, -, -] | |
kd | [-, -, -, -] | |
t_ff | [-, -, -, -] | |
mode | - |
Chassis Drive Interface
This interface is a ROS package used for chassis state feedback, defining multiple topics to report the status of chassis motors. The following is a detailed description of each topic and its associated message type:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/feedback_chassis | Output | Chassis wheel 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 wheel and steering motor control | hdas_msg::motor_control |
The specific fields and their detailed descriptions for the above topics are shown in the following table:
Topic Name | Field | Description |
---|---|---|
/hdas/feedback_chassis | header | Standard message header |
position | [Left front wheel angle, Right front wheel angle, Rear wheel angle] | |
velocity | [Left front wheel linear velocity, Right front 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 error descriptions | |
/motion_control/control_chassis | header | Standard message header |
name | - | |
p_des | [Left front wheel angle, Right front wheel angle, Rear wheel angle] | |
v_des | [Left front wheel linear velocity, Right front 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 camera left eye RGB compressed image | sensor_msgs::CompressedImage |
/hdas/camera_head/right_raw/image_raw_color/compressed | Output | Head camera right eye 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 |
The specific fields and their detailed descriptions for the above topics are shown in the following table:
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 settings | |
width | Depends on settings | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | Depends on settings | |
data | Image data | |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | header | Standard message header |
height | Depends on settings | |
width | Depends on settings | |
encoding | 16UC1 | |
is_bigendian | 0 | |
step | Determined by 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 |
The specific fields and their detailed descriptions for the above topics are shown in the following table:
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 |
The specific fields and their detailed descriptions for the above topic are shown in the following table:
Topic Name | Field | Description |
---|---|---|
/hdas/bms | header | Standard message header |
voltage | Voltage (V) | |
current | Current (I) | |
capital | Remaining battery capacity (%) |
Remote Controller Interface
Topic Name | I/O | Description | <极市 style="width: 300px; padding: 8px; border: 1px solid #ddd;">Message Type|
---|---|---|---|
/controller | Output | Remote controller signal | hdas_msg::controller_signal_stamped |
The specific fields and their detailed descriptions for the above topic are shown in the following table:
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: Remote controller control (chassis)5: Host computer control (chassis) |
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, divided into left arm pose control 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 control the R1 Lite chassis and can send velocity commands in three directions simultaneously: 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 with the following command:
# Before calling the following interfaces, please ensure that FDCAN communication and the HDAS node have been started (refer to the separate section on how to start them).
# You can choose to launch either of the following two configurations; the only difference is the joint velocity limit parameter.
roslaunch mobiman r1_lite_jointTrackerdemo.launch #(Normal mode)
roslaunch mobiman r1_lite_jointTrackerdemo_fast.launch #(High-follow mode)
The interface information is as follows:
Topic Name | I/O | <极市 style="background-color: black; color: white; vertical-align: middle; padding: 8px; border: 1px solid #ddd; width: 200px;">DescriptionMessage Type | |
---|---|---|---|
/motion_target/target_joint_state_arm_left | Input | Target position for each joint of the left arm | sensor_msgs::JointState |
/motion_target/target_joint_state_arm_right | Input | Target position for each joint of the right arm | 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 |
Output | Right arm motor control | hdas_msg::motor_control |
The specific fields and their detailed descriptions for the above topics are shown in the following table:
Topic Name | Field | Description |
---|---|---|
/motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
header | Standard message header |
position | This is a vector containing six elements, representing the six target positions for each joint. | |
velocity | This is a vector containing six elements, representing the maximum velocity for each joint during motion. | |
/hdas/feedback_arm_left | - | Please refer to the Arm Drive Interface |
/hdas极市/feedback_arm_right | - | Please refer to the Arm Drive Interface |
/motion_control/control_arm_left | - | Please refer to the Arm Drive Interface |
/motion_control/control_arm_right | - | Please refer to the Arm Drive Interface |
Arm Pose Control
Arm pose control is a ROS package used to control the arm's movement to the target end-effector (ee) coordinate frame. It mainly includes two launch files, corresponding to the left arm's pose control and the right arm's pose control respectively. It can be started with 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.
roslaunch mobiman r1_lite_left_arm_relaxed_ik.launch
#Open a new terminal window
roslaunch mobiman r1_lite_right_arm_relaxed_ik.launch
# 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:
The interface information is as follows:Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_pose_arm_left | Input | Target left arm end-effector pose | geometry_msgs::PoseStamped |
/motion_target/target_pose_arm_right | Input | Target right arm end-effector pose | 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 left arm end-effector pose | geometry_msgs::PoseStamped |
/motion_control/pose_ee_arm_right | <极市 style="vertical-align: middle; padding: 8px; border: 1px solid #ddd;">OutputActual right arm end-effector pose | geometry_msgs::极市:PoseStamped |
The specific fields and their detailed descriptions for the above topics are shown in the following table:
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 Drive Interface |
/hdas/feedback_arm_right | - | Please refer to the Arm Drive Interface |
/motion_极市control/control_arm_left | - | Please refer to the Arm Drive Interface |
/motion_control/control_arm_right | - | Please refer to the Arm Drive 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
Gripper control is a ROS package used to control the end-effector gripper. It can be started with the following command:
# Before calling the following interfaces, please ensure that FDCAN communication and the HDAS node have been started (refer to the separate section on how to start them).
roslaunch mobiman r1_gripperController.launch 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 |
Detailed fields of the above topics and their descriptions are shown in the table below:
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 a ROS package used to control the torso to move to the target floating base coordinate frame.
It can be launched with the following command:
#Before calling the following interfaces, please ensure that FDCAN communication and the HDAS node have been started (refer to the separate section on how to start them).
roslaunch mobiman torso_control_r1_lite.launch
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_speed_torso | Input | Target speed of 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 |
Detailed fields of the above topics and their descriptions are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/motion_target/target_speed_torso | target_speed.v_x = msg->linear.x | Torso Cartesian linear velocity in the x direction, [-0.2, 0.2] m/s; -0.1 ≤ x ≤ 0.2 |
target_speed.v_z = msg->linear.z | Torso Cartesian linear velocity in the z direction, [-0.2, 0.2] m/s; 0.1 ≤ z ≤ 0.7 |
|
target_speed.v_pitch = msg->twist.angular.y | Torso Cartesian angular velocity in pitch | |
target_speed.v_yaw = msg->twist.angular.z | Torso Cartesian angular velocity in yaw | |
/hdas/feedback_torso | - | Please refer to the torso driver interface |
/motion_control/control_torso | - | Please refer to the torso driver interface |
This control node, as shown in the figure, represents the velocity control of torsolink3
relative to base_link
, with directions aligned to the base_link
frame.
- v_x is the torso frame velocity relative to
base_link
in the x direction (maximum 0.1 m/s). A positive value means forward relative tobase_link
, and a negative value means backward. - v_z is the torso frame velocity relative to
base_link
in the z direction (maximum 0.1 m/s). A positive value means upward relative tobase_link
, and a negative value means downward. - w_pitch is the torso frame angular velocity relative to
base_link
around the y-axis (maximum 0.3 rad/s), following the right-hand rule. - w_yaw is the torso frame angular velocity relative to
base_link
around the z-axis (maximum 0.3 rad/s), following the right-hand rule.
Torso Joint Control
The torso joint control node is responsible for controlling each joint of the torso, with a total of 3 joints.
It can be launched with the following command:
# Please choose and run only one of the following launch files; the only difference between them is the joint velocity limit parameter.
# Before using the following interfaces, please ensure that FDCAN communication and the HDAS node are already running (refer to the separate startup section for instructions).
roslaunch mobiman r1_lite_jointTrackerdemo_fast.launch # (High-fidelity tracking mode) (default)
roslaunch mobiman r1_lite_jointTrackerdemo.launch # (Normal mode)
Note: The torso joint control node and the arm control node are the same node.
Important Note: While the torso speed control node and the joint control node can be activated simultaneously, the torso speed control signal and the torso joint control signal cannot be used interchangeably; otherwise, it may cause joint conflicts and pose a safety risk.
# In other words, these two control methods (using torso velocity control and joint control) cannot be used simultaneously; you must choose one or the other. Otherwise, it may cause conflicts and potentially dangerous situations for the joints.
/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 position of each torso joint | Sensor_msgs::JointState |
/hdas/feedback_torso | Input | Torso joint feedback | Sensor_msgs::JointState |
/motion_control/control_torso | Output | Torso motor control | hdas_msg::motor_control |
The detailed fields and descriptions of the above topics are shown in the following table:
Message Name | Field | Description |
---|---|---|
/motion_target/target_joint_state_torso | header | Standard message header |
position | A vector containing six elements, representing the six 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
Chassis control is a node that uses vector control to operate the R1 Lite chassis. It can simultaneously send velocity commands in three directions: x, y, and w.
It can be launched with 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).
roslaunch mobiman r1_lite_chassis_control.launch
This file will launch a node: r1_lite_chassis_control_node
, which is responsible for controlling the speed of the R1 Lite chassis. Its interface is as follows:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_speed_chassis | Input | Target speed of the chassis, including vx, vy, and omega | geometry_msgs::Twist |
/motion_target/chassis_acc_limit | Input | Acceleration limits of the chassis, with maximum values of 2.5, 1.0, 1.0 | geometry_msgs::Twist |
/motion_target/brake_mode | Input | Command indicating 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 | R1 Lite chassis control subscribes to this topic and controls the target speed of the chassis. | sensor_msgs::JointState |
/motion_control/control_chassis | Output | R1 Lite chassis control publishes this topic to control the motors. | hdas_msg::motor_control |
The detailed fields and descriptions of the above topics are shown in the following table:
Message Name | Field | Description |
---|---|---|
/motion_target/target_speed_chassis | header | Standard 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, range (-3, 3) rad/s | |
/motion_target/chassis_acc_limit | header | Standard message header |
linear | Linear velocity | |
.x | Acceleration limit x, range (-2.5, 2.5) m/s² | |
.y | Acceleration limit y, range (-1.0, 1.0) m/s² | |
angular | Angular velocity | |
.z | Angular acceleration limit, range (-3, 3) rad/s² | |
/motion_target/brake_mode | data | Boolean Enter brake mode: True Exit brake mode: False |
/hdas/feedback_chassis | - | Please refer to the chassis driver interface |
/motion_control/control_chassis | - | Please refer to the chassis driver interface |