Menlo
Hardware Design

Joint Design and Actuation

Asimov Full Body is a 25-DOF humanoid robot with 23 actuated DOF and 2 passive toe joints.

  • 12 leg joints (6 per leg): hip_pitch, hip_roll, hip_yaw, knee, ankle_pitch, ankle_roll
  • 1 waist joint: waist_yaw
  • 10 arm joints (5 per arm): shoulder_pitch, shoulder_roll, shoulder_yaw, elbow, wrist_yaw
  • 2 head joints: neck_yaw, neck_pitch
  • 2 passive toe joints: left_toe_joint, right_toe_joint

For locomotion, we use the 23-DOF body model and lock the two head joints.

This chapter documents joint-level actuation limits and the ankle mechanism model used for design and control.

1. Joint Actuator Specification

The table below maps each actuated joint to its actuator, kinematic limits, and the core actuator-model parameters used for that joint. Passive toe joints are included for completeness and are marked with N/A where actuator-specific values do not apply.

Motor IDJoint NameActuator IDMotion Range (rad)Velocity Limit (rad/s)KtArmatureRated Torque (Nm)Peak Torque (Nm)Static FrictionDynamic Friction
1left_hip_pitch_jointEC-A6416-P2-25-2.09 ~ 1.0012.572.750.09562540.0120.00.700.050
2left_hip_roll_jointEC-A5013-H17-100-0.79 ~ 0.793.987.150.1130.090.00.200.020
3left_hip_yaw_jointEC-A3814-H14-107-0.79 ~ 0.795.455.700.03820.060.00.700.050
4left_knee_jointEC-A4315-P2-360.00 ~ 1.5012.252.530.033955225.075.00.700.020
5left_ankle_pitch_jointEC-A4310-P2-36-0.35 ~ 0.359.321.810.056505640.0145.40.400.015
6left_ankle_roll_jointEC-A4310-P2-36-0.10 ~ 0.109.321.810.056505617.057.60.400.015
7right_hip_pitch_jointEC-A6416-P2-25-1.00 ~ 2.0912.572.750.09562540.0120.00.700.050
8right_hip_roll_jointEC-A5013-H17-100-0.79 ~ 0.793.987.150.1130.090.00.200.020
9right_hip_yaw_jointEC-A3814-H14-107-0.79 ~ 0.795.455.700.03820.060.00.700.050
10right_knee_jointEC-A4315-P2-36-1.50 ~ 0.0012.252.530.033955225.075.00.700.020
11right_ankle_pitch_jointEC-A4310-P2-36-0.35 ~ 0.359.321.810.056505640.0145.40.400.015
12right_ankle_roll_jointEC-A4310-P2-36-0.10 ~ 0.109.321.810.056505617.057.60.400.015
13left_shoulder_pitch_jointEC-A5013-H17-100-3.14 ~ 0.873.987.150.1130.090.00.200.020
14left_shoulder_roll_jointEC-A4315-P2-36-1.57 ~ 0.0012.252.530.033955225.075.00.700.020
15left_shoulder_yaw_jointEC-A3814-H14-107-1.57 ~ 1.575.455.700.03820.060.00.700.050
16left_elbow_jointEC-A4310-P2-360.00 ~ 2.449.321.810.028252812.036.00.400.015
17left_wrist_yaw_jointEC-A4310-P2-36-3.14 ~ 3.149.321.810.028252812.036.00.400.015
18right_shoulder_pitch_jointEC-A5013-H17-100-0.87 ~ 3.143.987.150.1130.090.00.200.020
19right_shoulder_roll_jointEC-A4315-P2-360.00 ~ 1.5712.252.530.033955225.075.00.700.020
20right_shoulder_yaw_jointEC-A3814-H14-107-1.57 ~ 1.575.455.700.03820.060.00.700.050
21right_elbow_jointEC-A4310-P2-36-2.44 ~ 0.009.321.810.028252812.036.00.400.015
22right_wrist_yaw_jointEC-A4310-P2-36-3.14 ~ 3.149.321.810.028252812.036.00.400.015
23waist_yaw_jointEC-A6416-P2-25-1.57 ~ 1.5712.572.750.09562540.0120.00.700.050
24neck_yaw_jointEC-A4310-P2-36-1.57 ~ 1.579.321.810.028252812.036.00.400.015
25neck_pitch_jointEC-A4310-P2-36-0.79 ~ 0.799.321.810.028252812.036.00.400.015

Motor ID mapping:

Motor ID map for assembly

Parameter Definitions

  • Kt: motor torque constant. It maps motor current to output torque: Torque (Nm) = Kt * current. A larger Kt means more torque is produced per ampere of current.
  • Armature: joint armature can help with stability by adding joint-space inertia and corresponding damping. If a geared actuator is modeled, armature can be set to represent the reflected inertia of the motor rotor, where armature = JG^2, with G denoting the ratio of motor angular velocity to output shaft angular velocity, and J denoting the rotor inertia.
  • Rated Torque: the continuous torque the actuator can sustain without overheating under normal operating conditions.
  • Peak Torque: the short-duration maximum torque the actuator can produce for brief events such as impacts, push-off, or fast recovery motions.
  • Static friction: the torque needed to break the joint free from rest. Measured from a stall test.
  • Dynamic friction: the lower resisting torque once the joint is already moving. Estimated from slow-motion joint tests and fitted into the actuator model.

2. Ankle Parallel Mechanism

Parallel Mechanical Design

alt text Figure: RSU ankle parallel mechanism

Asimov uses a parallel RSU ankle (Revolute-Spherical-Universal) instead of a simple serial single-DOF ankle. The RSU layout provides two ankle DOFs (pitch and roll) while allowing coupled actuation through two revolute motors.

Kinematic Mapping for the Parallel Mechanism

alt text Figure: Ankle joint overview

In simulation, we model the ankle pitch and roll joints as directly actuated at their ideal joint locations to avoid the computational cost of simulating the full parallel mechanism. In hardware, pitch and roll are controlled by moving two endpoints on a straight bar; these endpoints are connected through parallel linkages to ankle motors A and B. Because the ankle pitch and roll joints are not directly actuated in the real system, kinematic mapping is required for sim-to-real policy deployment.

We define the following variables:

  • theta_p: ankle pitch angle (joint space)
  • theta_r: ankle roll angle (joint space)
  • theta_A: motor A rotation angle
  • theta_B: motor B rotation angle
  • r_A, r_B: effective crank/linkage radii of motors A and B
  • r: common radius when r_A = r_B = r
  • d: distance from the ankle pivot to the bar midpoint line
  • c: distance between the left and right bar endpoints

Assumptions:

  • Small-angle approximation is used: sin(theta) ≈ theta, tan(theta) ≈ theta (angles in radians)
  • The bar/linkage geometry is rigid and symmetric
  • r_A and r_B are constant effective radii (no compliance, backlash, or slip)
  • Sign convention is fixed and consistent:
    • +y is away from the ground, -y is toward the ground
    • Positive motor/joint rotation directions are predefined and unchanged
  • The same derivation frame (right-leg convention) is used when applying the equations
  • For simplified forms, assume r_A = r_B = r

Mapping equations (AB -> PR):

theta_p = (r_A * theta_A - r_B * theta_B) / (2 * d)

theta_p = (theta_A - theta_B) * (r / (2 * d))

theta_r = - (1 / c) * (r_A * theta_A + r_B * theta_B)

theta_r = - (theta_A + theta_B) * (r / c)

Code example:

float right_pitch = (right_A - right_B) / (2.0f * K_PITCH);
float right_roll  = -(right_A + right_B) / (2.0f * K_ROLL);

float left_pitch  = (left_A - left_B) / (2.0f * K_PITCH);
float left_roll   = -(left_A + left_B) / (2.0f * K_ROLL);

For more information on deriving the ankle mechanism equations, see the ankle mechanism derivation note.

3. Passive toe joints

alt text Figure: Passive toe joint design

Similar to how human toes passively bend to conform to the ground during stance, an articulated toe increases effective contact area and helps distribute load more evenly. The main benefit appears during the stance-to-push-off transition.

As the body moves forward, the toe rocker allows the foot to roll rather than pivot on a rigid edge. This reduces peak local forces, maintains ground contact, and increases effective contact area, improving traction stability and forward propulsion.

In Asimov, this is implemented as an additional toe hinge that is articulated but not actively actuated. The toe joint is passive and compliant, using elastic/spring-like return behavior instead of a dedicated motor drive. This approach captures most toe-rollover benefits while avoiding the added complexity, mass, and control burden of another powered joint.

The passive toe joint stiffness is 2.67 Nm. The toe motion ranges are:

  • Left toe: -1.05 ~ 0.00 rad
  • Right toe: 0.00 ~ 1.05 rad

4. References

  1. Unitree G1 developer documentation (parallel-ankle context): https://support.unitree.com/home/en/G1_developer/basic_motion_routine

After the previous chapters, you should now have a clear understanding of our mechanical design. You can now begin manufacturing the parts to build your robot in 3D Printing and Fabrication.

How is this guide?

On this page