Skip to content

JSON Command Reference

Every command sent to the RoArm-M2-S is a JSON object with a T (type) field that identifies the operation. This reference is sourced directly from the firmware’s json_cmd.h header file — the authoritative definition of all supported commands.

Commands can be sent over serial UART (115200 baud), HTTP (/js?json=...), or ESP-NOW.

Immediately halts all motion.

{"T":0}

Clears the emergency stop state so the arm can accept motion commands again.

{"T":999}

Switch between gripper and wrist end-effector modes.

{"T":1,"mode":0}
modeType
0Gripper
1Wrist

Configure the physical dimensions of the installed end-effector for correct kinematics.

{"T":2,"pos":3,"ea":0,"eb":20}
ParameterDescription
posMount position: 0=edge, 1=D-3.2, 2=D-4.2, 3=D-10.2
eaExtension A length (mm)
ebExtension B length (mm)

Moves all joints to default position without interpolation.

{"T":100}

Move one joint to a specific angle in radians.

{"T":101,"joint":1,"rad":0,"spd":0,"acc":10}
jointName+ Direction
1BaseLeft
2ShoulderDown
3ElbowDown
4End-effectorGrab/down

Move all joints simultaneously. Angles in radians (180° = π).

{"T":102,"base":0,"shoulder":0,"elbow":1.57,"hand":1.57,"spd":0,"acc":10}

Move along one Cartesian axis.

{"T":103,"axis":2,"pos":0,"spd":0.25}
axisDefault (mm)Description
1 (x)235.11Forward/backward
2 (y)0Left/right
3 (z)234.79Up/down
4 (t)1.57 radEnd-effector angle

Move to Cartesian position with interpolation (smooth motion).

{"T":104,"x":235,"y":0,"z":234,"t":3.14,"spd":0.25}

Move to Cartesian position without interpolation (fastest path).

{"T":1041,"x":235,"y":0,"z":234,"t":3.14}

Read current position and torque values.

{"T":105}

Returns: x, y, z, t, torB, torS, torE

Control the gripper/wrist angle in radians.

{"T":106,"cmd":1.57,"spd":0,"acc":0}
cmd valueAction
1.57Release/open
3.14Grab/close

Set maximum grip force.

{"T":107,"tor":200}

Range: 0–1000.

Adjust P and I gains for a specific joint.

{"T":108,"joint":3,"p":16,"i":0}

Defaults: P=16, I=8 (with PID mode on for RoArm-M2).

Reset all PID parameters to factory defaults.

{"T":109}

Redefine the forward direction of the coordinate frame.

{"T":110,"xAxisAngle":0}

Insert a delay (used in mission sequences).

{"T":111,"cmd":3000}

cmd is the delay in milliseconds.

T:112 — Dynamic External Force Adaptation

Section titled “T:112 — Dynamic External Force Adaptation”

Enable/disable compliance mode with per-joint torque limits.

Start:

{"T":112,"mode":1,"b":60,"s":110,"e":50,"h":50}

Stop:

{"T":112,"mode":0,"b":1000,"s":1000,"e":1000,"h":1000}

Control the two 12V switched outputs (PWM).

{"T":113,"pwm_a":-255,"pwm_b":-255}

Range: -255 to +255 (0 = off).

Control the onboard LED brightness.

{"T":114,"led":255}

Range: 0 (off) to 255 (max).

Turn off all switched outputs.

{"T":115}

Move one joint to a specific angle in degrees.

{"T":121,"joint":1,"angle":0,"spd":10,"acc":10}

Max acceleration: 22.5 deg/s².

Move all joints simultaneously. Angles in degrees.

{"T":122,"b":0,"s":0,"e":90,"h":180,"spd":10,"acc":10}

Continuous motion along an axis (for jogging).

{"T":123,"m":0,"axis":0,"cmd":0,"spd":3}
mMode
0Angle
1XYZT
cmdAction
0Stop
1Increase
2Decrease

List all files in flash storage.

{"T":200}
{"T":201,"name":"file.txt","content":"content here"}
{"T":202,"name":"file.txt"}
{"T":203,"name":"file.txt"}
{"T":204,"name":"file.txt","content":"new line"}
{"T":205,"name":"file.txt","lineNum":3,"content":"inserted"}
{"T":206,"name":"file.txt","lineNum":3,"content":"replaced"}
{"T":207,"name":"file.txt","lineNum":3}
{"T":208,"name":"file.txt","lineNum":3}

Enable or disable servo torque.

{"T":210,"cmd":1}
cmdState
0Off (arm goes limp)
1On (servos hold position)
{"T":220,"name":"mission_a","intro":"description here"}
{"T":221,"name":"mission_a"}
{"T":222,"name":"mission_a","step":"{\"T\":104,\"x\":235,\"y\":0,\"z\":234,\"t\":3.14,\"spd\":0.25}"}

Record the current arm position as a step.

{"T":223,"name":"mission_a","spd":0.25}
{"T":224,"name":"mission_a","delay":3000}
{"T":225,"name":"mission_a","stepNum":3,"step":"{\"T\":104,\"x\":235,\"y\":0,\"z\":234,\"t\":3.14,\"spd\":0.25}"}
{"T":226,"name":"mission_a","stepNum":3,"spd":0.25}
{"T":227,"stepNum":3,"delay":3000}
{"T":228,"name":"mission_a","stepNum":3,"step":"{\"T\":114,\"led\":255}"}
{"T":229,"name":"mission_a","stepNum":3,"spd":0.25}
{"T":230,"name":"mission_a","stepNum":3,"delay":3000}
{"T":231,"name":"mission_a","stepNum":3}

Navigate the arm to a specific step’s position.

{"T":241,"name":"mission_a","stepNum":3}

Execute a mission with a repeat count. Use -1 for infinite loop.

{"T":242,"name":"mission_a","times":3}
{"T":300,"mode":1}

Mode 1: accept broadcast. Mode 0 + mac: whitelist a specific leader.

{"T":301,"mode":3}
modeRole
0Disabled
1Group leader
2Single leader
3Follower (default)
{"T":302}
{"T":303,"mac":"CC:DB:A7:5B:E4:1C"}
{"T":304,"mac":"CC:DB:A7:5B:E4:1C"}

Send to all registered peers.

{"T":305,"dev":0,"b":0,"s":0,"e":1.57,"h":1.57,"cmd":0,"megs":"hello!"}

Send to specific MAC or broadcast.

{"T":306,"mac":"FF:FF:FF:FF:FF:FF","dev":0,"b":0,"s":0,"e":1.57,"h":1.57,"cmd":0,"megs":"hello!"}
{"T":401,"cmd":3}
cmdMode
0Off
1AP
2STA
3AP+STA
{"T":402,"ssid":"RoArm-M2","password":"12345678"}
{"T":403,"ssid":"YourNetwork","password":"YourPassword"}
{"T":404,"ap_ssid":"RoArm-M2","ap_password":"12345678","sta_ssid":"YourNetwork","sta_password":"YourPassword"}
{"T":405}
{"T":406}
{"T":407,"mode":3,"ap_ssid":"RoArm-M2","ap_password":"12345678","sta_ssid":"YourNetwork","sta_password":"YourPassword"}
{"T":408}
{"T":501,"raw":1,"new":11}

Define the current position as the servo’s center (middle) point.

{"T":502,"id":11}
{"T":503,"id":14,"p":16}
{"T":600}
{"T":601}

Check if a mission is configured to run at startup.

{"T":602}

Clear the boot mission so nothing runs at startup.

{"T":603}

Clear non-volatile storage. Useful for WiFi recovery.

{"T":604}
{"T":605,"cmd":1}
cmdBehavior
0Silent
1Debug info (default)
2Flow feedback

Command reference sourced from firmware json_cmd.h (January 2025 release). Waveshare GitHub.