Firmware Walkthrough
This page walks through the structure of the RoArm-M2 example firmware (version 0.84, dated 2026-01-15). The firmware runs on the onboard ESP32 and handles everything from servo bus control to WiFi, HTTP, ESP-NOW, mission recording, and the embedded web interface.
File Map
Section titled “File Map”The firmware is a single Arduino sketch (.ino) that #includes 12 header files. There are no .cpp compilation units — everything shares a single flat namespace with global state.
graph TD
INO["RoArm-M2_example.ino<br/><em>setup() + loop()</em>"]
INO --> CFG["RoArm-M2_config.h<br/><em>pin defs, servo IDs, link lengths</em>"]
INO --> BAT["battery_ctrl.h<br/><em>INA219 voltage/current</em>"]
INO --> OLED["oled_ctrl.h<br/><em>SSD1306 128×32 display</em>"]
INO --> MOD["RoArm-M2_module.h<br/><em>servo control, IK, motion</em>"]
INO --> SW["switch_module.h<br/><em>12V PWM outputs</em>"]
INO --> JSON["json_cmd.h<br/><em>T-code constant definitions</em>"]
INO --> FS["files_ctrl.h<br/><em>LittleFS file operations</em>"]
INO --> ADV["RoArm-M2_advance.h<br/><em>mission system, EoAT config</em>"]
INO --> WIFI["wifi_ctrl.h<br/><em>AP/STA/AP+STA management</em>"]
INO --> NOW["esp_now_ctrl.h<br/><em>peer-to-peer wireless</em>"]
INO --> UART["uart_ctrl.h<br/><em>JSON command dispatch</em>"]
INO --> HTTP["http_server.h<br/><em>WebServer on port 80</em>"]
INO --> WEB["m2_web_page.h<br/><em>embedded HTML (~81KB)</em>"]
| File | Size | Role |
|---|---|---|
RoArm-M2_example.ino | 188 lines | Entry point — setup() and loop() |
RoArm-M2_config.h | 301 lines | All pin definitions, servo IDs, link lengths, defaults |
RoArm-M2_module.h | 1289 lines | Core: servo init, joint control, IK solver, FK, interpolation, feedback |
uart_ctrl.h | 404 lines | JSON command dispatch (giant switch statement) and serial input |
json_cmd.h | 442 lines | T-code constant definitions (CMD_STOP = 0, CMD_JOINT_RAD = 102, etc.) |
RoArm-M2_advance.h | 361 lines | Mission record/playback, EoAT mode switching |
wifi_ctrl.h | 397 lines | WiFi mode management, config persistence |
esp_now_ctrl.h | 332 lines | ESP-NOW leader/follower/broadcast control |
files_ctrl.h | 319 lines | LittleFS CRUD: create, read, delete, insert, replace lines |
http_server.h | 41 lines | WebServer routes and /js JSON endpoint |
switch_module.h | 94 lines | H-bridge driver for 12V output channels |
oled_ctrl.h | 42 lines | SSD1306 128×32 OLED with 4-line text buffer |
battery_ctrl.h | 28 lines | INA219 power monitor at I2C address 0x42 |
m2_web_page.h | ~81KB | Embedded HTML/JS/CSS for the web control interface |
Boot Sequence
Section titled “Boot Sequence”The setup() function initializes subsystems in a specific order, displaying progress on the OLED:
- Serial and I2C —
Serial.begin(115200)for debug/UART commands,Wire.begin(32, 33)for I2C bus (OLED + INA219) - OLED display — SSD1306 at address 0x3C, 128×32 pixels. Each subsequent init step updates the display with status text
- LittleFS — Mounts the flash filesystem. All persistent data (WiFi config, missions, boot commands) lives here
- 12V switch pins — Configures the H-bridge GPIOs and attaches PWM channels for the two 12V output ports
- INA219 power monitor — Initializes at I2C address 0x42 with 9-bit ADC mode, ±320mV shunt range, 16V bus range, 0.01Ω shunt resistor
- Servo bus —
Serial1.begin(1000000, SERIAL_8N1, 18, 19)— 1Mbps half-duplex TTL on GPIO 18/19 - Servo init check — Pings servo IDs 11–15 to verify they respond. OLED shows per-servo pass/fail status
- Move to init position — Sequential homing: base → shoulder (dual-drive calibration) → elbow → gripper. The shoulder driven servo’s offset is calibrated against the driving servo during this phase
- PID reset — Sets all servo P-gain to 16 (firmware default is lower than the servo’s factory 32), I-gain to 0
- Torque reset — All joints set to
ST_TORQUE_MAX(1000) - WiFi — Loads
wifiConfig.jsonfrom flash, starts in saved mode (default: AP “RoArm-M2” / “12345678”) - HTTP server — WebServer on port 80 with routes for the web interface and
/jsJSON endpoint - ESP-NOW — Registers send/receive callbacks, configures channel 0, no encryption
- Boot mission — Calls
missionPlay("boot", 1)to execute any saved startup commands fromboot.mission - Gripper torque — Sets gripper to low torque (300) for safe initial gripping force
Main Loop
Section titled “Main Loop”The loop() function runs a tight cooperative event loop with no RTOS tasks or interrupts for motion control:
void loop() { serialCtrl(); // 1. Process UART JSON input server.handleClient(); // 2. Handle HTTP requests
if (millis() - prev_time >= 10) { constantHandle(); // 3. Velocity-mode tick (100Hz) prev_time = millis(); }
RoArmM2_getPosByServoFeedback(); // 4. Poll servo positions
switch(espNowMode) { // 5. ESP-NOW flow control case 1: espNowGroupDevsFlowCtrl(); break; case 2: espNowSingleDevFlowCtrl(); break; }
if (InfoPrint == 2) { RoArmM2_infoFeedback(); // 6. Continuous telemetry }
if (runNewJsonCmd) { // 7. Deferred command execution jsonCmdReceiveHandler(); jsonCmdReceive.clear(); runNewJsonCmd = false; }}Execution Model
Section titled “Execution Model”The loop processes events cooperatively — there’s no preemption. Each subsystem gets a slice:
| Step | Function | Frequency | Blocking? |
|---|---|---|---|
| Serial input | serialCtrl() | Every loop | No (char-by-char) |
| HTTP requests | server.handleClient() | Every loop | Brief (per-request) |
| Velocity tick | constantHandle() | 100 Hz (10ms) | No |
| Servo feedback | RoArmM2_getPosByServoFeedback() | Every loop | Brief (serial round-trip) |
| ESP-NOW flow | espNowGroupDevsFlowCtrl() | Every loop (modes 1/2 only) | No |
| Telemetry | RoArmM2_infoFeedback() | Every loop (InfoPrint=2 only) | No |
| Deferred commands | jsonCmdReceiveHandler() | On flag | Yes (motion commands block) |
Velocity Mode (constantHandle)
Section titled “Velocity Mode (constantHandle)”When the web GUI sends a continuous-motion command (T:123), the firmware enters “constant control” mode. The constantHandle() function, called at 100Hz, increments the target position by const_spd each tick:
- Joint mode — Increments the selected joint angle by
const_spdradians per tick - Cartesian mode — Increments
x,y, orzbyconst_spdmm per tick - Stop — Setting
const_spd = 0or sending T:123 with axis 255 stops motion
This is the mechanism behind the “hold-to-move” buttons in the web interface. The 10ms tick rate provides smooth motion at up to ~6°/s per unit of const_spd.
Command Dispatch
Section titled “Command Dispatch”All control goes through a single JSON-over-serial protocol. Every command is a JSON object with a T field identifying the T-code:
{"T":102,"base":0,"shoulder":0,"elbow":1.57,"hand":1.57,"spd":0,"acc":10}Input Paths
Section titled “Input Paths”Three input paths feed the same dispatcher:
graph LR
UART["UART Serial<br/>115200 baud"] -->|synchronous| DISPATCH["jsonCmdReceiveHandler()"]
HTTP["HTTP /js endpoint<br/>port 80"] -->|deferred via flag| DISPATCH
NOW["ESP-NOW<br/>peer wireless"] -->|deferred or sync| DISPATCH
DISPATCH --> ACTIONS["Servo control<br/>WiFi config<br/>File ops<br/>Mission play<br/>..."]
UART — serialCtrl() reads characters one-at-a-time from Serial until a newline. Once a complete line arrives, it deserializes into jsonCmdReceive and calls jsonCmdReceiveHandler() immediately.
HTTP — The /js endpoint takes the first query argument as a JSON string, deserializes it, calls the handler, serializes the response to jsonInfoHttp, and returns it. This path runs inside server.handleClient().
ESP-NOW — The receive callback (OnDataRecv) handles three sub-modes: cmd=0 directly sets joint angles via RoArmM2_allJointAbsCtrl() (bypassing JSON dispatch entirely for low-latency mirroring), cmd=1 calls the handler synchronously, and cmd=2 sets the deferred flag.
The Switch Statement
Section titled “The Switch Statement”jsonCmdReceiveHandler() in uart_ctrl.h is a ~300-line switch statement that maps every T-code to its handler:
void jsonCmdReceiveHandler() { int cmdCode = cycleJsonCmd["T"]; switch(cmdCode) { case CMD_STOP: // T:0 emergencyStopFlag = true; // ... stop all servos, switches break; case CMD_JOINT_SINGLE: // T:101 RoArmM2_singleJointAbsCtrl( cycleJsonCmd["joint"], cycleJsonCmd["rad"], cycleJsonCmd["spd"], cycleJsonCmd["acc"]); break; case CMD_JOINT_RAD: // T:102 RoArmM2_allJointAbsCtrl( cycleJsonCmd["base"], cycleJsonCmd["shoulder"], cycleJsonCmd["elbow"], cycleJsonCmd["hand"], cycleJsonCmd["spd"], cycleJsonCmd["acc"]); break; // ... 50+ more cases }}The T-code constants are defined in json_cmd.h:
| Range | Category | Examples |
|---|---|---|
| 0 | Emergency stop | T:0 (stop), T:999 (reset) |
| 1–2 | EoAT configuration | T:1 (mode), T:2 (dimensions) |
| 100–123 | Arm control | T:101 (single joint), T:102 (all joints rad), T:104 (XYZ goal), T:105 (feedback) |
| 200–208 | File system | T:200 (scan), T:201 (create), T:202 (read), T:203 (delete) |
| 210 | Torque lock | T:210 (lock/unlock all servos) |
| 220–242 | Mission system | T:220 (create), T:230 (append step), T:241 (play) |
| 300–306 | ESP-NOW | T:300 (follower mode), T:303 (add peer), T:305 (group send) |
| 401–408 | WiFi | T:401 (mode), T:404 (STA config), T:406 (info) |
| 501–503 | Servo settings | T:501 (change ID), T:502 (set middle), T:503 (set PID) |
| 600–605 | System | T:600 (reboot), T:603 (boot mission), T:605 (info print mode) |
Servo Control Layer
Section titled “Servo Control Layer”Bus Architecture
Section titled “Bus Architecture”The arm uses Feetech ST3215/ST3235 serial bus servos connected in a daisy chain on a single half-duplex TTL line at 1Mbps:
ESP32 GPIO18/19 ──TTL──▶ Servo 11 (base) ──▶ Servo 12 (shoulder drive) ──▶ Servo 13 (shoulder driven) ──▶ Servo 14 (elbow) ──▶ Servo 15 (gripper)The SCServo library handles the half-duplex protocol. The firmware uses two main write paths:
- Individual writes —
st.WritePosEx(id, pos, speed, acc)for single-joint commands - Sync writes —
st.SyncWritePosEx(ids[], count, positions[], speeds[], accs[])for coordinated multi-joint motion
Joint-to-Servo Mapping
Section titled “Joint-to-Servo Mapping”Each joint control function converts radians to the servo’s native position units (0–4095 for 360°):
void RoArmM2_baseJointCtrlRad(float radInput, int workinSpd, int workinAcc) { goalPos[0] = (int)(radInput / (2*PI) * SERVO_STEPS + SERVO_MIDDLE); st.WritePosEx(servoID[0], goalPos[0], workinSpd, workinAcc);}The conversion formula: position = (radians / 2π) × 4096 + 2048
where 2048 is the servo’s mechanical center. Positive radians map to increasing position values.
Dual-Drive Shoulder
Section titled “Dual-Drive Shoulder”The shoulder is special — it uses two servos (IDs 12 and 13) mechanically coupled to double the torque. The driving servo (12) commands a position, and the driven servo (13) mirrors it with an inverted direction and an offset calibrated at boot:
void RoArmM2_shoulderJointCtrlRad(float radInput, int workinSpd, int workinAcc) { goalPos[1] = (int)(-radInput / (2*PI) * SERVO_STEPS + SERVO_MIDDLE); goalPos[2] = (int)( radInput / (2*PI) * SERVO_STEPS + SERVO_MIDDLE) + shoulderDrivenOffset; st.WritePosEx(servoID[1], goalPos[1], workinSpd, workinAcc); st.WritePosEx(servoID[2], goalPos[2], workinSpd, workinAcc);}Note the negated sign on goalPos[1] — the two servos rotate in opposite directions to produce additive torque through the mechanical linkage.
Sync Write for Coordinated Motion
Section titled “Sync Write for Coordinated Motion”When all joints need to move simultaneously, goalPosMove() collects all goalPos[] values and fires a single SyncWritePosEx:
void RoArmM2_goalPosMove(int workinSpd, int workinAcc) { RoArmM2_computeGoalPosByJointRad(); u8 idArr[5] = {11, 12, 13, 14, 15}; s16 posArr[5] = {goalPos[0], goalPos[1], goalPos[2], goalPos[3], goalPos[4]}; s16 spdArr[5] = {workinSpd, workinSpd, workinSpd, workinSpd, workinSpd}; u8 accArr[5] = {workinAcc, workinAcc, workinAcc, workinAcc, workinAcc}; st.SyncWritePosEx(idArr, 5, posArr, spdArr, accArr);}The sync write ensures all servos begin moving on the same bus cycle, preventing the “sequential start” jitter that individual writes would cause.
Inverse Kinematics
Section titled “Inverse Kinematics”The IK solver reduces the 4-DOF arm to a 2-link planar problem in the XZ plane, with the base rotation handled separately as a polar coordinate.
Coordinate System
Section titled “Coordinate System” Z (up) │ │ │ EE (end effector) │ ╱ │ ╱ L3 │ ╱ │ ╱ │ ● Elbow │ ╱ │ ╱ L2 │ ╱ │╱ ● Shoulder ──────── X (forward) │ │ L1 │ ═══ Base (rotates in XY plane)The base rotation is computed first as atan2(y, x), projecting the target into the arm’s plane. The remaining 3 joints are solved in the radial-vertical plane.
The 2-Link Solver
Section titled “The 2-Link Solver”simpleLinkageIkRad() solves the classic two-link arm for shoulder and elbow angles:
void simpleLinkageIkRad(float LA, float LB, float aIn, float bIn) { float A = aIn; // radial distance to target float B = bIn; // vertical distance to target float C = sqrt(A*A + B*B);
// Law of cosines for elbow angle float elbowCos = (LA*LA + LB*LB - C*C) / (2*LA*LB); ELBOW_JOINT_RAD = PI - acos(elbowCos);
// Shoulder angle: angle to target minus internal triangle angle float shoulderAngle = atan2(B, A); float internalAngle = acos((LA*LA + C*C - LB*LB) / (2*LA*C)); SHOULDER_JOINT_RAD = shoulderAngle + internalAngle;}The function also computes EOAT_JOINT_RAD_BUFFER — the angle needed to maintain the end-effector’s requested tilt relative to the world frame. This is the t parameter from Cartesian commands — the firmware subtracts the shoulder and elbow contributions so the gripper/wrist maintains the desired orientation regardless of the arm’s configuration.
EoAT Mode Branching
Section titled “EoAT Mode Branching”The Cartesian control function (RoArmM2_baseCoordinateCtrl) takes different code paths depending on the end-effector mode:
Mode 0 (gripper) — Straightforward 2-link IK. The gripper angle parameter t controls the tool orientation directly. L3 includes the gripper mounting offset (L4A=67.85mm, L4B=5.98mm).
Mode 1 (wrist) — More complex. The target point is projected backward along the L4 vector (accounting for the wrist link), the 2-link IK solves for the intermediate point, and the wrist joint angle is computed to achieve the requested world-frame tilt. This mode uses rotatePoint() and movePoint() helper functions for the geometric transformations.
NaN Guard
Section titled “NaN Guard”Every IK computation is checked with isnan():
nanIK = isnan(SHOULDER_JOINT_RAD) || isnan(ELBOW_JOINT_RAD) || isnan(EOAT_JOINT_RAD_BUFFER);If the target is unreachable (outside the workspace envelope), the IK solver produces NaN through acos() of a value outside [-1, 1]. When this happens, the firmware silently discards the command and retains the previous joint angles. There is no error response to the caller — the arm simply doesn’t move.
Motion Interpolation
Section titled “Motion Interpolation”The firmware provides two motion strategies: direct servo commands (the servo’s own profile generator handles acceleration) and firmware-side cosine interpolation for smooth multi-waypoint paths.
Cosine Curve (“Bessel”)
Section titled “Cosine Curve (“Bessel”)”The function besselCtrl() generates a smooth S-curve using a cosine ramp — despite the name, it’s not a Bézier curve:
float besselCtrl(float inputVal, float outputVal, float steps, float currentStep) { float factor = (1 - cos(PI * currentStep / steps)) / 2.0; return inputVal + (outputVal - inputVal) * factor;}This produces ease-in/ease-out motion: slow start, fast middle, slow end. The spd parameter in T:104 commands controls the step size, which determines how many intermediate points are generated.
Interpolated Cartesian Move (T:104)
Section titled “Interpolated Cartesian Move (T:104)”RoArmM2_movePosGoalfromLast() implements the interpolated move:
- Captures current position as the start point
- Divides the path into steps based on the
spdparameter - For each step, computes an intermediate XYZ target using
besselCtrl()on each axis - Runs IK on the intermediate point
- If IK produces NaN (unreachable), reverts to the previous valid position
- Commands all servos via
goalPosMove()with speed=0 (max speed) — the interpolation handles the velocity profile, not the servo - Inserts a brief delay between steps for the servo bus to process
Mission System
Section titled “Mission System”The mission system (RoArm-M2_advance.h) provides record-and-playback functionality. Missions are stored as plain-text files on LittleFS where each line is a JSON command.
File Format
Section titled “File Format”{"name":"pick-and-place","intro":"Demo pick sequence"}{"T":104,"x":200,"y":0,"z":100,"t":0,"spd":0.25}{"T":107,"tor":200}{"T":104,"x":200,"y":100,"z":150,"t":0,"spd":0.25}{"T":106,"cmd":3.14,"spd":0,"acc":0}Line 1 is metadata (name + description). Lines 2+ are steps — each is a complete JSON command that gets fed back through jsonCmdReceiveHandler().
CRUD Operations
Section titled “CRUD Operations”| T-Code | Function | Description |
|---|---|---|
| T:220 | createMission() | Create new mission file with metadata |
| T:221 | Read mission | Dump all lines to serial/HTTP |
| T:230 | appendStepJson() | Append a JSON command as a new step |
| T:231 | appendStepFB() | Append the current arm position as a step (teach mode) |
| T:232–234 | Insert/Replace | Insert or replace steps at a line number |
| T:235 | deleteStep() | Delete a step by line number |
| T:241 | missionPlay() | Execute all steps sequentially |
| T:242 | Stop | Abort a running mission |
Playback
Section titled “Playback”missionPlay() reads each line from the mission file, deserializes it as JSON, and calls jsonCmdReceiveHandler() recursively. Between steps, it checks for serial input — if a stop command arrives, playback aborts. The repeat parameter supports infinite loops (-1).
Boot Mission
Section titled “Boot Mission”A special mission named boot runs automatically during setup(). This lets users configure startup behavior (initial position, torque limits, WiFi commands) by appending steps to the boot mission via T:230.
Communication Stack
Section titled “Communication Stack”WiFi Management
Section titled “WiFi Management”The firmware supports four WiFi modes, persisted in /wifiConfig.json on LittleFS:
| Mode | Code | Behavior |
|---|---|---|
| OFF | 0 | WiFi disabled |
| AP | 1 | Access point: SSID “RoArm-M2”, password “12345678” |
| STA | 2 | Station: connects to configured network |
| AP+STA | 3 | Both simultaneously |
Default is AP mode. After a successful STA connection, the firmware auto-upgrades to AP+STA so the device remains discoverable on its own network while also joining the user’s WiFi. Connection timeout is 15 seconds — on failure, it falls back to AP mode.
HTTP Server
Section titled “HTTP Server”The WebServer (not AsyncWebServer, despite a comment in the source) serves three pages and one API endpoint:
| Route | Handler | Purpose |
|---|---|---|
/ | index_html | Main control web interface |
/horiDrag | horizontal_drag_html | Horizontal drag control page |
/vertDrag | vertical_drag_html | Vertical drag control page |
/js?{json} | JSON dispatcher | All JSON commands go through here |
The /js endpoint is simple — the entire JSON command is passed as the first query argument:
http://192.168.4.1/js?json={"T":105}The response is the contents of jsonInfoHttp, serialized as JSON with content type text/plane (sic — a typo in the firmware, should be text/plain).
Serial at 115200 baud. Input is read character-by-character until a newline. The complete line is deserialized as JSON and dispatched synchronously — unlike HTTP, there’s no deferred execution flag.
ESP-NOW
Section titled “ESP-NOW”ESP-NOW provides low-latency peer-to-peer wireless control without WiFi infrastructure. The firmware supports four roles:
| Mode | Code | Description |
|---|---|---|
| None | 0 | ESP-NOW disabled |
| Group leader | 1 | Broadcasts joint angles to all peers every loop iteration |
| Single leader | 2 | Sends joint angles to one specific peer every loop iteration |
| Follower | 3 | Receives and executes commands from a leader |
The message struct carries joint angles as floats plus a cmd byte and a 210-char message buffer:
typedef struct struct_message { byte devCode; float base, shoulder, elbow, hand; byte cmd; char message[210];} struct_message;The cmd byte determines how the message is processed:
- cmd=0 — Direct joint control (low-latency mirror mode, bypasses JSON dispatch)
- cmd=1 — JSON command in
message[], processed synchronously - cmd=2 — JSON command in
message[], deferred to next loop iteration - cmd=3 — Print message to serial (debug)
A follower can optionally restrict which leader MAC addresses it accepts (ctrlByBroadcast flag with MAC whitelist).
File System (LittleFS)
Section titled “File System (LittleFS)”The ESP32’s internal flash is formatted with LittleFS and provides persistent storage for:
- WiFi configuration —
/wifiConfig.json - Missions —
*.missionfiles (see Mission System above) - Boot mission —
/boot.missionfor startup commands
File Operations (T:200–208)
Section titled “File Operations (T:200–208)”| T-Code | Operation | Notes |
|---|---|---|
| T:200 | Scan all files | Lists filenames and first lines |
| T:201 | Create file | Fails if file already exists |
| T:202 | Read file | Returns all lines with line numbers |
| T:203 | Delete file | Silently succeeds if already deleted |
| T:204 | Append line | Adds content at end of file |
| T:205 | Insert line | Inserts before a given line number |
| T:206 | Replace line | Replaces a specific line by number |
| T:207 | Delete line | Removes a specific line by number |
| T:601 | Free space | Reports total and available flash bytes |
The file operations read entire files into String arrays in RAM for line-level editing. This works for the small mission files typical on this platform but could cause memory issues with large files on the ESP32’s limited heap.
Peripheral Drivers
Section titled “Peripheral Drivers”INA219 Power Monitor
Section titled “INA219 Power Monitor”An INA219 at I2C address 0x42 monitors the supply voltage and current draw. It’s configured for:
- 9-bit ADC mode (fastest, lowest resolution)
- ±320mV shunt range with 0.01Ω resistor
- 16V bus range
The inaDataUpdate() function reads shunt voltage, bus voltage, current, and power. The load voltage is computed as busVoltage + shuntVoltage/1000. The voltage reading (multiplied by 100) is included in the T:105 feedback response as the v field.
OLED Display
Section titled “OLED Display”A 0.91” SSD1306 OLED (128×32 pixels) at I2C address 0x3C provides a 4-line status display. The firmware uses a simple model — four global String variables (screenLine_0 through screenLine_3) that are rendered on each oled_update() call. Content is set by various subsystems:
- Line 0: “RoArm-M2” (constant)
- Line 1: Version or connection info
- Line 2: Status messages (servo check, WiFi, MAC address)
- Line 3: Current operation
12V Switch Module
Section titled “12V Switch Module”Two H-bridge output channels (A and B) provide bidirectional 12V PWM control for external accessories (pneumatic valves, lights, motors). Each channel uses two direction pins and a PWM pin:
| Channel | PWM | Direction 1 | Direction 2 |
|---|---|---|---|
| A | GPIO25 | GPIO21 (AIN1) | GPIO17 (AIN2) |
| B | GPIO26 | GPIO22 (BIN1) | GPIO23 (BIN2) |
Positive PWM values drive in one direction, negative in the other. The lightCtrl() function is a convenience wrapper that drives channel A in one direction (always negative, for a unidirectional LED strip).
Configuration Constants
Section titled “Configuration Constants”Key values from RoArm-M2_config.h:
Link Lengths
Section titled “Link Lengths”| Constant | Value | Description |
|---|---|---|
L1 | 126.06 mm | Base height (shoulder above ground) |
L2A | 236.82 mm | Upper arm vertical component |
L2B | 30.00 mm | Upper arm horizontal offset |
L3A_0 | 280.15 mm | Forearm (gripper mode, includes EoAT) |
L3A_1 | 215.99 mm | Forearm (wrist mode, shorter — wrist link is separate) |
L3B_0 | 1.73 mm | Forearm lateral offset (gripper mode) |
L4A | 67.85 mm | EoAT forward offset |
L4B | 5.98 mm | EoAT lateral offset |
Servo Configuration
Section titled “Servo Configuration”| Parameter | Value |
|---|---|
| Bus speed | 1,000,000 baud |
| RXD pin | GPIO 18 |
| TXD pin | GPIO 19 |
| Servo IDs | 11 (base), 12 (shoulder drive), 13 (shoulder driven), 14 (elbow), 15 (gripper) |
| Steps per revolution | 4096 |
| Center position | 2048 |
| Default P-gain | 16 |
| Default I-gain | 0 |
| Max torque | 1000 |
| Min torque | 50 |
Default Position
Section titled “Default Position”The arm boots to: x = 310.15mm (l3A + l2B), y = 0, z = 235.09mm (l2A − l3B), with tool angle t = π (gripper pointing up). This places the arm roughly vertical with the forearm extended forward.
Source: RoArm-M2_example firmware v0.84 (2026-01-15) from the Waveshare RoArm-M2 resources. All code excerpts are from the original firmware with minor formatting for readability.