Arm Control
The arm accepts motion commands in three coordinate spaces: individual joint radians, joint degrees, and Cartesian XYZ coordinates. All commands use the JSON protocol over serial, HTTP, or ESP-NOW.
Control Modes
Section titled “Control Modes”graph LR
A[JSON Command] --> B{Control Mode}
B -->|T:101/102| C[Joint Radian]
B -->|T:121/122| D[Joint Degree]
B -->|T:103/104| E[XYZ Cartesian]
C --> F[Inverse Kinematics]
D --> F
E --> F
F --> G[Servo Bus]
G --> H[Joint Motion]
Home Position
Section titled “Home Position”Move the arm to its default (home) position:
{"T":100}This moves all joints to their initial positions without interpolation — the arm moves directly to the target.
Joint Control (Radians)
Section titled “Joint Control (Radians)”Single Joint
Section titled “Single Joint”Move one joint at a time. Angles are in radians (π ≈ 3.14159 = 180°).
{"T":101,"joint":1,"rad":0,"spd":0,"acc":10}| Parameter | Description |
|---|---|
joint | 1=Base, 2=Shoulder, 3=Elbow, 4=End-effector |
rad | Target angle in radians |
spd | Speed (steps/s). 0 = maximum speed |
acc | Acceleration (steps/s²) |
All Joints
Section titled “All Joints”Control all four joints simultaneously:
{"T":102,"base":0,"shoulder":0,"elbow":1.57,"hand":1.57,"spd":0,"acc":10}Joint Control (Degrees)
Section titled “Joint Control (Degrees)”Single Joint
Section titled “Single Joint”Same as radian control, but input is in degrees:
{"T":121,"joint":1,"angle":0,"spd":10,"acc":10}| Parameter | Description |
|---|---|
joint | 1=Base, 2=Shoulder, 3=Elbow, 4=End-effector |
angle | Target angle in degrees |
spd | Speed (degrees/s) |
acc | Acceleration (degrees/s²), max 22.5 |
All Joints (Degrees)
Section titled “All Joints (Degrees)”{"T":122,"b":0,"s":0,"e":90,"h":180,"spd":10,"acc":10}XYZ Cartesian Control
Section titled “XYZ Cartesian Control”Single Axis
Section titled “Single Axis”Move along one Cartesian axis:
{"T":103,"axis":2,"pos":0,"spd":0.25}| Axis | Default Position | Description |
|---|---|---|
| 1 (x) | 235.11 mm | Forward/backward |
| 2 (y) | 0 mm | Left/right |
| 3 (z) | 234.79 mm | Up/down |
| 4 (t) | 1.57 rad | End-effector angle |
Full XYZT Control
Section titled “Full XYZT Control”Move to an XYZ position with end-effector angle, with interpolation:
{"T":104,"x":235,"y":0,"z":234,"t":3.14,"spd":0.25}Direct XYZT (No Interpolation)
Section titled “Direct XYZT (No Interpolation)”Move to the target position immediately, without path interpolation:
{"T":1041,"x":235,"y":0,"z":234,"t":3.14}Position Feedback
Section titled “Position Feedback”Read the current arm position:
{"T":105}Returns:
| Field | Description |
|---|---|
x, y, z | Current Cartesian position (mm) |
t | End-effector angle (radians) |
torB | Base joint torque |
torS | Shoulder joint torque |
torE | Elbow joint torque |
Constant Motion
Section titled “Constant Motion”Start continuous motion along an axis — useful for jogging:
{"T":123,"m":0,"axis":0,"cmd":1,"spd":3}| Parameter | Values |
|---|---|
m | 0 = angle mode, 1 = XYZT mode |
cmd | 0 = stop, 1 = increase, 2 = decrease |
axis | Joint or axis index |
spd | Movement speed |
Speed and Acceleration
Section titled “Speed and Acceleration”Setting spd to 0 in radian-mode commands (T:101, T:102) tells the servo to move at maximum speed. For XYZ commands, spd is in mm/step of interpolation — lower values mean faster movement.
PID Tuning
Section titled “PID Tuning”Adjust the PID parameters for a specific joint:
{"T":108,"joint":3,"p":16,"i":0}Default values:
- Servo default: P=32, I=0
- RoArm-M2 default: P=16, I=8 (when PID mode is on)
Reset all PID values to defaults:
{"T":109}X-Axis Redefinition
Section titled “X-Axis Redefinition”Redefine the forward direction (x-axis) of the arm:
{"T":110,"xAxisAngle":0}This rotates the Cartesian coordinate frame without physically moving the arm — useful when the arm is mounted at an angle on a mobile platform.
Dynamic External Force Adaptation
Section titled “Dynamic External Force Adaptation”Enable compliance mode where the arm yields to external forces:
Start (set torque limits per joint):
{"T":112,"mode":1,"b":60,"s":110,"e":50,"h":50}Stop (restore full torque):
{"T":112,"mode":0,"b":1000,"s":1000,"e":1000,"h":1000}Control reference from firmware source json_cmd.h and Waveshare Wiki.