Software API
get_a1z_robot()
Factory function that creates a configured ArmRobot instance:
get_a1z_robot(
can_channel="can0", # CAN channel name
gravity_comp_factor=1.0, # Gravity compensation factor (0=off, 1=full compensation)
zero_gravity_mode=True, # True=zero-force floating, False=position holding
control_freq_hz=250, # Control loop frequency (Hz)
urdf_path=None, # Override URDF path
default_kp=None, # Override default position gain
default_kd=None, # Override default velocity gain
) -> ArmRobot
Main ArmRobot Methods
| Method | Description |
|---|---|
| start(initial_kp, initial_kd) | Enables the motors and starts the control loop. |
| stop() | Performs a smooth shutdown with 0.3s decay, then disables the motors. |
| get_joint_pos() -> np.ndarray | Gets the current joint angles (rad). |
| get_joint_state() -> dict | Gets {`pos`, `vel`, `eff`}. |
| command_joint_pos(pos) | Sets target joint angles using the default PD gains. |
| command_joint_state(joint_state) | Sets target joint angles with custom gains. |
| move_joints(target, speed, kp, kd) | Moves to the target position with linear interpolation (blocking). |
| is_running | Indicates whether the control loop is running. |
Kinematics
from a1z.robots.kinematics import Kinematics
kin = Kinematics("/path/to/urdf")
# Forward kinematics -> 4x4 homogeneous transformation matrix
T = kin.fk(q)
# Inverse kinematics (damped least squares)
converged, q_sol = kin.ik(target_pose, init_q=q0)
Joint Limits
| Joint | Name | Mechanical Limit (deg) | Mechanical Limit (rad) | Soft Limit (deg) | Soft Limit (rad) |
|---|---|---|---|---|---|
| 0 | arm_joint1 | [-130°, 130°] | [-2.269, 2.269] | [-120°, 120°] | [-2.094, 2.094] |
| 1 | arm_joint2 | [-1.94°, 192.78°] | [-0.034, 3.365] | [0°, 180°] | [0.000, 3.142] |
| 2 | arm_joint3 | [-200.38°, 0°] | [-3.497, 0.000] | [-180°, 0°] | [-3.142, 0] |
| 3 | arm_joint4 | [-91.88°, 110.38°] | [-1.604, 1.926] | [-85°, 85°] | [-1.484, 1.484] |
| 4 | arm_joint5 | [-90°, 90°] | [-1.571, 1.571] | [-90°, 90°] | [-1.484, 1.484] |
| 5 | arm_joint6 | [-120°, 120°] | [-2.094, 2.094] | [-115°, 115°] | [-2.007, 2.007] |
Default Control Parameters
| Control Item | Parameter Value |
|---|---|
| Default KP | [30, 30, 30, 20, 5, 5] |
| Default KD | [1, 1, 1, 0.5, 0.5, 0.5] |
| Joint Coordinate Sign | [1, 1, -1, 1, 1, 1] (joint 3 is opposite to the URDF direction) |
| Gravity Torque Scale | [1, 1, 1, 1, 1, 1] |
| Maximum Gravity Torque | [50, 50, 50, 24, 10, 10] Nm |
| Torque Limit | [70, 70, 70, 27, 10, 10] Nm |
| MotorA KT | 2.8 (current-to-torque conversion factor) |
| Control Frequency | 250 Hz |
Control Principles
1. MIT Hybrid Force-Position Control
The motor firmware executes:
τ_motor = kp × (pos_target - pos_actual) + kd × (vel_target - vel_actual) + τ_ff
The SDK executes the following at each control cycle (250 Hz by default):
- Reads feedback from all motors over the CAN bus.
- Uses Pinocchio RNEA to calculate the gravity compensation torque
τ_g(q)for the current posture. - Performs safety checks: if
|τ_g|exceeds the threshold, an emergency stop is triggered. - Composes the final torque:
τ_motor = (user_torque + τ_g × scale × factor) × joint_sign. - Clips the torque to the safe range and sends it to the motors.
2. Zero-Force Floating Mode
kp=0, kd=small value. The arm uses gravity compensation torque only to offset gravity, so it can be freely dragged.
3. Position Holding Mode
kp=default gain, kd=default gain. PD control is combined with gravity compensation.
Notes
- For first-time use, set
gravity_comp_factorto a small value, such as 0.3. After confirming that the compensation direction is correct, increase it gradually. - The system automatically triggers an emergency stop when gravity torque exceeds the safety threshold for any joint.
- During shutdown, gravity compensation decays smoothly within 0.3s and damping is increased to prevent the arm from dropping suddenly after motor disable.
- All target joint angles are clipped to the URDF limit range.