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.
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/motor_state | Chassis motion status feedback | chassis_msg/DrivetrainStamped |
Topic Name | Field | Description |
---|---|---|
/hdas/motor_state | header | Standard ROS header |
.steering_angle_fl | Front wheel left wheel steering angle degrees | |
.steering_angle_fr | Front wheel right wheel steering angle degrees | |
.steering_angle_rl | Rear wheel left wheel steering angle degrees | |
.steering_angle_rr | Rear wheel right wheel steering angle degrees | |
.drive_speed_fl | Front wheel left wheel linear speed m/s | |
.drive_speed_fr | Front wheel right wheel linear speed m/s | |
.drive_speed_rl | Rear wheel left wheel linear speed m/s | |
.drive_speed_rr | Rear wheel right wheel linear speed m/s | |
.drive_angular_speed_fl | Front wheel left wheel angular speed rad/s | |
.drive_angular_speed_fr | Front wheel right wheel angular speed rad/s | |
.drive_angular_speed_rl | Rear wheel left wheel angular speed rad/s | |
.drive_angular_speed_rr | Rear wheel right wheel angular speed rad/s | |
.motion_mode | N/A | |
mode | Control mode | |
/gripper_joint_command | header | Standard header |
gripper_force | Gripper force |
Arms Driver Interface
This interface is used for 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 |
---|---|---|
/left_arm/joint_states/right_arm/joint_states | Arm joint status feedback | sensor_msgs/JointState |
/left_arm/arm_status/right_arm/arm_status | Arm motor status feedback | signal_arm/status_stamped |
/left_arm/arm_joint_command/right_arm/arm_joint_command | Arm control interface | signal_arm/arm_control |
/left_arm/gripper_joint_command/right_arm/gripper_joint_command | Gripper force control interface | signal_arm/gripper_joint_command |
Topic Name | Field | Description |
---|---|---|
/left_arm/joint_states/right_arm/joint_states | Header | Standard header |
name | Name of each arm joint | |
position | Position of each arm joint | |
velocity | Velocity of each arm joint | |
/left_arm/arm_status/right_arm/arm_status | header | Standard header |
status.name | Name of each status | |
status.motor_errors | Errors of each status | |
/left_arm/arm_joint_command/right_arm/arm_joint_command | header | Standard header |
p_des | Position command of the arm | |
v_des | Velocity command of the arm | |
t_ff | Torque command of the arm | |
kp | Proportion coefficient of position | |
kd | Differential coefficient of position | |
/left_arm/gripper_joint_command/right_arm/gripper_joint_command | header | Standard header |
gripper_force | Gripper force |
Diagnostic Trouble Code
DTC is used to feedback the error information of the MCU and the driver, and can be used to view the real-time status of each motor and the running status of the driver. The following is a detailed description of each fault code and its corresponding status.
DTC | Status |
---|---|
0 | Disabled |
1 | Disabled |
2 | Motor Disconnected |
3 | Position Jump |
4 | Continuous High Current |
5 | Excessive Torque |
6 | ECU -> ACU Timeout |
7 | Position Limit Exceeded |
8 | Speed Limit Exceeded |
9 | Torque Limit Exceeded |
10 | Overpressure |
11 | Low pressure |
12 | Overcurrent |
13 | MOS Overtemperature |
14 | Motor Winding Overtemperature |
15 | Communication loss |
16 | Overload |
17 | Serial Connection Disconnected (No Device File) |
18 | Device File Connected, No Messages |
19 | Serial Read/Write Failure |
20 | Feedback Reception Overflow |
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 |
---|---|---|
/torso_feedback | Joint status feedback of the torso motor | sensor_msgs/JointState |
/torso_control | Torso motor status feedback | signal_arm/arm_control |
Topic Name | Field | Description |
---|---|---|
/torso_feedback | Header | Standard header |
name | Name of each torso joint | |
position | Position of each torso joint | |
velocity | Velocity of each torso joint | |
effort | N/A | |
/torso_control | header | Standard header |
p_des | Position command of torso | |
v_des | Velocity command of torso | |
t_ff | N/A | |
kp | N/A | |
kd | N/A |
Operation Control Interface
The current Galaxea R1 operation and control interface is mainly composed of three parts: the chassis, the left and right arms, and the torso. Each drive has different motion interface exposure. The interfaces provided by these drivers are in the form of ROS topics as described below and available to users.
Chassis Control Interface
The chassis control interface can be used to command the chassis to move at the target speed, which includes the combination of X, Y, and Yaw Rate:
Topic Name | Description | Message Type |
---|---|---|
/cmd_vel | Issuing the chassis control signal | geometry_msgs/Twist |
Topic Name | Field | Description |
---|---|---|
/cmd_vel | header | Standard ROS header |
linear | Control of linear speed | |
.x | Linear speed of x, range (-1 to 1) m/s | |
.y | Linear speed of y, range (-1 to 1) m/s | |
angular | Control of yaw rate | |
.z | Control of angular speed, -1 to 1 rad/s |
Arms Control Interface
Joint Position Movement Interface
joint_move
is a ROS package for the single-joint control of robot arms and is used to move each joint from the current position to the target position. The maximum speed and maximum acceleration can be specified; if not, the default maximum speed, 20 rad/s, and the default maximum acceleration, 20 rad/s², will be used for planning.
The following are detailed descriptions of each topic and its related message types:
Topic Name | Description | Message Type |
---|---|---|
/left_arm/arm_joint_target_position/right_arm/arm_joint_target_position | Target position and pose of each arm joint | Sensor_msgs/JointState |
Topic Name | Field | Description |
---|---|---|
/left_arm/arm_joint_target_position/right_arm/arm_joint_target_position | Header | Standard header |
name | Name of each arm joint | |
position | Position of each arm joint | |
velocity | Velocity of each arm joint | |
effort | Torque of each arm joints |
End Pose Movement Interface
eef_move
is a ROS package for the end control of robot arms and is used to move the end of the robot arm to the target position with the target pose.
Note: If the given position and pose are unreachable, the robot arm will be as close to the target position and pose as possible through the optimization function. When setting the targets, the weight of the position gap is twice the weight of the pose gap.
Topic Name | Description | Message Type |
---|---|---|
/left_arm/arm_target_pose/right_arm/arm_target_pose | Target positions of the end of the robot arm | Geometry_msgs::PoseStamped |
Topic Name | Field | Description |
---|---|---|
/left_arm/arm_target_pose/right_arm/arm_target_pose | header | Standard header |
pose.position.x | Shift in the X direction | |
pose.position.y | Shift in the Y direction | |
pose.position.z | Shift in the Z direction | |
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion |
End Trajectory Movement interface
eef_follow
is a ROS package for the end control of robot arms and is used to move the end following the target trajectory to the target position.
Note: If the given position and pose are unreachable, the robot arm will be as close to the target position and pose as possible through the optimization function. When setting the targets, the weight of the position gap is twice the weight of the pose gap.
Topic Name | Description | Message Type |
---|---|---|
/left_arm/arm_target_trajectory/right_arm/arm_target_trajectory | Target trajectory of the end of arms | Geometry_msgs::PoseArray |
Topic Name | Field | Description |
---|---|---|
/left_arm/arm_target_trajectory/right_arm/arm_target_trajectory | header | Standard header |
posesgeometry_msgs/Pose[] | Description of pose in the BaseLink coordinate system, where each pose has a fixed time interval of 0.1s. | |
pose.position.x | Shift in the X direction | |
pose.position.y | Shift in the Y direction | |
pose.position.z | Shift in the Z direction | |
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion |
Torso Control Interface
The coordinate system is defined as follows:
-
The coordinate axes represent the end of the torso.
-
The red, green, and blue lines represent the X, Y, and Z axes, respectively.
Torso Speed Control Interface
torso_control
is a ROS package for the end control of the torso and is used to move the end of the torso at a target speed.
Topic Name | Description | Message Type |
---|---|---|
/target_torso_speed | Issuing the torso control signal | geometry_msgs/Twist |
Topic Name | Field | Description |
---|---|---|
/cmd_vel | header | Standard ROS header |
linear | control of linear speed | |
.z | linear_speed of z, range (-0.2 to 0.2) m/s | |
angular | control of yaw rate | |
.x | control of angular speed in pitch direction, -0.5 - 0.5 rad/s | |
.y | control of angular speed in pitch direction, -0.5 - 0.5 rad/s |
Torso Pose Control Interface
torso_control
is a ROS package for the end control of the torso and is used to move the pose of the torso to the target height and to the corresponding pitch and yaw.
This pose is subject to certain constraints, as described below.
Topic Name | Description | Message Type |
---|---|---|
/torso_target_pose | Target pose of end arm joint | Geometry_msgs::PoseStamped |
Topic Name | Field | Description |
---|---|---|
/torso_target_pose | 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 | The constraint of -Pitch satisfies sin(pitch) (-x/0.32, (0.25-x)/0.32). The constraint of -Yaw is satisfied with (-3.05-3.05) | |
pose.orientation.x | Orientation quaternion | |
pose.orientation.y | Orientation quaternion | |
pose.orientation.z | Orientation quaternion | |
pose.orientation.w | Orientation quaternion |
Torso Re-calibration
Disable the Auto-start Torso Control Interface
Before performing zero-point calibration, please first disable the auto-start torso control algorithm.
ps aux | grep torso_control
### Find the Torso Control Node PID First
kill -9 (PID)
### PID is the found PID
Adjust Single-joint Position Control Interface
Please proceed with caution during the adjustment and ensure that the delta position of each joint is less than 10 degrees each time. Adjust each Torso joint one at a time, and hold the robot during the adjustment to prevent any potential tipping.
rostopic echo /torso_feedback
## Find Current Torso Feedback Position First, p1, p2, p3, p4 for the current degree
source ${SDK_PATH}/install/setup.bash
rostopic pub /torso_control signal_arm/arm_control "header:
seq: 0
stamp: {secs: 0, nsecs: 0}
frame_id: ''
p_des: [${p1+delta_p1}, ${p2+delta_p2}, ${p3+delta_p3}, ${p4+delta_p4}]
v_des: [0.1, 0.1, 0.1, 0.1]
kp: [0]
kd: [0]
t_ff: [0]
mode: 0"
### delta_pi is the delta degree wanna each joint to move.
### delta_p1 > 0 -> T1 Moves Forward
### delta_p2 > 0 -> T2 Moves Forward
### delta_p3 > 0 -> T3 Moves Backward
### delta_p4 > 0 -> T4 Moves anticlockwise
Rosservice Call
Importance: Hold the robot by hand.
Once near the zero-point, you can use the following interface for calibration. The zero-point posture is as shown. When issuing commands, the motor brakes will briefly release, so please hold the robot to prevent calibration errors.
rosservice call /torso_node/function_frame "0x03"
- Repower the system and check if it is at zero.
rostopic echo /torso_feedback
### Check Current Torso Feedback Position Check whether calibration succeed