A1XY Software Introduction (ROS2)
Environment Dependencies
- Operating System Dependency: Ubuntu 22.04 LTS
- Middleware Dependency: ROS Humble
Software Changelog
Visit Galaxea A1XY Software Changelog to view the latest SDK packages and update information.
First Operation Guide
Visit Galaxea A1XY Unboxing and Startup Guide and follow the instructions to operate the Galaxea A1XY.
SDK Startup
Currently supports separate startup method to launch the software interface.
Operating instructions are as follows:
| Module Name | Included Components | Path | Launch File |
|---|---|---|---|
| HDAS | Arms Driver |
{sdk_path}/install/HDAS/share/HDAS/launch | a1xy.py |
| mobiman | Arm Control Gripper Control End Effector Pose Control |
{sdk_path}/install/mobiman/share/mobiman/launch/simpleExample/A1X | A1x_jointTrackerdemo_launch.py A1y_jointTrackerdemo_launch.py A1xy_gripperController_launch.py A1x_arm_relaxed_ik_launch.py A1y_arm_relaxed_ik_launch.py |
Separate Startup
All nodes can be launched through the following command template, configuration method is as follows:
Note: Before starting nodes, please confirm that the CAN driver has been properly configured.
sudo ip link set can0 type can bitrate 1000000 sample-point 0.875 dbitrate 5000000 fd on dsample-point 0.875
sudo ip link set up can0
# If you encounter the error "RTNETLINK answers: Device or resource busy", it usually means that the device you are trying to configure (such as a network interface or CAN transceiver) has already been configured and is running.
Node startup commands are as follows: - Environment variable setup (must be configured before running programs in each terminal)
- Arm driver (must be started before using all motion control algorithms) - Joint control#A1X
ros2 launch mobiman A1x_jointTrackerdemo_launch.py
#A1Y
ros2 launch mobiman A1y_jointTrackerdemo_launch.py
#A1X
ros2 launch mobiman A1x_arm_relaxed_ik_launch.py
#A1Y
ros2 launch mobiman A1y_arm_relaxed_ik_launch.py
Software Interfaces
Driver Interface
| Topic Name | I/O | Description | Message Type |
|---|---|---|---|
| /hdas/feedback_arm | Output | Joint feedback position/velocity/torque | sensor_msgs::msg::JointState |
| /hdas/feedback_gripper | Output | End-effector gripper travel feedback | sensor_msgs::msg::JointState |
| /hdas/feedback_status_arm | Output | Joint status feedback | hdas_msg::msg::FeedbackStatus |
| /motion_control/control_arm | Input | Joint motor control interface | hdas_msg::msg::MotorControl |
| hdas_msg/msg/MotorControl | Input | End-effector gripper motor control interface | hdas_msg::msg::MotorControl |
| /motion_control/position_control_gripper | Input | End-effector gripper travel control interface | std_msgs::msg::Float32 |
| /hdas/function_frame_arm | Input | Arm function frame | hdas_msg::srv::FunctionFrame |
The specific fields and detailed descriptions of the above topics are shown in the table below:
| Topic Name | Field | Description |
|---|---|---|
| /hdas/feedback_arm | header | Standard message header |
| position | [Joint 1 motor position feedback, Joint 2 motor position feedback, Joint 3 motor position feedback, Joint 4 motor position feedback, Joint 5 motor position feedback, Joint 6 motor position feedback, Gripper motor position feedback] | |
| velocity | [Joint 1 motor velocity feedback, Joint 2 motor velocity feedback, Joint 3 motor velocity feedback, Joint 4 motor velocity feedback, Joint 5 motor velocity feedback, Joint 6 motor velocity feedback, Gripper motor velocity feedback] | |
| effort | [Joint 1 motor torque feedback, Joint 2 motor torque feedback, Joint 3 motor torque feedback, Joint 4 motor torque feedback, Joint 5 motor torque feedback, Joint 6 motor torque feedback, Gripper motor torque feedback] | |
| /hdas/feedback_gripper | header | Standard message header |
| position | [Gripper travel feedback] | |
| velocity | Not used | |
| effort | Not used | |
| /hdas/feedback_status_arm | header | Standard message header |
| name_id | Joint name | |
| errors | Contains error codes and descriptions | |
| /motion_control/control_arm | header | Standard message header |
| name | - | |
| p_des | [Joint 1 target position, Joint 2 target position, Joint 3 target position, Joint 4 target position, Joint 5 target position, Joint 6 target position] | |
| v_des | [Joint 1 target velocity, Joint 2 target velocity, Joint 3 target velocity, Joint 4 target velocity, Joint 5 target velocity, Joint 6 target velocity] | |
| kp | [Joint 1 target Kp, Joint 2 target Kp, Joint 3 target Kp, Joint 4 target Kp, Joint 5 target Kp, Joint 6 target Kp] | |
| kd | [Joint 1 target Kd, Joint 2 target Kd, Joint 3 target Kd, Joint 4 target Kd, Joint 5 target Kd, Joint 6 target Kd] | |
| t_ff | [Joint 1 target torque, Joint 2 target torque, Joint 3 target torque, Joint 4 target torque, Joint 5 target torque, Joint 6 target torque] | |
| mode | - | |
| hdas_msg/msg/MotorControl | header | Standard message header |
| name | - | |
| p_des | [Gripper motor target position] | |
| v_des | [Gripper motor target velocity] | |
| kp | [Gripper motor target Kp] | |
| kd | [Gripper motor target Kd] | |
| t_ff | [Gripper motor target torque] | |
| mode | - | |
| /motion_control/position_control_gripper | header | Standard message header |
| data | Target gripper travel, control range (0 to 100) mm | |
| /hdas/function_frame_arm | command | 1: Enable 2: Disable 3: Full arm calibration 4: Clear errors 5: MIT mode (embedded firmware version needs to be greater than 2.1.3) 6: PID mode (embedded firmware version needs to be greater than 2.1.3) |
Motion Control Interface
Joint Control
Interface information is as follows:
| Topic Name | I/O | Description | Message Type |
|---|---|---|---|
| /hdas/feedback_arm | Output | Arm joint feedback | hdas_msg::msg::MotorControl |
| /motion_control/control_arm | Input | Arm motor control | hdas_msg::msg::MotorControl |
| /motion_target/target_joint_state_arm | Input | Target positions of each joint | sensor_msgs::msg::JointState |
The specific fields and detailed descriptions of the above topics are shown in the table below:
| Topic Name | Field | Description |
|---|---|---|
| /motion_target/target_joint_state_arm | position | This is a vector containing six elements, representing the six target positions of each joint. |
| velocity | This is a vector containing six elements, representing the maximum velocity of each joint during movement. Maximum velocities are as follows: {3, 3, 3, 5, 5, 5, 5}. Acceleration and jerk limits are set to 1.5 times the velocity limit. | |
| /hdas/feedback_arm | - | Please refer to the arm driver interface |
| /motion_control/control_arm | - | Please refer to the arm driver interface |
Arm Pose Control
- The current end-effector pose control uses relative pose transformation from gripper_link to base_link in the URDF. Taking A1X as an example, the figure below shows the relative relationship between the gripper_link coordinate system and the base_link coordinate system, including the offsets in x, y, z directions and the rotational offsets corresponding to orientation.

The interface is as follows:
| Topic Name | I/O | Description | Message Type |
|---|---|---|---|
| /hdas/pose_ee_arm | Output | Actual end-effector pose | geometry_msgs::msg::PoseStamped |
| /hdas/feedback_arm | Output | Arm joint feedback | hdas_msg::msg::MotorControl |
| /motion_target/target_joint_state_arm | Input | Arm joint targets | sensor_msgs::msg::JointState |
| /motion_control/pose_ee_arm | Input | Target arm end-effector pose | geometry_msgs::PoseStamped |
The specific fields and detailed descriptions of the above topics are shown in the table below:
| Topic Name | Field | Description |
|---|---|---|
| /motion_target/target_pose_arm | 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 | - | Please refer to the arm driver interface |
| /motion_target/target_joint_state_arm | - | Please refer to the joint control interface |
Gripper Control
Interface information is as follows:
| Topic Name | I/O | Description | Message Type |
|---|---|---|---|
| /motion_target/target_position_gripper | Input | Gripper target position | sensor_msgs::msg::JointState |
| hdas_msg/msg/MotorControl | Input | Gripper motor control | sensor_msgs::msg::JointState |
The specific fields and detailed descriptions of the above topics are shown in the table below:
| Topic Name | Field | Description |
|---|---|---|
| /motion_target/target_position_gripper | position | Represents the target position of the gripper, [0, 100], 0 for fully closed, 100 for fully open. |
| hdas_msg/msg/MotorControl | - | Please refer to the driver interface |
ß