Galaxea R1 Software Guide
Software Dependency
- Ubuntu 20.04 LTS
- ROS Noetic
Installation
The SDK does not require recompilation. Please refer to the contents below.
First Move
Visit the page R1_Demo and get started to operate R1 following the instructions.
Software Interface
In this chapter, we describe the various control and status feedback interfaces for Galaxea R1, to help users better understand how to communicate and control the arm through the ROS package.
Driver Interface
The current Galaxea R1 driver is mainly composed of three parts, including four independent ROS nodes: the drivers of the chassis, the left and right arms, and the torso. The interfaces provided by these drivers are in the form of ROS topics, as described below.
Please type the following command to launch the corresponding driver:
-
Chassis, Arms, Torso, IMU, BMS, Remote Controller
roslaunch HDAS hdas.launch
-
Chassis Camera
sudo chmod 777 /dev/ttyTHS1 roslaunch signal_camera signal_camera.launch
-
Wrist Camera
roslaunch realsense_camera rs_multiple_devices.launch
-
LiDAR
roslaunch livox_ros_driver2 msg_MID360.launch
Chassis Driver Interface
This interface is used for the chassis status feedback ROS package. The package defines multiple topics for posting the status of multiple motors in the chassis. The following are detailed descriptions of each topic and its related message types:
Topic Name | Description | Message Type |
---|---|---|
/hdas/feedback_chassis | Feedback of chassis | sensor_msgs::JointState |
/hdas/feedback_status_chassis | Status of chassis | hdas_msg::feedback_status |
/motion_control/control_chassis | Motor control of chassis | hdas_msg::motor_control |
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_arm_right | 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 | - |
Arms Driver Interface
This interface is used for robot arm control and status feedback ROS package. The package defines multiple topics for publishing and subscribing to the status of the robot arm, control commands, and associated error code information. The following are detailed descriptions of each topic and its related message types:
Topic Name | Description | Message Type |
---|---|---|
/hdas/feedback_arm_left | Joint feedback of left arm | sensor_msgs::JointState |
/hdas/feedback_arm_right | Joint feedback of right arm | sensor_msgs::JointState |
/hdas/feedback_gripper_left | Gripper stroke of left gripper | sensor_msgs::JointState |
/hdas/feedback_gripper_right | Gripper stroke of right gripper | sensor_msgs::JointState |
/hdas/feedback_status_arm_left | Status of left arm | hdas_msg::feedback_status |
/hdas/feedback_status_arm_right | Status of right arm | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_left | Status of left gripper | hdas_msg::feedback_status |
/hdas/feedback_status_gripper_right | Status of right gripper | hdas_msg::feedback_status |
/motion_control/control_arm_left | Motor control of left arm | hdas_msg::motor_control |
/motion_control/control_arm_right | Motor control of right arm | hdas_msg::motor_control |
/motion_control/control_gripper_left | Motor control of left gripper | hdas_msg::motor_control |
/motion_control/control_gripper_right | Motor control of right gripper | hdas_msg::motor_control |
/motion_control/position_control_gripper_left | Position control of left gripper | std_msgs::Float32 |
/motion_control/position_control_gripper_right | Position control of right gripper | std_msgs::Float32 |
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 torso control and status feedback ROS package. The package defines multiple topics for publishing and subscribing to the status of torso motors and control commands. The following are detailed descriptions of each topic and its related message types:
Topic Name | ">Description | ">Message Type |
---|---|---|
/hdas/feedback_torso | Joint feedback of torso | sensor_msgs/JointState |
/hdas/feedback_status_torso | Torso motor status feedback | hdas_msg::feedback_status |
/motion_control/control_torso | Motor control of torso | hdas_msg::motor_control |
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_arm_left | 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] | |
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 | - |
Camera Interface
Topic Name | Description | Message Type |
---|---|---|
/hdas/camera_chassis_front_left/rgb/compressed | Compressed Image from front_left chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_front_right/rgb/compressed | Compressed Image from front_right chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_left/rgb/compressed | Compressed Image from left chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_right/rgb/compressed | Compressed Image from right chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_chassis_rear/rgb/compressed | Compressed Image from rear chassis camera | sensor_msgs::CompressedImage |
/hdas/camera_wrist_left/color/image_raw/compressed | Compressed Image from left wrist camera | sensor_msgs::CompressedImage |
/hdas/camera_wrist_right/color/image_raw/compressed | Compressed Image from right wrist camera | sensor_msgs::CompressedImage |
/hdas/camera_head/left_raw/image_raw_color/compressed | Compressed Image from head camera | sensor_msgs::CompressedImage |
/hdas/camera_wrist_left/aligned_depth_to_color/image_raw | Depth Image from left wrist camera | sensor_msgs::Image |
/hdas/camera_wrist_right/aligned_depth_to_color/image_raw | Depth Image from right wrist camera | sensor_msgs::Image |
/hdas/camera_head/depth/depth_registered | Depth Image from head camera | sensor_msgs::Image |
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 setttings | |
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 setttings | |
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 setttings | |
data | Image data |
LiDAR Interface
Topic Name | Description | Message Type |
---|---|---|
/hdas/lidar_chassis_left | Lidar pointcloud | sensor_msgs::PointCloud2 |
Topic Name | Field | Description |
---|---|---|
/hdas/lidar_chassis_left | header | Standard header |
fields | LiDAR data |
IMU Interface
Topic Name | Description | Message Type |
---|---|---|
/hdas/imu_chassis | Imu information | sensor_msgs::Imu |
/hdas/imu_torso | Imu information | sensor_msgs::Imu |
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 | Description | Message Type |
---|---|---|
/hdas/bms | Battery BMS information | hdas_msg::bms |
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 | Description | Message Type |
---|---|---|
/hdas/controller | Signal from remote controler | hdas_msg::controller_signal_stamped |
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 | - |
Control Interface
The current Galaxea R1 control diagram is shown as below, consisting of mainly 5 parts, R1 Pose Feedback, R1 Joint Control, R1 Chassis Control, R1 Arm Pose Control, and R1 Torso Pose Control. Details will be illustrated in below chapters. The whole package name is "mobiman", short for mobile manipulation.
R1 Chassis Control
R1 Chassis Control is the node which can control R1 chassis by vector control, which means you can send speed in three directions at the same time, which are direction x, direction y, and direction yaw(w). It can be brought up by command.
roslaunch mobiman r1_chassis_control.launch
This launch file will bring up two nodes, which are chassis_control_node and r1_control_manager. Chassis_control_node is the main function for R1 chassis speed control, the interface is shown as blow.
Topic Name | Description | Message Type |
---|---|---|
/motion_target/target_speed_chassis | Issue the target speed of chassis, consisting of three directions, x, y and w | geometry_msgs::Twist |
/motion_target/chassis_acc_limit | 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 | 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 | R1 chassis control subscribes to this topic and controls the chassis the target speed | sensor_msgs::JointState |
/motion_control/control_chassis | R1 chassis control publishes this topic to control the motor | hdas_msg::motor_control |
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 |
R1 Joint Control
R1 Chassis Control is the node which can control R1 each joint of torso, arms, 16 joints in total. It can be brought up by command.
roslaunch mobiman r1_jointTrackerdemo.launch
This launch file will bring up robot state publisher, eepose_pub_node
and r1_jointTracker_demo_node
. Robot state publisher is a ros-provided tool, providing tf for RVIZ according to /joint_states.
andr1_jointTracker_demo_node
is the main function node to control each joint.
r1_jointTracker_demo_node
interface is shown below.
Topic Name | Description | Message Type |
---|---|---|
/motion_target/target_joint_state_arm_left | Target position of each left arm joint | sensor_msgs::JointState |
/motion_target/target_joint_state_arm_right | Target position of each right arm joint | sensor_msgs::JointState |
/motion_target/target_joint_state_torso | Target position of each torso joint | sensor_msgs::JointState |
/hdas/feedback_arm_left | Feedback of left arm motor | sensor_msgs::JointState |
/hdas/feedback_arm_right | Feedback of right arm motor | sensor_msgs::JointState |
/hdas/feedback_torso | Feedback of torso motor | sensor_msgs::JointState |
/motion_control/control_arm_left | Control of left arm motor | hdas_msg::motor_control |
/motion_control/control_arm_right | Control of right arm motor | hdas_msg::motor_control |
/motion_control/control_torso | Control of torso motor | hdas_msg::motor_control |
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 |
eepose_pub_node
defines two frames, which are base link frame (Left), floating base frame (Middle) and ee pose frame(Right).
Topic Name | Description | Message Type |
---|---|---|
/motion_control/pose_ee_arm_left | Transform from floating base to left EE pose | geometry_msgs::PoseStamped |
/motion_control/pose_ee_arm_right | Transform from floating base to right EE pose | geometry_msgs::PoseStamped |
/motion_control/pose_floating_base | Transform from base-link to floating base | geometry_msgs::PoseStamped |
Topic Name | Field | Description |
---|---|---|
/motion_control/pose_floating_base /motion_control/pose_ee_arm_right /motion_control/pose_ee_arm_left |
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 |
R1 Arm Pose Control - Coming Soon
R1 Arm Pose Control is a ROS Package for controlling arm movement to target arm ee frame, and it can be brought up by
roslaunch mobiman r1_arm_pose_control.launch
The interface is shown below.
Topic Name | Description | Message Type |
---|---|---|
/motion_target/pose_ee_arm_left /motion_target/pose_ee_arm_right |
Target pose of arm ee frame | Geometry_msgs::PoseStamped |
/motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
Target Joint position of each joint of arm | Sensor_msgs::JointState |
/hdas/feedback_arm_left /hdas/feedback_arm_right |
Feedback of arm joint | Sensor_msgs::JointState |
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 | |
/motion_target/target_joint_state_arm_left /motion_target/target_joint_state_arm_right |
- | Refer to R1 Joint Control Chapter |
/hdas/feedback_arm_left /hdas/feedback_arm_right |
- | Refer to HDAS msg |
R1 Torso Pose Control - Coming Soon
R1 Torso Pose Control is a ROS Package for controlling torso movement to target floating base frame. It can be brought up by
roslaunch mobiman r1_torso_pos_control.launch
This pose is subject to certain constraints, as described below.
Topic Name | Description | Message Type |
---|---|---|
/motion_target/target_pose_torso | Target pose of floating base frame | geometry_msgs::PoseStamped |
/motion_target/target_joint_state_torso | Target joint position of each joint of torso | sensor_msgs::JointState |
/hdas/feedback_torso | Feedback of torso joint | sensor_msgs::JointState |
Topic Name | Field | Description |
---|---|---|
/motion_target/pose_ee_arm_left | header | Standard Header |
pose.position.x | Shift in x-direction in the range of (0,0.25) | |
pose.position.z | Shift in z-direction in the range of (0,1) | |
pose.orientation.x | The constraint of -Pitch satisfies sin(pitch) (-x/0.32, (0.25-x)/0.32). The constraint of -Yaw is satisfied with ±3.05. |
|
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion | |
/motion_target/target_joint_state_torso | - | Refer to R1 Joint Control Chapter |
/hdas/feedback_torso | - | Refer to HDAS msg |