Complete hardware reference from hal@Orin spec (2026-04-04): - docs/SAUL-TEE-SYSTEM-REFERENCE.md: authoritative pin/protocol/CAN reference ESP32-S3 BALANCE: QMI8658 SPI(IO38-42), GC9A01 LCD, SN65HVD230 CAN(IO43/44), inter-board UART(IO17/18) ESP32-S3 IO: Crossfire UART0(IO43/44), ELRS UART2(IO16/17), BTS7960(IO1-8), I2C(IO11/12), WS2812(IO13), buzzer/headlight/fan, arming btn, kill-sw, UART(IO18/21) - Inter-board binary protocol: [0xAA][LEN][TYPE][PAYLOAD][CRC8] @ 460800 baud - CAN: VESC L=68, R=56; Orin cmds 0x300-0x303; telemetry 0x400-0x401 @ 10Hz - RC: CH5=ARM, CH6=ESTOP, CH7=speed-limit; CRSF loss >100ms = motors cut - CLAUDE.md, TEAM.md, docs/AGENTS.md, docs/SALTYLAB.md updated with full spec Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
223 lines
7.4 KiB
Markdown
223 lines
7.4 KiB
Markdown
# SAUL-TEE System Reference — SaltyLab ESP32 Architecture
|
||
*Authoritative source of truth for hardware, pins, protocols, and CAN assignments.*
|
||
*Spec from hal@Orin, 2026-04-04.*
|
||
|
||
---
|
||
|
||
## Overview
|
||
|
||
| Board | Role | MCU | USB chip |
|
||
|-------|------|-----|----------|
|
||
| **ESP32-S3 BALANCE** | PID balance loop, CAN→VESCs, LCD display | ESP32-S3 | CH343 USB-serial |
|
||
| **ESP32-S3 IO** | RC input, motor drivers, sensors, LEDs, peripherals | ESP32-S3 | JTAG USB (native) |
|
||
|
||
**Robot form factor:** 4-wheel wagon — 870 × 510 × 550 mm, ~23 kg
|
||
**Power:** 36 V LiPo, DC-DC → 5 V and 12 V rails
|
||
**Orin connection:** CANable2 USB → 500 kbps CAN (same bus as VESCs)
|
||
|
||
---
|
||
|
||
## ESP32-S3 BALANCE
|
||
|
||
### Board
|
||
Waveshare ESP32-S3 Touch LCD 1.28
|
||
- GC9A01 round 240×240 LCD
|
||
- CST816S capacitive touch
|
||
- QMI8658 6-axis IMU (accel + gyro, SPI)
|
||
- CH343 USB-to-serial chip
|
||
|
||
### Pin Assignments
|
||
|
||
| Function | GPIO | Notes |
|
||
|----------|------|-------|
|
||
| **QMI8658 IMU (SPI)** | | |
|
||
| SCK | IO39 | |
|
||
| MOSI | IO38 | |
|
||
| MISO | IO40 | |
|
||
| CS | IO41 | |
|
||
| INT1 | IO42 | data-ready interrupt |
|
||
| **GC9A01 LCD (shares SPI bus)** | | |
|
||
| CS | IO12 | |
|
||
| DC | IO11 | |
|
||
| RST | IO10 | |
|
||
| BL | IO9 | PWM backlight |
|
||
| **CST816S Touch (I2C)** | | |
|
||
| SDA | IO4 | |
|
||
| SCL | IO5 | |
|
||
| INT | IO6 | |
|
||
| RST | IO7 | |
|
||
| **CAN — SN65HVD230 transceiver** | | 500 kbps |
|
||
| TX | IO43 | → SN65HVD230 TXD |
|
||
| RX | IO44 | ← SN65HVD230 RXD |
|
||
| **Inter-board UART (to IO board)** | | 460800 baud |
|
||
| TX | IO17 | |
|
||
| RX | IO18 | |
|
||
|
||
### Responsibilities
|
||
- Read QMI8658 @ 1 kHz (SPI, INT1-driven)
|
||
- Complementary filter → pitch angle
|
||
- PID balance loop (configurable Kp / Ki / Kd)
|
||
- Send VESC speed commands via CAN (ID 68 = left, ID 56 = right)
|
||
- Receive Orin velocity+mode commands via CAN (0x300–0x303)
|
||
- Receive IO board status (arming, RC, faults) via UART protocol
|
||
- Drive GC9A01 LCD: pitch, speed, battery %, error state
|
||
- Enforce tilt cutoff at ±25°; IWDG 50 ms timeout
|
||
- Publish telemetry on CAN 0x400–0x401 at 10 Hz
|
||
|
||
---
|
||
|
||
## ESP32-S3 IO
|
||
|
||
### Board
|
||
Bare ESP32-S3 devkit (JTAG USB)
|
||
|
||
### Pin Assignments
|
||
|
||
| Function | GPIO | Notes |
|
||
|----------|------|-------|
|
||
| **TBS Crossfire RC — UART0 (primary)** | | |
|
||
| RX | IO44 | CRSF frames from Crossfire RX |
|
||
| TX | IO43 | telemetry to Crossfire TX |
|
||
| **ELRS failover — UART2** | | active if CRSF absent >100 ms |
|
||
| RX | IO16 | |
|
||
| TX | IO17 | |
|
||
| **BTS7960 Motor Driver — Left** | | |
|
||
| RPWM | IO1 | forward PWM |
|
||
| LPWM | IO2 | reverse PWM |
|
||
| R_EN | IO3 | right enable |
|
||
| L_EN | IO4 | left enable |
|
||
| **BTS7960 Motor Driver — Right** | | |
|
||
| RPWM | IO5 | |
|
||
| LPWM | IO6 | |
|
||
| R_EN | IO7 | |
|
||
| L_EN | IO8 | |
|
||
| **I2C bus** | | |
|
||
| SDA | IO11 | |
|
||
| SCL | IO12 | |
|
||
| NFC (PN532 or similar) | I2C | |
|
||
| Barometer (BMP280/BMP388) | I2C | |
|
||
| ToF (VL53L0X/VL53L1X) | I2C | |
|
||
| **WS2812B LEDs** | | |
|
||
| Data | IO13 | |
|
||
| **Outputs** | | |
|
||
| Horn / buzzer | IO14 | PWM tone |
|
||
| Headlight | IO15 | PWM or digital |
|
||
| Fan | IO16 | (if ELRS not fitted on UART2) |
|
||
| **Inputs** | | |
|
||
| Arming button | IO9 | active-low, hold 3 s to arm |
|
||
| Kill switch sense | IO10 | hardware estop detect |
|
||
| **Inter-board UART (to BALANCE board)** | | 460800 baud |
|
||
| TX | IO18 | |
|
||
| RX | IO21 | |
|
||
|
||
### Responsibilities
|
||
- Parse CRSF frames (TBS Crossfire, primary)
|
||
- Parse ELRS frames (failover, activates if no CRSF for >100 ms)
|
||
- Drive BTS7960 left/right PWM motor drivers
|
||
- Read NFC, barometer, ToF via I2C
|
||
- Drive WS2812B LEDs (armed/fault/idle patterns)
|
||
- Control horn, headlight, fan, buzzer
|
||
- Manage arming: hold button 3 s while upright → send ARM to BALANCE
|
||
- Monitor kill switch input → immediate motor off + FAULT frame
|
||
- Forward RC + sensor data to BALANCE via binary UART protocol
|
||
- Report faults and RC-loss upstream
|
||
|
||
---
|
||
|
||
## Inter-Board Binary Protocol (UART @ 460800 baud)
|
||
|
||
```
|
||
[0xAA][LEN][TYPE][PAYLOAD × LEN bytes][CRC8]
|
||
```
|
||
- `0xAA` — start byte
|
||
- `LEN` — payload length in bytes (uint8)
|
||
- `TYPE` — message type (uint8)
|
||
- `CRC8` — CRC-8/MAXIM over TYPE + PAYLOAD bytes
|
||
|
||
### IO → BALANCE Messages
|
||
|
||
| TYPE | Name | Payload | Description |
|
||
|------|------|---------|-------------|
|
||
| 0x01 | RC_CMD | int16 throttle, int16 steer, uint8 flags | flags: bit0=armed, bit1=kill |
|
||
| 0x02 | SENSOR | uint16 tof_mm, int16 baro_delta_pa, uint8 nfc_present | |
|
||
| 0x03 | FAULT | uint8 fault_flags | bit0=rc_loss, bit1=motor_fault, bit2=estop |
|
||
|
||
### BALANCE → IO Messages
|
||
|
||
| TYPE | Name | Payload | Description |
|
||
|------|------|---------|-------------|
|
||
| 0x10 | STATE | int16 pitch_x100, int16 pid_out, uint8 error_state | |
|
||
| 0x11 | LED_CMD | uint8 pattern, uint8 r, uint8 g, uint8 b | |
|
||
| 0x12 | BUZZER | uint8 tone_id, uint16 duration_ms | |
|
||
|
||
---
|
||
|
||
## CAN Bus — 500 kbps
|
||
|
||
### Node Assignments
|
||
|
||
| Node | CAN ID | Role |
|
||
|------|--------|------|
|
||
| VESC Left motor | **68** | Receives speed/duty via VESC CAN protocol |
|
||
| VESC Right motor | **56** | Receives speed/duty via VESC CAN protocol |
|
||
| ESP32-S3 BALANCE | — | Sends VESC commands; publishes telemetry |
|
||
| Jetson Orin (CANable2) | — | Sends velocity commands; receives telemetry |
|
||
|
||
### Frame Table
|
||
|
||
| CAN ID | Direction | Description | Rate |
|
||
|--------|-----------|-------------|------|
|
||
| 0x300 | Orin → BALANCE | Velocity cmd: int16 speed_mmps, int16 steer_mrad | 20 Hz |
|
||
| 0x301 | Orin → BALANCE | PID tuning: float Kp, float Ki, float Kd (3×4B IEEE-754) | on demand |
|
||
| 0x302 | Orin → BALANCE | Mode: uint8 (0=off, 1=balance, 2=manual, 3=estop) | on demand |
|
||
| 0x303 | Orin → BALANCE | Config: uint16 tilt_limit_x100, uint16 max_speed_mmps | on demand |
|
||
| 0x400 | BALANCE → Orin | Telemetry A: int16 pitch_x100, int16 pid_out, int16 speed_mmps, uint8 state | 10 Hz |
|
||
| 0x401 | BALANCE → Orin | Telemetry B: int16 vesc_l_rpm, int16 vesc_r_rpm, uint16 battery_mv, uint8 faults | 10 Hz |
|
||
|
||
---
|
||
|
||
## RC Channel Mapping (TBS Crossfire / ELRS CRSF)
|
||
|
||
| CH | Function | Range (µs) | Notes |
|
||
|----|----------|------------|-------|
|
||
| 1 | Steer (Roll) | 988–2012 | ±100% → ±max steer |
|
||
| 2 | Throttle (Pitch) | 988–2012 | forward / back speed |
|
||
| 3 | Spare | 988–2012 | |
|
||
| 4 | Spare | 988–2012 | |
|
||
| 5 | ARM switch | <1500=disarm, >1500=arm | SB on TX |
|
||
| 6 | **ESTOP** | <1500=normal, >1500=kill | SC on TX — checked first every loop |
|
||
| 7 | Speed limit | 988–2012 | maps to 10–100% speed cap |
|
||
| 8 | Spare | | |
|
||
|
||
**RC loss:** No valid CRSF frame >100 ms → IO sends FAULT(rc_loss) → BALANCE cuts motors.
|
||
|
||
---
|
||
|
||
## Safety Invariants
|
||
|
||
1. **Motors NEVER spin on power-on** — 3 s button hold required while upright
|
||
2. **Tilt cutoff ±25°** — immediate motor zero, manual re-arm required
|
||
3. **IWDG 50 ms** — firmware hang → motors cut
|
||
4. **ESTOP RC channel** checked first in every loop iteration
|
||
5. **Orin CAN timeout 500 ms** → revert to RC-only mode
|
||
6. **Speed hard cap** — start at 10%, increase in 10% increments only after stable tethered testing
|
||
7. **Never untethered** until stable for 5+ continuous minutes tethered
|
||
|
||
---
|
||
|
||
## USB Debug Commands (both boards, serial console)
|
||
|
||
```
|
||
help list commands
|
||
status print pitch, PID state, CAN stats, UART stats
|
||
pid <Kp> <Ki> <Kd> set PID gains
|
||
arm arm (if upright and safe)
|
||
disarm disarm immediately
|
||
estop emergency stop (requires re-arm)
|
||
tilt_limit <deg> set tilt cutoff angle (default 25)
|
||
speed_limit <pct> set speed cap percentage (default 10)
|
||
can_stats CAN bus counters (tx/rx/errors/busoff)
|
||
uart_stats inter-board UART frame counters
|
||
reboot soft reboot
|
||
```
|