M3 Wrist Control
The M3 extends the M2 kinematic chain with a 2-DOF articulated wrist between the elbow and gripper. This adds two independently controlled axes — pitch (vertical tilt) and rotation (axial spin) — enabling the gripper to approach objects from arbitrary orientations rather than being locked to the arm’s plane of motion.
Image: Waveshare
Wrist Anatomy
Section titled “Wrist Anatomy”The M3 wrist consists of two additional servos mounted at the end of the forearm link (L4 = 171.67mm):
| Joint | Servo ID | Firmware Constant | Range | Default |
|---|---|---|---|---|
| Wrist pitch | 15 | WRIST_JOINT (4) | ±90° (±π/2 rad) | 0 rad (horizontal) |
| Wrist rotation | 16 | ROLL_JOINT (5) | ±180° (±π rad) | 0 rad (neutral) |
| Gripper | 17 | EOAT_JOINT (6) | ~135° (3.14 → 1.08 rad) | 3.14 rad (fully open) |
The pitch servo tilts the gripper in the vertical plane — positive values tilt downward. The rotation servo spins the gripper around its longitudinal axis — positive values rotate clockwise when viewed from the arm.
Command Reference
Section titled “Command Reference”Every M2 motion command that accepted joint parameters has been extended with additional fields for the M3 wrist. The T-code numbers are identical — the M3 firmware simply recognizes extra JSON keys.
Joint-Level Control
Section titled “Joint-Level Control”Single Joint (T:101)
Section titled “Single Joint (T:101)”Control any individual joint by number. The M3 adds joints 4 (wrist), 5 (roll), and 6 (gripper):
{"T":101,"joint":4,"rad":0.5,"spd":0,"acc":10}| Joint Number | Name | Direction |
|---|---|---|
| 1 | Base | + = left |
| 2 | Shoulder | + = down |
| 3 | Elbow | + = down |
| 4 | Wrist pitch | + = down |
| 5 | Wrist rotation | + = CW |
| 6 | Gripper | (see gripper section) |
All Joints — Radians (T:102)
Section titled “All Joints — Radians (T:102)”Move all joints simultaneously using radian values:
{"T":102,"base":0,"shoulder":0,"elbow":1.57,"wrist":0,"roll":0,"hand":1.57,"spd":0,"acc":10}{"T":102,"base":0,"shoulder":0,"elbow":1.57,"hand":1.57,"spd":0,"acc":10}| Parameter | Joint | Unit | M3 Range |
|---|---|---|---|
base | Base rotation | radians | ±π |
shoulder | Shoulder | radians | ±π/2 |
elbow | Elbow | radians | (constrained by servo) |
wrist | Wrist pitch | radians | ±π/2 |
roll | Wrist rotation | radians | ±π |
hand | Gripper | radians | ~1.08 to 3.14 |
spd | Speed | servo steps/s | 0 = max |
acc | Acceleration | servo steps/s² | 1–254 |
All Joints — Degrees (T:122)
Section titled “All Joints — Degrees (T:122)”Same as T:102 but using degrees. Shorthand parameter names:
{"T":122,"b":0,"s":0,"e":90,"t":0,"r":0,"h":180,"spd":10,"acc":10}| Parameter | Joint | Unit |
|---|---|---|
b | Base | degrees |
s | Shoulder | degrees |
e | Elbow | degrees |
t | Wrist pitch | degrees |
r | Wrist rotation | degrees |
h | Gripper | degrees |
Cartesian Control (XYZ + Orientation)
Section titled “Cartesian Control (XYZ + Orientation)”The M3 inverse kinematics solver extends XYZ positioning with wrist orientation parameters. The key insight is that the t parameter represents the desired tilt angle relative to the world frame, not a raw wrist joint angle — the firmware automatically compensates for the shoulder and elbow configuration to maintain the requested tilt.
XYZ Goal with Interpolation (T:104)
Section titled “XYZ Goal with Interpolation (T:104)”Moves to a target position with smooth interpolation:
{"T":104,"x":235,"y":0,"z":234,"t":0,"r":0,"g":3.14,"spd":0.25}XYZ Direct (T:1041)
Section titled “XYZ Direct (T:1041)”Moves to a target position immediately (no interpolation):
{"T":1041,"x":235,"y":0,"z":234,"t":0,"r":0,"g":3.14}| Parameter | Description | Unit | Default |
|---|---|---|---|
x | Forward distance | mm | 346.16 (l2B + l3A + L4A) |
y | Lateral distance | mm | 0 |
z | Vertical distance | mm | 223.13 (l2A − L4B) |
t | Wrist tilt (world frame) | radians | 0 (horizontal) |
r | Wrist rotation | radians | 0 (neutral) |
g | Gripper angle | radians | 3.14 (fully open) |
spd | Interpolation speed | (T:104 only) | 0.25 |
Dynamic Adaptation (T:112)
Section titled “Dynamic Adaptation (T:112)”Limit the torque on individual joints for compliant/force-sensitive behavior. The M3 version adds per-joint torque limits for the wrist and roll:
{"T":112,"mode":1,"b":60,"s":110,"e":50,"t":50,"r":50,"h":50}| Parameter | Joint | Range |
|---|---|---|
b | Base | 50–1000 |
s | Shoulder | 50–1000 |
e | Elbow | 50–1000 |
t | Wrist pitch | 50–1000 |
r | Wrist rotation | 50–1000 |
h | Gripper | 50–1000 |
Set mode to 0 to restore full torque on all joints. Lower values make joints more compliant (easier to push by hand).
Gripper Control (T:106, T:107)
Section titled “Gripper Control (T:106, T:107)”The gripper commands work the same on M3 as M2:
{"T":106,"cmd":3.14,"spd":0,"acc":0}cmd: 3.14— fully opencmd: 1.57— approximately half closedcmd: 1.08— fully closed (minimum from firmware constraint)
For torque-limited gripping (grasp until resistance):
{"T":107,"tor":200}Kinematic Chain
Section titled “Kinematic Chain”The M3 forward kinematics compute end-effector position by chaining four link segments. The wrist adds a fourth link (L4) that the M2 doesn’t have:
graph LR
A["Base<br/>L1 = 126.06mm"] --> B["Shoulder<br/>L2 = 238.71mm"]
B --> C["Elbow<br/>L3 = 144.49mm"]
C --> D["Wrist<br/>L4 = 172.21mm"]
D --> E["Gripper"]
The firmware computes the effective L4 length as √(L4A² + L4B²) = √(171.67² + 13.69²) ≈ 172.21mm. The small L4B offset (13.69mm) accounts for the mechanical offset between the wrist pitch axis and the gripper centerline.
When using Cartesian control (T:104/T:1041), the IK solver:
- Computes the wrist pitch compensation from the
t(tilt) parameter - Projects the target point back along the L4 vector to find the elbow-wrist intersection
- Solves the 2-link (L2 + L3) planar IK for shoulder and elbow angles
- Sets the wrist joint angle to maintain the requested world-frame tilt
- Passes
r(roll) andg(gripper) directly to their servos
Feedback
Section titled “Feedback”Query the current state of all joints with T:105:
{"T":105}The M3 response includes wrist and roll data:
{ "T": 1051, "x": 346.16, "y": 0, "z": 223.13, "tit": 0, "b": 0, "s": 0, "e": 1.57, "t": 0, "r": 0, "g": 3.14, "tB": 0, "tS": 0, "tE": 0, "tT": 0, "tR": 0, "tG": 0, "v": 1200}| Field | Description |
|---|---|
x, y, z | Cartesian end-effector position (mm) |
tit | Computed world-frame tilt |
b, s, e | Base, shoulder, elbow joint angles (rad) |
t, r, g | Wrist pitch, roll, gripper angles (rad) |
tB…tG | Per-joint torque load readings |
v | Supply voltage (×100, so 1200 = 12.00V) |
ESP-NOW with Wrist
Section titled “ESP-NOW with Wrist”The ESP-NOW group and single control commands also extend with wrist parameters:
{"T":305,"dev":0,"b":0,"s":0,"e":1.57,"t":0,"r":0,"h":1.57,"cmd":0,"megs":"hello!"}{"T":306,"mac":"FF:FF:FF:FF:FF:FF","dev":0,"b":0,"s":0,"e":1.57,"t":0,"r":0,"h":1.57,"cmd":0,"megs":"hello!"}The t, r, and h fields map to wrist pitch, roll, and gripper respectively — matching the T:122 degree-mode naming convention.
Common Patterns
Section titled “Common Patterns”Pick from Above
Section titled “Pick from Above”Point the gripper straight down, open it, lower to target, close, lift:
{"T":104,"x":200,"y":0,"z":150,"t":-1.57,"r":0,"g":3.14,"spd":0.25}{"T":104,"x":200,"y":0,"z":50,"t":-1.57,"r":0,"g":3.14,"spd":0.15}{"T":107,"tor":200}{"T":104,"x":200,"y":0,"z":150,"t":-1.57,"r":0,"g":3.14,"spd":0.25}Rotated Placement
Section titled “Rotated Placement”Pick an object and rotate it 90° before placing:
{"T":104,"x":200,"y":0,"z":100,"t":0,"r":0,"g":3.14,"spd":0.25}{"T":107,"tor":200}{"T":104,"x":200,"y":100,"z":100,"t":0,"r":1.57,"g":3.14,"spd":0.25}{"T":106,"cmd":3.14,"spd":0,"acc":0}Compliant Wrist Teaching
Section titled “Compliant Wrist Teaching”Lower the wrist torque limits so a human can physically guide the arm, then record the position:
{"T":112,"mode":1,"b":60,"s":110,"e":50,"t":30,"r":30,"h":50}{"T":105}{"T":112,"mode":0,"b":1000,"s":1000,"e":1000,"t":1000,"r":1000,"h":1000}Firmware reference from RoArm-M3_config.h, RoArm-M3_module.h, and json_cmd.h in the RoArm-M3 example firmware. Images: Waveshare.