Galaxea R1 Software Guide
Environment Dependency
- Hardware Dependency: R1 Computing Unit
- OS Dependency: Ubuntu 20.04 LTS
- Middleware Dependency: ROS Noetic
Software Version Changelog
Visit the R1 Software Version Changelog and find the latest update.
First Move
Visit the page R1_Demo and get started to operate R1 following the instructions.
Software Interface
The current Galaxea R1 control diagram is shown below, consisting of five main parts: R1 Pose Feedback, R1 Joint Control, R1 Chassis Control, R1 Arm Pose Control, and R1 Torso Pose Control. Details will be provided in the following chapters. The entire package is called 'mobiman,' short for mobile manipulation.
Driver Interface
The current Galaxea R1 driver consists of several components, including actuator interface, sensor interface and external function interface. All the components can be launched by using the following command template.
source ~/work/galaxea/install/setup.bash
roslaunch <Package Name> <Launch File>
# Example
roslaunch HDAS r1.launch
Topic Name | Description | Message Type |
---|---|---|
Arms Driver Interface Torso Driver Interface Chassis Driver Interface IMU Interface BMS Interface Remote Controller Interface |
HDAS | r1.launch |
Camera Interface | signal_camera | signal_camera.launch |
LiDAR Interface | livox_ros_driver2 | msg_MID360.launch |
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 | 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 | 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 | Output | 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, joint4_position] | |
velocity | [joint1_velocity, joint2_velocity, joint3_velocity, joint4_velocity] | |
effort | Not used | |
/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, Joint4_position] | |
v_des | [Joint1_velocity, Joint2_velocity, Joint3_velocity, Joint4_velocity] | |
kp | [Joint1_kp, Joint2_kp, Joint3_kp, Joint4_kp] | |
kd | [Joint1_kd, Joint2_kd, Joint3_kd, Joint4_kd] | |
t_ff | [Joint1_effort, Joint2_effort, Joint3_effort, Joint4_effort] | |
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_chassis_front_left/rgb/compressed | Output | Compressed Image from front_left chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_front_right/rgb/compressed | Output | Compressed Image from front_right chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_left/rgb/compressed | Output | Compressed Image from left chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_right/rgb/compressed | Output | Compressed Image from right chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_rear/rgb/compressed | Output | Compressed Image from rear chassis camera | sensor_msgs::CompressedImage |
/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_head/left_raw/image_raw_color/compressed | Output | Compressed Image from head 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 |
/hdas/camera_head/depth/depth_registered | Output | Depth Image from head 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_chassis_front_left/rgb/compressed | header | Standard header |
format | JPEG | |
data | Image data | |
/hdas/camera_chassis_front_right/rgb/compressed | header | Standard header |
format | JPEG | |
data | Image data | |
/hdas/camera_chassis_left/rgb/compressed | header | Standard header |
format | JPEG | |
data | Image data | |
/hdas/camera_chassis_right/rgb/compressed | header | Standard header |
format | JPEG | |
data | Image data | |
/hdas/camera_chassis_rear/rgb/compressed | header | Standard header |
format | JPEG | |
data | Image data | |
/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_head/left_raw/image_raw_color/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 | |
/hdas/camera_head/depth/depth_registered | header | Standard header |
height | Depend on settings | |
width | Depend on settings | |
encoding | 32FC1 | |
is_bigendian | 0 | |
step | Depend on settings | |
data | Image data |
LiDAR Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/lidar_chassis_left | Output | Lidar pointcloud | sensor_msgs::PointCloud2 |
The specific fields and their detailed descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/hdas/lidar_chassis_left | header | Standard header |
fields | LiDAR data |
IMU Interface
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/hdas/imu_chassis | Output | Imu information | sensor_msgs::Imu |
/hdas/imu_torso | Output | Imu information | 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 |
---|---|---|---|
/hdas/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 |
---|---|---|
/hdas/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
- Joint Control: The node controls each joint of the R1 torso and arms.
- Arm Pose Control: The node controls arm movement to the target end-effector (ee) frame.
- Torso Speed Control: The node controls torso movement to the target floating base frame.
- Chassis Control: The node controls the R1 chassis using vector control, allowing you to send speed commands in three directions simultaneously: x, y, and w.
- Pose Estimation: The node receives joint angle feedback from HDAS and calculates the feedback corresponding to three coordinate systems.
Joint Control
R1 Joint Control is a ROS package for controlling each joint of the R1 torso and arms, with a total of 16 joints. It can be launched using a command.
source ~/work/galaxea/install/setup.bash
roslaunch mobiman r1_jointTrackerdemo.launch
## For R1 Lite
##roslaunch mobiman pi_jointTrackerdemo.launch
This launch file will start with the r1_jointTracker_demo_node
, which is the main node responsible for controlling each joint.
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 |
/motion_target/target_joint_state_torso | Input | Target position of each torso 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 | Input | Control of left arm motor | hdas_msg::motor_control |
/motion_control/control_arm_right | Input | Control of right arm motor | hdas_msg::motor_control |
/motion_control/control_torso | Input | 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_joint_state_arm_left /motion_target/target_joint_state_arm_right |
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. The max speed is below, {3, 3, 3, 5, 5, 5}. The acc & jerk limit is set to 1.5* speed limit. |
|
/motion_target/target_joint_state_torso | position | This is a vector of four elements. 4 joint target positions for each joint. |
velocity | This is a vector of four elements. Standing for four velocity of each joint during movement. The max speed is below, {1.5, 1.5, 1.5, 1.5}. The acc & jerk limit is set to 1.5* speed limit. |
|
/hdas/feedback_arm_left | - | Refer to HDAS msg Description |
/hdas/feedback_arm_right | - | Refer to HDAS msg Description |
/hdas/feedback_torso | - | Refer to HDAS msg Description |
/motion_control/control_arm_left | - | Refer to HDAS msg Description |
/motion_control/control_arm_right | - | Refer to HDAS msg Description |
/motion_control/control_torso | - | Refer to HDAS msg Description |
Extra Features
-
High tracking mode provided for R1.
Note: In high tracking mode, joint level acceleration needs to be planed. If this interface is called to follow a big angle jump, it will trigger motors' protection. The recommended joint accleration and speed are shown below:
Joint | Speed Limit | Acceleration Limit |
---|---|---|
Arm Joint | [3,3,3,5,5,5] rad/s | [5,5,5,5,5,5] rad/s² |
Torso Joint | [1,1,1,1] rad/s | [1.5, 1.5, 1.5, 1.5] rad/s² |
-
Disable Torso Control is also provided, which are
Note: This should be used together with torso speed control interface. The torso speed control interface will call motor control interface directly, so torso joint control should be disabled.
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_left_arm_mpc.launch # MPC control of the left arm end-effector.
roslaunch mobiman r1_right_arm_mpc.launch # MPC control of the right arm end-effector.
Note:
- When the dual-arm pose controller is activated, both the left and right arms will automatically adjust to the position shown in the figure below. Please ensure that the R1 is placed with both arms naturally hanging down to avoid initialization failure due to excessive movement angles.
- The current end-effector pose control's relative pose is the transformation of the gripper_link relative to torso_link4 in the URDF. For the left arm, this refers to the relative relationship between the left_gripper_link coordinate frame and torso_link4 coordinate frame, including offsets in x, y, and z, as shown in the right figure below, transforming as well as the rotational offsets corresponding to the orientation.
The interface is shown below.
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/pose_ee_arm_left | Input | Target pose of left arm end-effector frame | Geometry_msgs::PoseStamped |
/motion_target/pose_ee_arm_right | Input | Target pose of right arm end-effector frame | 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/pose_ee_arm_left | 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 /hdas/feedback_arm_right |
- | Refer to HDAS msg |
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_hard.launch
## Note, this command cannot be executed simultaneously with joint_tracker.
## If you want to use joint tracker simultaneously, use joint_tracker_disable_torso instead.
## Detail information can be found at joint Control Page
This node represents the velocity control of torso_link3 relative to base_link, with its direction aligned with the base_link frame.
- v_x represents the velocity in the x-direction of the torso frame relative to base_link (maximum speed is 0.2 m/s). A positive value indicates forward movement based on base_link, while a negative value indicates backward movement.
- v_z represents the velocity in the z-direction of the torso frame relative to base_link (maximum speed is 0.2 m/s). A positive value suggests upward movement based on base_link, while a negative value indicates downward movement.
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 |
/motion_target/target_speed_torso | Input | Target speed of floating base frame | Geometry_msgs::Twist::ConstPtr |
/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 |
target_speed.v_z = msg->linear.z; | Linear velocity in the z direction of the torso in Cartesian space | |
/hdas/feedback_torso | - | Refer to HDAS msg |
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.
This launch file will bring up two nodes: chassis_control_node and r1_control_manager. The chassis_control_node
is responsible for R1 chassis speed control.
The interface is shown below:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_target/target_speed_chassis | Input | Issue the target speed of chassis, consisting of three directions, x, y and w | geometry_msgs::Twist |
/motion_target/chassis_acc_limit | Input | Issuing the chassis control acceleration limit, the max value for x, y, w is 2.5, 1.0, 1.0. | geometry_msgs::Twist |
/motion_target/brake_mode | Input | Issuing whether the chassis is entering brake mode. If in brake mode, when speed is 0, the chassis will lock itself by turning the wheel to a certain degree. | std_msgs::Bool |
/hdas/feedback_chassis | Input | R1 chassis control subscribes to this topic and controls the chassis the target speed | sensor_msgs::JointState |
/motion_control/control_chassis | Output | R1 chassis control publishes this topic to control the 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_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 |
Pose Estimation
In the chassis control launch file, a node called eepose_pub_node
will also be launched. This node receives joint angle feedback from HDAS and calculates the feedback corresponding to three coordinate systems. The eepose_pub_node
defines three coordinate frames: the Base Link Frame (left), the Floating Base Frame (middle), and the End-Effector Pose Frame (right).
The interface is shown below:
Topic Name | I/O | Description | Message Type |
---|---|---|---|
/motion_control/pose_ee_arm_left | Output | Transform from floating base to left end-effector pose | Geometry_msgs::PoseStamped |
/motion_control/pose_ee_arm_right | Output | Transform from floating base to right end-effector pose | Geometry_msgs::PoseStamped |
/motion_control/pose_floating_base | Output | Transform from base-link to floating base | Geometry_msgs::PoseStamped |
/hdas/feedback_arm_right | Input | Feedback of left arm motor | Sensor_msgs::JointState |
/hdas/feedback_arm_left | Input | Feedback of left arm motor | Sensor_msgs::JointState |
/hdas/feedback_torso | Input | Feedback of torso motor | Sensor_msgs::JointState |
The specific fields and their detailed descriptions for the above topic are shown in the table below:
Topic Name | Field | Description |
---|---|---|
/motion_control/pose_ee_arm_right /motion_control/pose_ee_arm_left /motion_control/pose_floating_base |
position | This is the translation information in X, Y, Z position |
pose.position.x | Shift in the X direction | |
pose.position.y | Shift in the Y direction | |
pose.position.z | Shift in the Z direction | orientation | This is orientation information |
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion |