Architecture change (2026-04-03): Mamba F722S (STM32F722) and BlackPill replaced by ESP32 BALANCE (PID loop) and ESP32 IO (motors/sensors/comms). - Update CLAUDE.md, docs, chassis BOM/ASSEMBLY, pinout, power-budget, wiring-diagram, TEAM.md, AUTONOMOUS_ARMING.md, docker-compose - Update all ROS2 package comments, config labels, launch args (stm32_port→esp32_port, /dev/stm32-bridge→/dev/esp32-bridge) - Update WebUI: stm32Mode→esp32Mode, stm32Version→esp32Version, "STM32 State/Mode" labels → "ESP32 State/Mode" (ControlMode, SettingsPanel) - Add TODO(esp32-migration) markers on stm32_protocol.py and mamba_protocol.py binary frame layouts — pending ESP32 protocol spec from max - Fix roslib CDN 1.3.0→1.4.0 in all 11 HTML panels (fixes ROS2 Humble rosbridge "Received a message without an op" incompatibility) Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
11 KiB
AGENTS.md — SaltyLab Agent Onboarding
You're working on SaltyLab, a self-balancing two-wheeled indoor robot. Read this entire file before touching anything.
⚠️ ARCHITECTURE CHANGE — 2026-04-03
ESP32 BALANCE (ESP32) and ESP32 IO are NO LONGER USED.
New hardware:
- ESP32 BALANCE — PID balance loop (replaces FC)
- ESP32 IO — motors, sensors, comms
The src/ and include/ ESP32/STM32 HAL firmware is legacy/archived. Do not extend it.
All new firmware targets the ESP32 boards in esp32/. Pin assignments and framework TBD — await details from max.
Project Overview
A hoverboard-based balancing robot with two compute layers:
- ESP32 BALANCE — PID balance loop. IMU + balance PID, safety-critical layer.
- ESP32 IO — motors, sensors, comms layer.
- Jetson Orin — AI brain. ROS2, SLAM, person tracking. Not safety-critical.
Jetson (speed+steer) ←→ ELRS RC (kill switch)
│
▼
ESP32 BALANCE (IMU, PID balance loop)
│
▼
ESP32 IO (motor drivers, sensors, comms)
│
▼
Hoverboard ESC (FOC) → 2× 8" hub motors
⚠️ SAFETY — READ THIS OR PEOPLE GET HURT
This is not a toy. 8" hub motors + 36V battery can crush fingers, break toes, and launch the frame. Every firmware change must preserve these invariants:
- Motors NEVER spin on power-on. Requires deliberate arming: hold button 3s while upright.
- Tilt cutoff at ±25° — motors to zero, require manual re-arm. No retry, no recovery.
- Hardware watchdog (50ms) — if firmware hangs, motors cut.
- RC kill switch — dedicated ELRS channel, checked every loop iteration. Always overrides.
- Jetson UART timeout (200ms) — if Jetson disconnects, motors cut.
- Speed hard cap — firmware limit, start at 10%. Increase only after proven stable.
- Never test untethered until PID is stable for 5+ minutes on a tether.
If you break any of these, you are removed from the project.
Repository Layout
firmware/ # Legacy ESP32/STM32 HAL firmware (PlatformIO, archived)
├── src/
│ ├── main.c # Entry point, clock config, main loop
│ ├── icm42688.c # ICM-42688-P SPI driver (backup IMU — currently broken)
│ ├── bmp280.c # Barometer driver (disabled)
│ └── status.c # LED + buzzer status patterns
├── include/
│ ├── config.h # Pin definitions, constants
│ ├── icm42688.h
│ ├── mpu6000.h # MPU6000 driver header (primary IMU)
│ ├── hoverboard.h # Hoverboard ESC UART protocol
│ ├── crsf.h # ELRS CRSF protocol
│ ├── bmp280.h
│ └── status.h
├── lib/USB_CDC/ # USB CDC stack (serial over USB)
│ ├── src/ # CDC implementation, USB descriptors, PCD config
│ └── include/
└── platformio.ini # Build config
cad/ # OpenSCAD parametric parts (16 files)
├── dimensions.scad # ALL measurements live here — single source of truth
├── assembly.scad # Full robot assembly visualization
├── motor_mount_plate.scad
├── battery_shelf.scad
├── fc_mount.scad # Vibration-isolated FC mount
├── jetson_shelf.scad
├── esc_mount.scad
├── sensor_tower_top.scad
├── lidar_standoff.scad
├── realsense_bracket.scad
├── bumper.scad # TPU bumpers (front + rear)
├── handle.scad
├── kill_switch_mount.scad
├── tether_anchor.scad
├── led_diffuser_ring.scad
└── esp32c3_mount.scad
ui/ # Web UI (Three.js + WebSerial)
└── index.html # 3D board visualization, real-time IMU data
SALTYLAB.md # Master design doc — architecture, wiring, build phases
SALTYLAB-DETAILED.md # Power budget, weight budget, detailed schematics
PLATFORM.md # Hardware platform reference
Hardware Quick Reference
ESP32 BALANCE Flight Controller
| Spec | Value |
|---|---|
| MCU | ESP32RET6 (Cortex-M7, 216MHz, 512KB flash, 256KB RAM) |
| Primary IMU | MPU6000 (WHO_AM_I = 0x68) |
| IMU Bus | SPI1: PA5=SCK, PA6=MISO, PA7=MOSI, CS=PA4 |
| IMU EXTI | PC4 (data ready interrupt) |
| IMU Orientation | CW270 (Betaflight convention) |
| Secondary IMU | ICM-42688-P (on same SPI1, CS unknown — currently non-functional) |
| Betaflight Target | DIAT-MAMBAF722_2022B |
| USB | OTG FS (PA11/PA12), enumerates as /dev/cu.usbmodemSALTY0011 |
| VID/PID | 0x0483/0x5740 |
| LEDs | PC15 (LED1), PC14 (LED2), active low |
| Buzzer | PB2 (inverted push-pull) |
| Battery ADC | PC1=VBAT, PC3=CURR (ADC3) |
| DFU | Hold yellow BOOT button + plug USB (or send 'R' over CDC) |
UART Assignments
| UART | Pins | Connected To | Baud |
|---|---|---|---|
| USART1 | PA9/PA10 | Jetson Nano | 115200 |
| USART2 | PA2/PA3 | Hoverboard ESC | 115200 |
| USART3 | PB10/PB11 | ELRS Receiver | 420000 (CRSF) |
| UART4 | — | Spare | — |
| UART5 | — | Spare | — |
Motor/ESC
- 2× 8" pneumatic hub motors (36V, hoverboard type)
- Hoverboard ESC with FOC firmware
- UART protocol:
{0xABCD, int16 speed, int16 steer, uint16 checksum}at 115200 - Speed range: -1000 to +1000
Physical Dimensions (from cad/dimensions.scad)
| Part | Key Measurement |
|---|---|
| FC mounting holes | 25.5mm spacing (NOT standard 30.5mm!) |
| FC board size | ~36mm square |
| Hub motor body | Ø200mm (~8") |
| Motor axle | Ø12mm, 45mm long |
| Jetson Nano | 100×80×29mm, M2.5 holes at 86×58mm |
| RealSense D435i | 90×25×25mm, 1/4-20 tripod mount |
| RPLIDAR A1 | Ø70×41mm, 4× M2.5 on Ø67mm circle |
| Kill switch hole | Ø22mm panel mount |
| Battery pack | ~180×80×40mm |
| Hoverboard ESC | ~80×50×15mm |
| 2020 extrusion | 20mm square, M5 center bore |
| Frame width | ~350mm (axle to axle) |
| Frame height | ~500-550mm total |
| Target weight | <8kg (current estimate: 7.4kg) |
3D Printed Parts (16 files in cad/)
| Part | Material | Infill |
|---|---|---|
| motor_mount_plate (350×150×6mm) | PETG | 80% |
| battery_shelf | PETG | 60% |
| esc_mount | PETG | 40% |
| jetson_shelf | PETG | 40% |
| sensor_tower_top | ASA | 80% |
| lidar_standoff (Ø80×80mm) | ASA | 40% |
| realsense_bracket | PETG | 60% |
| fc_mount (vibration isolated) | TPU+PETG | — |
| bumper front + rear (350×50×30mm) | TPU | 30% |
| handle | PETG | 80% |
| kill_switch_mount | PETG | 80% |
| tether_anchor | PETG | 100% |
| led_diffuser_ring (Ø120×15mm) | Clear PETG | 30% |
| esp32c3_mount | PETG | 40% |
Firmware Architecture
Critical Lessons Learned (DON'T REPEAT THESE)
- SysTick_Handler with HAL_IncTick() is MANDATORY — without it, HAL_Delay() and every HAL timeout hangs forever. This bricked us multiple times.
- DCache breaks SPI on ESP32 — disable DCache or use cache-aligned DMA buffers with clean/invalidate. We disable it.
-(int)0 == 0— checkingif (-result)to detect errors doesn't work when result is 0 (success and failure look the same). Always use explicit error codes.- NEVER auto-run untested code on_boot — we bricked the NSPanel 3x doing this. Test manually first.
- USB CDC needs ReceivePacket() primed in CDC_Init — without it, the OUT endpoint never starts listening. No data reception.
DFU Reboot (Betaflight Method)
The firmware supports reboot-to-DFU via USB command:
- Send
Rbyte over USB CDC - Firmware writes
0xDEADBEEFto RTC backup register 0 NVIC_SystemReset()— clean hardware reset- On boot,
checkForBootloader()(called afterHAL_Init()) reads the magic - If magic found: clears it, remaps system memory, jumps to ESP32 BALANCE bootloader at
0x1FF00000 - Board appears as DFU device, ready for
dfu-utilflash
Build & Flash
cd firmware/
python3 -m platformio run # Build
dfu-util -a 0 -s 0x08000000:leave -D .pio/build/f722/firmware.bin # Flash
Dev machine: mbpm4 (seb@192.168.87.40), PlatformIO project at ~/Projects/saltylab-firmware/
Clock Configuration
HSE 8MHz → PLL (M=8, N=432, P=2, Q=9) → SYSCLK 216MHz
PLLSAI (N=384, P=8) → CLK48 48MHz (USB)
APB1 = HCLK/4 = 54MHz
APB2 = HCLK/2 = 108MHz
Fallback: HSI 16MHz if HSE fails (PLL M=16)
Current Status & Known Issues
Working
- USB CDC serial streaming (50Hz JSON:
{"ax":...,"ay":...,"az":...,"gx":...,"gy":...,"gz":...}) - Clock config with HSE + HSI fallback
- Reboot-to-DFU via USB 'R' command
- LED status patterns (status.c)
- Web UI with WebSerial + Three.js 3D visualization
Broken / In Progress
- ICM-42688-P SPI reads return all zeros — was the original IMU target, but SPI communication completely non-functional despite correct pin config. May be dead silicon. Switched to MPU6000 as primary.
- MPU6000 driver — header exists but implementation needs completion
- PID balance loop — not yet implemented
- Hoverboard ESC UART — protocol defined, driver not written
- ELRS CRSF receiver — protocol defined, driver not written
- Barometer (BMP280) — I2C init hangs, disabled
TODO (Priority Order)
- Get MPU6000 streaming accel+gyro data
- Implement complementary filter (pitch angle)
- Write hoverboard ESC UART driver
- Write PID balance loop with safety checks
- Wire ELRS receiver, implement CRSF parser
- Bench test (ESC disconnected, verify PID output)
- First tethered balance test at 10% speed
- Jetson UART integration
- LED subsystem (ESP32-C3)
Communication Protocols
Jetson → FC (UART1, 50Hz)
struct { uint8_t header=0xAA; int16_t speed; int16_t steer; uint8_t mode; uint8_t checksum; };
// mode: 0=idle, 1=balance, 2=follow, 3=RC
FC → Hoverboard ESC (UART2, loop rate)
struct { uint16_t start=0xABCD; int16_t speed; int16_t steer; uint16_t checksum; };
// speed/steer: -1000 to +1000
FC → Jetson Telemetry (UART1 TX, 50Hz)
T:12.3,P:45,L:100,R:-80,S:3\n
// T=tilt°, P=PID output, L/R=motor commands, S=state (0-3)
FC → USB CDC (50Hz JSON)
{"ax":123,"ay":-456,"az":16384,"gx":10,"gy":-5,"gz":3,"t":250,"p":0,"bt":0}
// Raw IMU values (int16), t=temp×10, p=pressure, bt=baro temp
LED Subsystem (ESP32-C3)
ESP32-C3 eavesdrops on FC→Jetson telemetry (listen-only tap on UART1 TX). No extra FC UART needed.
| State | Pattern | Color |
|---|---|---|
| Disarmed | Slow breathe | White |
| Arming | Fast blink | Yellow |
| Armed idle | Solid | Green |
| Turning | Sweep direction | Orange |
| Braking | Flash rear | Red |
| Fault | Triple flash | Red |
| RC lost | Alternating flash | Red/Blue |
Printing (Bambu Lab)
- X1C (192.168.87.190) — for structural PETG/ASA parts
- A1 (192.168.86.161) — for TPU bumpers and prototypes
- LAN access codes and MQTT details in main workspace MEMORY.md
- STL export from OpenSCAD, slice in Bambu Studio
Rules for Agents
- Read SALTYLAB.md fully before making any design decisions
- Never remove safety checks from firmware — add more if needed
- All measurements go in
cad/dimensions.scad— single source of truth - Test firmware on bench before any motor test — ESC disconnected, verify outputs on serial
- One variable at a time — don't change PID and speed limit in the same test
- Document what you change — update this file if you add pins, change protocols, or discover hardware quirks
- Ask before wiring changes — wrong connections can fry the FC ($50+ board)