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.
Safety
Section titled “Safety”T:0 — Emergency Stop
Section titled “T:0 — Emergency Stop”Immediately halts all motion.
{"T":0}T:999 — Reset Emergency Flag
Section titled “T:999 — Reset Emergency Flag”Clears the emergency stop state so the arm can accept motion commands again.
{"T":999}EoAT Configuration
Section titled “EoAT Configuration”T:1 — EoAT Type
Section titled “T:1 — EoAT Type”Switch between gripper and wrist end-effector modes.
{"T":1,"mode":0}mode | Type |
|---|---|
| 0 | Gripper |
| 1 | Wrist |
T:2 — EoAT Assembly
Section titled “T:2 — EoAT Assembly”Configure the physical dimensions of the installed end-effector for correct kinematics.
{"T":2,"pos":3,"ea":0,"eb":20}| Parameter | Description |
|---|---|
pos | Mount position: 0=edge, 1=D-3.2, 2=D-4.2, 3=D-10.2 |
ea | Extension A length (mm) |
eb | Extension B length (mm) |
Arm Control
Section titled “Arm Control”T:100 — Move to Init Position
Section titled “T:100 — Move to Init Position”Moves all joints to default position without interpolation.
{"T":100}T:101 — Single Joint Control (Radians)
Section titled “T:101 — Single Joint Control (Radians)”Move one joint to a specific angle in radians.
{"T":101,"joint":1,"rad":0,"spd":0,"acc":10}joint | Name | + Direction |
|---|---|---|
| 1 | Base | Left |
| 2 | Shoulder | Down |
| 3 | Elbow | Down |
| 4 | End-effector | Grab/down |
T:102 — All Joints Control (Radians)
Section titled “T:102 — All Joints Control (Radians)”Move all joints simultaneously. Angles in radians (180° = π).
{"T":102,"base":0,"shoulder":0,"elbow":1.57,"hand":1.57,"spd":0,"acc":10}T:103 — Single Axis Control (Cartesian)
Section titled “T:103 — Single Axis Control (Cartesian)”Move along one Cartesian axis.
{"T":103,"axis":2,"pos":0,"spd":0.25}axis | Default (mm) | Description |
|---|---|---|
| 1 (x) | 235.11 | Forward/backward |
| 2 (y) | 0 | Left/right |
| 3 (z) | 234.79 | Up/down |
| 4 (t) | 1.57 rad | End-effector angle |
T:104 — XYZT Goal Control
Section titled “T:104 — XYZT Goal Control”Move to Cartesian position with interpolation (smooth motion).
{"T":104,"x":235,"y":0,"z":234,"t":3.14,"spd":0.25}T:1041 — XYZT Direct Control
Section titled “T:1041 — XYZT Direct Control”Move to Cartesian position without interpolation (fastest path).
{"T":1041,"x":235,"y":0,"z":234,"t":3.14}T:105 — Position Feedback
Section titled “T:105 — Position Feedback”Read current position and torque values.
{"T":105}Returns: x, y, z, t, torB, torS, torE
T:106 — End-Effector Hand Control
Section titled “T:106 — End-Effector Hand Control”Control the gripper/wrist angle in radians.
{"T":106,"cmd":1.57,"spd":0,"acc":0}cmd value | Action |
|---|---|
| 1.57 | Release/open |
| 3.14 | Grab/close |
T:107 — Grab Torque
Section titled “T:107 — Grab Torque”Set maximum grip force.
{"T":107,"tor":200}Range: 0–1000.
T:108 — Set Joint PID
Section titled “T:108 — Set Joint PID”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).
T:109 — Reset PID
Section titled “T:109 — Reset PID”Reset all PID parameters to factory defaults.
{"T":109}T:110 — Set New X-Axis
Section titled “T:110 — Set New X-Axis”Redefine the forward direction of the coordinate frame.
{"T":110,"xAxisAngle":0}T:111 — Delay
Section titled “T:111 — Delay”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}T:113 — 12V Switch Control
Section titled “T:113 — 12V Switch Control”Control the two 12V switched outputs (PWM).
{"T":113,"pwm_a":-255,"pwm_b":-255}Range: -255 to +255 (0 = off).
T:114 — LED Light Control
Section titled “T:114 — LED Light Control”Control the onboard LED brightness.
{"T":114,"led":255}Range: 0 (off) to 255 (max).
T:115 — Switch Off
Section titled “T:115 — Switch Off”Turn off all switched outputs.
{"T":115}T:121 — Single Joint Control (Degrees)
Section titled “T:121 — Single Joint Control (Degrees)”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².
T:122 — All Joints Control (Degrees)
Section titled “T:122 — All Joints Control (Degrees)”Move all joints simultaneously. Angles in degrees.
{"T":122,"b":0,"s":0,"e":90,"h":180,"spd":10,"acc":10}T:123 — Constant Control
Section titled “T:123 — Constant Control”Continuous motion along an axis (for jogging).
{"T":123,"m":0,"axis":0,"cmd":0,"spd":3}m | Mode |
|---|---|
| 0 | Angle |
| 1 | XYZT |
cmd | Action |
|---|---|
| 0 | Stop |
| 1 | Increase |
| 2 | Decrease |
File System
Section titled “File System”T:200 — Scan Files
Section titled “T:200 — Scan Files”List all files in flash storage.
{"T":200}T:201 — Create File
Section titled “T:201 — Create File”{"T":201,"name":"file.txt","content":"content here"}T:202 — Read File
Section titled “T:202 — Read File”{"T":202,"name":"file.txt"}T:203 — Delete File
Section titled “T:203 — Delete File”{"T":203,"name":"file.txt"}T:204 — Append Line
Section titled “T:204 — Append Line”{"T":204,"name":"file.txt","content":"new line"}T:205 — Insert Line
Section titled “T:205 — Insert Line”{"T":205,"name":"file.txt","lineNum":3,"content":"inserted"}T:206 — Replace Line
Section titled “T:206 — Replace Line”{"T":206,"name":"file.txt","lineNum":3,"content":"replaced"}T:207 — Read Line
Section titled “T:207 — Read Line”{"T":207,"name":"file.txt","lineNum":3}T:208 — Delete Line
Section titled “T:208 — Delete Line”{"T":208,"name":"file.txt","lineNum":3}T:210 — Torque Lock Control
Section titled “T:210 — Torque Lock Control”Enable or disable servo torque.
{"T":210,"cmd":1}cmd | State |
|---|---|
| 0 | Off (arm goes limp) |
| 1 | On (servos hold position) |
Mission Control
Section titled “Mission Control”T:220 — Create Mission
Section titled “T:220 — Create Mission”{"T":220,"name":"mission_a","intro":"description here"}T:221 — Read Mission Content
Section titled “T:221 — Read Mission Content”{"T":221,"name":"mission_a"}T:222 — Append Step (JSON)
Section titled “T:222 — Append Step (JSON)”{"T":222,"name":"mission_a","step":"{\"T\":104,\"x\":235,\"y\":0,\"z\":234,\"t\":3.14,\"spd\":0.25}"}T:223 — Append Step (Feedback)
Section titled “T:223 — Append Step (Feedback)”Record the current arm position as a step.
{"T":223,"name":"mission_a","spd":0.25}T:224 — Append Delay
Section titled “T:224 — Append Delay”{"T":224,"name":"mission_a","delay":3000}T:225 — Insert Step (JSON)
Section titled “T:225 — Insert Step (JSON)”{"T":225,"name":"mission_a","stepNum":3,"step":"{\"T\":104,\"x\":235,\"y\":0,\"z\":234,\"t\":3.14,\"spd\":0.25}"}T:226 — Insert Step (Feedback)
Section titled “T:226 — Insert Step (Feedback)”{"T":226,"name":"mission_a","stepNum":3,"spd":0.25}T:227 — Insert Delay
Section titled “T:227 — Insert Delay”{"T":227,"stepNum":3,"delay":3000}T:228 — Replace Step (JSON)
Section titled “T:228 — Replace Step (JSON)”{"T":228,"name":"mission_a","stepNum":3,"step":"{\"T\":114,\"led\":255}"}T:229 — Replace Step (Feedback)
Section titled “T:229 — Replace Step (Feedback)”{"T":229,"name":"mission_a","stepNum":3,"spd":0.25}T:230 — Replace with Delay
Section titled “T:230 — Replace with Delay”{"T":230,"name":"mission_a","stepNum":3,"delay":3000}T:231 — Delete Step
Section titled “T:231 — Delete Step”{"T":231,"name":"mission_a","stepNum":3}T:241 — Move to Step
Section titled “T:241 — Move to Step”Navigate the arm to a specific step’s position.
{"T":241,"name":"mission_a","stepNum":3}T:242 — Play Mission
Section titled “T:242 — Play Mission”Execute a mission with a repeat count. Use -1 for infinite loop.
{"T":242,"name":"mission_a","times":3}ESP-NOW
Section titled “ESP-NOW”T:300 — Broadcast Follower Config
Section titled “T:300 — Broadcast Follower Config”{"T":300,"mode":1}Mode 1: accept broadcast. Mode 0 + mac: whitelist a specific leader.
T:301 — ESP-NOW Mode Config
Section titled “T:301 — ESP-NOW Mode Config”{"T":301,"mode":3}mode | Role |
|---|---|
| 0 | Disabled |
| 1 | Group leader |
| 2 | Single leader |
| 3 | Follower (default) |
T:302 — Get MAC Address
Section titled “T:302 — Get MAC Address”{"T":302}T:303 — Add Follower
Section titled “T:303 — Add Follower”{"T":303,"mac":"CC:DB:A7:5B:E4:1C"}T:304 — Remove Follower
Section titled “T:304 — Remove Follower”{"T":304,"mac":"CC:DB:A7:5B:E4:1C"}T:305 — Group Control
Section titled “T:305 — Group Control”Send to all registered peers.
{"T":305,"dev":0,"b":0,"s":0,"e":1.57,"h":1.57,"cmd":0,"megs":"hello!"}T:306 — Single Device Control
Section titled “T:306 — Single Device Control”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 — WiFi Mode on Boot
Section titled “T:401 — WiFi Mode on Boot”{"T":401,"cmd":3}cmd | Mode |
|---|---|
| 0 | Off |
| 1 | AP |
| 2 | STA |
| 3 | AP+STA |
T:402 — Set AP Credentials
Section titled “T:402 — Set AP Credentials”{"T":402,"ssid":"RoArm-M2","password":"12345678"}T:403 — Set STA Credentials
Section titled “T:403 — Set STA Credentials”{"T":403,"ssid":"YourNetwork","password":"YourPassword"}T:404 — Set AP+STA Credentials
Section titled “T:404 — Set AP+STA Credentials”{"T":404,"ap_ssid":"RoArm-M2","ap_password":"12345678","sta_ssid":"YourNetwork","sta_password":"YourPassword"}T:405 — Get WiFi Info
Section titled “T:405 — Get WiFi Info”{"T":405}T:406 — Save WiFi Config (from status)
Section titled “T:406 — Save WiFi Config (from status)”{"T":406}T:407 — Save WiFi Config (from input)
Section titled “T:407 — Save WiFi Config (from input)”{"T":407,"mode":3,"ap_ssid":"RoArm-M2","ap_password":"12345678","sta_ssid":"YourNetwork","sta_password":"YourPassword"}T:408 — Disconnect WiFi
Section titled “T:408 — Disconnect WiFi”{"T":408}Servo Settings
Section titled “Servo Settings”T:501 — Change Servo ID
Section titled “T:501 — Change Servo ID”{"T":501,"raw":1,"new":11}T:502 — Set Middle Position
Section titled “T:502 — Set Middle Position”Define the current position as the servo’s center (middle) point.
{"T":502,"id":11}T:503 — Set Servo PID
Section titled “T:503 — Set Servo PID”{"T":503,"id":14,"p":16}System
Section titled “System”T:600 — Reboot
Section titled “T:600 — Reboot”{"T":600}T:601 — Free Flash Space
Section titled “T:601 — Free Flash Space”{"T":601}T:602 — Boot Mission Info
Section titled “T:602 — Boot Mission Info”Check if a mission is configured to run at startup.
{"T":602}T:603 — Reset Boot Mission
Section titled “T:603 — Reset Boot Mission”Clear the boot mission so nothing runs at startup.
{"T":603}T:604 — Clear NVS
Section titled “T:604 — Clear NVS”Clear non-volatile storage. Useful for WiFi recovery.
{"T":604}T:605 — Debug Output Control
Section titled “T:605 — Debug Output Control”{"T":605,"cmd":1}cmd | Behavior |
|---|---|
| 0 | Silent |
| 1 | Debug info (default) |
| 2 | Flow feedback |
Command reference sourced from firmware json_cmd.h (January 2025 release). Waveshare GitHub.