Skip to content

A1XY Software Introduction

Software Dependency

  1. OS Dependency: Ubuntu 20.04 LTS
  2. Middleware Dependency: ROS Noetic

Obtain Resources

Click any of the following links to obtain A1XY SDK.

This is the initial software release for the A1XY robot arm. For subsequent version updates, you can refer to the A1XY Software Version Cahngelog to obtain the latest SDK package and update information.

Click the following links to obtain A1XY URDF.

Start SDK

Visit the A1XY Startup and Demo Guide.

Demo

Visit the A1XY Demo Guide.

Software Interface

Driver Interface

Topic Name I/O Desciption Message Type
/hdas/feedback_arm Output Position, speed, and torque feedback for each joint sensor_msgs::JointState
/hdas/feedback_gripper Output End-effector gripper stroke feedback sensor_msgs::JointState
/hdas/feedback_status Output Status feedback for each joint hdas_msg::feedback_status
/motion_control/control_arm Input Motor control interface for each joint hdas_msg::motor_control
/motion_control/control_gripper Input End-effector gripper motor control interface hdas_msg::motor_control
/motion_control/position_control_gripper Input End-effector gripper stroke control interface std_msgs::Float32
/arm_node/function_frame_arm Input Robot arm function frame hdas_msg/FunctionFrame

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Desciption
/hdas/feedback_arm 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 header Standard Header
position [gripper_stroke]
velocity Not used
effort Not used
/hdas/feedback_status_arm header Standard Header
name_id Joint name
errors Contains error code and desciption
/motion_control/control_arm 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 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 header Standard Header
data desired_gripper_stroke, range (0 to 100) mm
/arm_node/function_frame_arm command 1: Enable
2: Disable
3: Whole arm calibration
4: Clear error

Motion Control Interface

Joint Control

source A1XY_workspace/install/setup.bash

# Depending on the product model, select one of the following startup methods:
roslaunch mobiman a1x_jointTrackerdemo.launch
roslaunch mobiman a1y_jointTrackerdemo.launch

This launch file will start with the a1_xy_jointTracker_demo_node, which is the main node responsible for controlling each joint.

The interface is shown below:

Topic Name I/O Desciption Message Type
/hdas/feedback_arm Output Arm joint feedback Hdas_msg::motor_control
/motion_control/control_arm Input Arm motor control Sensor_msgs::JointState
/motion_target/target_joint_state_arm Input Target position of each joint sensor_msgs::JointState

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Desciption
/motion_target/target_joint_state_arm position This is a vector with six elements representing the target positions of each joint.This is a vector with six elements representing the target positions of each joint.
velocity This is a vector with six elements representing the maximum velocity of each joint during motion. The maximum velocities are as follows: {3, 3, 3, 5, 5, 5, 5}. The acceleration and jerk limits are set to 1.5 times the velocity limits.
/hdas/feedback_arm - Please refer to the arm diver interface.
/motion_control/control_arm - Please refer to the arm diver interface.

Arm Pose Control

A1XY Arm Pose Control is a ROS package designed to control the movement of the robotic arm to the target end-effector (ee) coordinate frame. It primarily includes a launch file that can be started using the following command:

source A1XY_workspace/install/setup.bash

# Depending on the product model, select one of the following startup methods:
roslaunch mobiman a1x_arm_relaxed_ik.launch
roslaunch mobiman a1y_arm_relaxed_ik.launch

Note:

  • When the dual-arm pose controller is started, the joint control node must also be launched. This is because the pose controller continuously calculates the target joint angles based on the desired end-effector (ee) pose and sends these target angles to the /motion_target/target_joint_state_arm topic.

    source A1XY_workspace/install/setup.bash
    
    # Depending on the product model, select one of the following startup methods:
    roslaunch mobiman a1x_jointTrackerdemo.launch
    roslaunch mobiman a1y_jointTrackerdemo.launch
    
  • The relative pose of the current end-effector pose control is the transformation of the gripper_link relative to the base_link in the URDF. Taking the A1X as an example, the following figure shows the relative relationship of the gripper_link coordinate system to the base_link coordinate system, including the offsets in x, y, and z, as well as the rotational offsets corresponding to the orientation.

A1XY_arm_pose_cn

The interface is shown below:

Topic Name I/O Desciption Message Type
/hdas/pose_ee_arm Output Actual pose of ee Hdas_msg::motor_control
/hdas/feedback_arm Output Arm joint feedback Hdas_msg::motor_control
/motion_target/target_joint_state_arm Input Target of Arm joint Sensor_msgs::JointState
/motion_target/pose_ee_arm Input Target pose of ee Geometry_msgs::PoseStamped

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Desciption
/motion_target/pose_ee_arm header Standard 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 diver interface.
/motion_target/target_joint_state_arm - Please refer to the joint control interface

Gripper Control

A1XY Gripper Control is a ROS node designed to control the end-effector gripper. It primarily includes a launch file that can be started using the following command:

source A1XY_workspace/install/setup.bash
roslaunch mobiman a1xy_gripperController.launch

This launch file will start a1_xy_jointTracker_demo_node, which is the main node responsible for controlling each joint.

The interface is shown below:

Topic Name I/O Desciption Message Type
/motion_target/target_position_gripper Input Target position of gripper Sensor_msgs::JointState
/motion_control/control_gripper Input Motor control of gripper Sensor_msgs::JointState

The specific fields and their detailed descriptions for the above topic are shown in the table below:

Topic Name Field Desciption
/motion_target/target_position_gripper position Indicates the target position of the gripper, ranging from [0, 100], where 0 represents fully closed and 100 represents fully open.
/motion_control/control_gripper - Please refer to the driver interface.