docs: SAUL-TEE full ESP32-S3 system reference (arch migration) #712

Merged
sl-jetson merged 5 commits from sl-firmware/arch-esp32-migration into main 2026-04-04 08:57:11 -04:00
2 changed files with 460 additions and 9 deletions
Showing only changes of commit bfca6d1d92 - Show all commits

View File

@ -0,0 +1,444 @@
# SAUL-TEE — System Reference
**Rev A — 2026-04-04**
_Authoritative architecture reference for all agents. Source: hal (Orin), max._
---
## 1. Robot Overview
| Parameter | Value |
|-----------|-------|
| **Name** | SAUL-TEE |
| **Config** | 4-wheel wagon (replaces 2-wheel self-balancing bot) |
| **Dimensions** | 870 × 510 × 550 mm (L × W × H) |
| **Mass** | ~23 kg |
| **Drive** | 4× hub motors via 2× VESC 6.7 (dual channel each) |
| **Power** | 36V battery bus |
| **AI brain** | Jetson Orin Nano Super (25W) |
| **CAN bus** | 500 kbps, CANable 2.0 USB↔CAN on Orin |
> ⚠️ **ARCHITECTURE CHANGE (2026-04-03):** Mamba F722S / STM32F722 / BlackPill are retired.
> New embedded stack: **ESP32-S3 BALANCE** + **ESP32-S3 IO** (see §23 below).
---
## 2. ESP32-S3 BALANCE Board
### Hardware
| Item | Detail |
|------|--------|
| **Module** | Waveshare ESP32-S3 Touch LCD 1.28 |
| **MCU** | ESP32-S3 (dual-core 240 MHz, 512KB SRAM, 8MB flash, 8MB PSRAM) |
| **USB** | CH343G USB-UART bridge (UART0 / GPIO43 TX, GPIO44 RX) |
| **Display** | 1.28" round GC9A01 240×240 LCD (SPI) |
| **Touch** | CST816S capacitive touch (I2C) |
| **IMU** | QMI8658 6-axis (gyro + accel), I2C on-board |
| **CAN transceiver** | SN65HVD230, external, wired to ESP32-S3 TWAI peripheral |
### Role
- Runs the **PID balance / drive loop** (or stability assist for wagon mode)
- Reads QMI8658 IMU at high rate for tilt / attitude
- Sends drive commands to VESCs over **500 kbps CAN** (VESC native protocol)
- Receives high-level velocity commands from Orin over CAN (0x3000x303)
- Publishes telemetry to Orin over CAN (0x4000x401)
- Bridges ESP32-IO sensor data over **inter-board UART** @ 460800 baud
### On-Board Pin Map (fixed by Waveshare PCB)
| Signal | GPIO | Notes |
|--------|------|-------|
| LCD SCLK | 10 | GC9A01 SPI clock |
| LCD MOSI | 11 | GC9A01 SPI data |
| LCD CS | 9 | GC9A01 chip select |
| LCD DC | 8 | GC9A01 data/cmd |
| LCD BL | 2 | Backlight PWM |
| Touch SDA | 6 | CST816S / I2C-0 |
| Touch SCL | 7 | CST816S / I2C-0 |
| Touch INT | 5 | Active-low interrupt |
| Touch RST | 4 | Active-low reset |
| IMU SDA | 6 | QMI8658 shares I2C-0 |
| IMU SCL | 7 | QMI8658 shares I2C-0 |
| IMU INT1 | 3 | Data-ready interrupt |
| CH343 USB TX | 43 | UART0 TX (USB serial) |
| CH343 USB RX | 44 | UART0 RX (USB serial) |
### External Wiring (user-soldered, confirm with calipers/multimeter)
| Signal | GPIO | Notes |
|--------|------|-------|
| CAN TX | **TBD** | → SN65HVD230 D pin; use free header GPIO |
| CAN RX | **TBD** | ← SN65HVD230 R pin; use free header GPIO |
| Inter-board UART TX | **TBD** | → ESP32-IO UART RX @ 460800 |
| Inter-board UART RX | **TBD** | ← ESP32-IO UART TX @ 460800 |
> ⚠️ **Verify GPIO assignments in `esp32/balance/src/config.h` before writing firmware.**
### QMI8658 Details
| Item | Value |
|------|-------|
| I2C address | 0x6A (SA0 pin low) or 0x6B (SA0 high) |
| Gyro full-scale | ±2048 °/s (configurable ±16/32/64/128/256/512/1024/2048) |
| Accel full-scale | ±16 g (configurable ±2/4/8/16) |
| Output data rate | Up to 7174.4 Hz |
| Interface | I2C or SPI (board routes I2C) |
---
## 3. ESP32-S3 IO Board
### Hardware
| Item | Detail |
|------|--------|
| **Module** | ESP32-S3 bare dev board (JTAG USB) |
| **MCU** | ESP32-S3 (dual-core 240 MHz) |
| **USB** | Built-in USB-JTAG/Serial (no external bridge) |
### Role
- All **physical I/O**: motors, RC, sensors, indicators, accessories
- TBS Crossfire primary RC (UART0)
- ELRS failover RC (UART2)
- BTS7960 half-bridge motor drivers (4-wheel PWM drive)
- NFC, barometer, ToF range sensors (I2C)
- WS2812B LED strip
- Horn, headlight, cooling fan, buzzer
### Pin Map
| Signal | GPIO | Protocol | Notes |
|--------|------|----------|-------|
| **TBS Crossfire RX** UART TX | 43 | CRSF @ 420000 baud | Telemetry out to TBS TX module |
| **TBS Crossfire RX** UART RX | 44 | CRSF @ 420000 baud | UART0 — RC frames in |
| **ELRS failover** UART TX | **TBD** | CRSF @ 420000 baud | UART2 |
| **ELRS failover** UART RX | **TBD** | CRSF @ 420000 baud | UART2 |
| **Inter-board UART TX** | **TBD** | Binary @ 460800 | → BALANCE UART RX |
| **Inter-board UART RX** | **TBD** | Binary @ 460800 | ← BALANCE UART TX |
| **BTS7960 — FL** RPWM | **TBD** | PWM | Front-left forward |
| **BTS7960 — FL** LPWM | **TBD** | PWM | Front-left reverse |
| **BTS7960 — FL** R_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — FL** L_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — FR** RPWM | **TBD** | PWM | Front-right forward |
| **BTS7960 — FR** LPWM | **TBD** | PWM | Front-right reverse |
| **BTS7960 — FR** R_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — FR** L_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — RL** RPWM | **TBD** | PWM | Rear-left forward |
| **BTS7960 — RL** LPWM | **TBD** | PWM | Rear-left reverse |
| **BTS7960 — RL** R_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — RL** L_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — RR** RPWM | **TBD** | PWM | Rear-right forward |
| **BTS7960 — RR** LPWM | **TBD** | PWM | Rear-right reverse |
| **BTS7960 — RR** R_EN | **TBD** | GPIO | Enable H |
| **BTS7960 — RR** L_EN | **TBD** | GPIO | Enable H |
| **I2C SDA** | **TBD** | I2C | NFC + baro + ToF shared bus |
| **I2C SCL** | **TBD** | I2C | NFC + baro + ToF shared bus |
| **WS2812B data** | **TBD** | RMT | LED strip |
| **Horn** | **TBD** | GPIO/PWM | MOSFET or relay |
| **Headlight** | **TBD** | GPIO/PWM | MOSFET |
| **Fan** | **TBD** | PWM | ESC/electronics cooling |
| **Buzzer** | **TBD** | GPIO/PWM | Piezo or active buzzer |
> ⚠️ **TBD pin assignments** — to be confirmed in `esp32/io/src/config.h` once wiring is set.
### I2C Peripherals
| Device | Address | Function |
|--------|---------|----------|
| NFC module | 0x24 (PN532) or 0x28 | NFC tag read/write |
| Barometer | 0x76 (BMP280/BMP388) | Altitude + temp |
| ToF range | 0x29 (VL53L0X) or 0x52 (VL53L4CD) | Proximity/obstacle |
---
## 4. Inter-Board UART Protocol (BALANCE ↔ IO)
### Link Parameters
| Parameter | Value |
|-----------|-------|
| Baud rate | 460800 |
| Format | 8N1 |
| Direction | Full-duplex |
### Frame Format
```
Byte 0: 0xAA (start-of-frame magic)
Byte 1: LEN (payload length in bytes, uint8)
Byte 2: TYPE (message type, uint8)
Byte 3…N: PAYLOAD (LEN bytes)
Byte N+1: CRC8 (CRC-8/MAXIM over bytes 1..N)
```
### Message Types (draft — confirm in firmware)
| Type | Direction | Payload | Description |
|------|-----------|---------|-------------|
| 0x01 | IO → BAL | `[ch1:u16][ch2:u16]…[ch16:u16][flags:u8]` | RC channels (16× uint16, 10002000 µs) + status flags |
| 0x02 | IO → BAL | `[sensor_id:u8][value:f32]` | Sensor reading (ToF, baro, etc.) |
| 0x03 | IO → BAL | `[nfc_uid:u8×7][len:u8]` | NFC tag detected |
| 0x10 | BAL → IO | `[leds:u8][horn:u8][light:u8][fan:u8][buzz:u8]` | Actuator commands |
| 0x11 | BAL → IO | `[state:u8][pitch:f32][speed:f32]` | Status for LED animations |
| 0xFF | both | `[uptime_ms:u32]` | Heartbeat (watchdog reset) |
> Frame types are **draft** — refer to `esp32/shared/protocol.h` for authoritative definitions.
### CRC-8 Polynomial
```
Poly: 0x31 (CRC-8/MAXIM, also called CRC-8/1-Wire)
Init: 0x00
RefIn/RefOut: true
XorOut: 0x00
```
---
## 5. CAN Bus
### Bus Parameters
| Parameter | Value |
|-----------|-------|
| Bit rate | 500 kbps |
| Topology | Single bus; all nodes share CANH/CANL + GND |
| Termination | 120 Ω at each end of the bus |
| Orin interface | CANable 2.0 USB↔CAN → `/dev/canable0` (or `can0` after `ip link`) |
### Node Addresses
| Node | CAN ID / Role |
|------|--------------|
| VESC left motor | ID **68** (0x44) — FSESC 6.7 Pro Mini Dual, left channel |
| VESC right motor | ID **56** (0x38) — FSESC 6.7 Pro Mini Dual, right channel |
| ESP32-S3 BALANCE | transmits telemetry 0x4000x401; receives Orin cmds 0x3000x303 |
| Orin (CANable2) | transmits cmds 0x3000x303; receives telemetry 0x4000x401 |
### Orin → Robot Command Frames (0x3000x303)
| CAN ID | DLC | Payload | Description |
|--------|-----|---------|-------------|
| **0x300** | 8 | `[speed:i16][steer:i16][mode:u8][flags:u8][_:u16]` | Drive command (speed/steer ±1000, mode byte) |
| **0x301** | 1 | `[arm:u8]` | Arm/disarm (0x01 = arm, 0x00 = disarm) |
| **0x302** | 8 | `[kp:f16][ki:f16][kd:f16][_:u16]` | PID update (half-float) |
| **0x303** | 1 | `[0xE5]` | Emergency stop (magic byte, cuts all motors) |
### Robot → Orin Telemetry Frames (0x4000x401)
| CAN ID | DLC | Payload | Description |
|--------|-----|---------|-------------|
| **0x400** | 8 | `[pitch:f16][speed:f16][yaw_rate:f16][state:u8][flags:u8]` | Attitude + drive state |
| **0x401** | 4 | `[vbat:u16][fault_code:u8][rssi:i8]` | Battery voltage (mV), fault, RC RSSI |
### VESC Native CAN (standard VESC protocol)
ESP32-S3 BALANCE sends VESC commands using the standard VESC CAN protocol:
| Frame type | CAN ID formula | Notes |
|------------|---------------|-------|
| SET_DUTY | `(0x00 << 8) | VESC_ID` | Duty cycle 1.0..+1.0 × 100000 |
| SET_CURRENT | `(0x01 << 8) | VESC_ID` | Current in mA |
| SET_RPM | `(0x03 << 8) | VESC_ID` | Electrical RPM |
| SET_CURRENT_BRAKE | `(0x02 << 8) | VESC_ID` | Braking current in mA |
| STATUS_1 | `(0x09 << 8) | VESC_ID` | ERPMs + current + duty (rx) |
| STATUS_4 | `(0x10 << 8) | VESC_ID` | Temp + input voltage + input current (rx) |
---
## 6. RC Channel Mapping
### Primary: TBS Crossfire (UART0 on ESP32-IO, CRSF @ 420000 baud)
| Channel | Function | Range | Notes |
|---------|----------|-------|-------|
| CH1 | Roll / Steer | 10002000 µs | Left stick X (mode 2) |
| CH2 | Pitch / Speed | 10002000 µs | Left stick Y |
| CH3 | Throttle | 10002000 µs | Right stick Y |
| CH4 | Yaw | 10002000 µs | Right stick X |
| CH5 | Arm | 1000 / 2000 µs | 2-pos switch — <1200=DISARM, >1800=ARM |
| CH6 | Drive mode | 1000/1500/2000 µs | 3-pos: RC / Assisted / Autonomous |
| CH7 | Speed limit | 10002000 µs | Analog knob, scales max speed |
| CH8 | Aux / Horn | 1000 / 2000 µs | Momentary for horn; held = klaxon |
### Failover: ELRS (UART2 on ESP32-IO, CRSF @ 420000 baud)
Same channel mapping as TBS Crossfire. IO board switches to ELRS automatically if Crossfire link lost for > 300 ms.
### Failsafe
- **RC lost > 300 ms**: motors stop, DISARM state, wait for link restoration
- **Arm switch** must be cycled to DISARM→ARM to re-arm after failsafe
---
## 7. Serial Commands (Orin → ESP32-S3 BALANCE via CAN 0x300)
All high-level commands from the Orin go over CAN. The BALANCE board also accepts direct USB-serial commands on its CH343 port for bench debugging:
```
# Arm / disarm
ARM
DISARM
# Set drive (speed -1000..1000, steer -1000..1000)
DRIVE <speed> <steer>
# Set mode
MODE RC # full RC passthrough
MODE ASSISTED # Orin sends velocity, BALANCE does stability
MODE AUTO # full autonomous (Orin CAN commands only)
# PID update
PID <kp> <ki> <kd>
# Emergency stop (same as CAN 0x303)
ESTOP
# Status query
STATUS # returns JSON telemetry line
# IMU calibration
IMU CAL
```
---
## 8. System Wiring Diagram
```
┌──────────────────────────────────────────────────────────┐
│ JETSON ORIN NANO SUPER │
│ (Top plate, 25W) │
│ │
│ USB-A ─── CANable 2.0 USB↔CAN (can0, 500 kbps) │
│ USB-A ─── RealSense D435i (USB 3.1) │
│ USB-A ─── RPLIDAR A1M8 (CP2102, 115200) │
│ USB-C ─── SIM7600A 4G/LTE modem │
│ CSI-A ─── 2× IMX219 cameras │
│ CSI-B ─── 2× IMX219 cameras │
│ 40-pin ── ReSpeaker 2-Mic HAT │
└──────────────────────┬───────────────────────────────────┘
│ USB-A
│ CANable 2.0
│ 500 kbps CAN
┌────────────────────────────────┴──────────────────────────────────┐
│ CAN BUS (CANH / CANL) │
│ 120Ω ───┤ (all nodes) ├─── 120Ω │
└───┬──────────────────────────┬───────────────────┬────────────────┘
│ │ │
▼ ▼ ▼
┌─────────────────────┐ ┌─────────────────────┐ (CAN ID 56/68)
│ ESP32-S3 BALANCE │ │ VESC left (ID 68)│ VESC right (ID 56)
│ Waveshare LCD 1.28 │ │ FSESC 6.7 Pro Mini│
│ │ │ Dual │
│ QMI8658 IMU (I2C) │ └────────┬────────────┘
│ SN65HVD230 (CAN) │ │ Phase wires
│ CH343 USB (debug) │ ┌─────┴────────────────┐
│ │ │ Hub motors (4×) │
│ UART ─────────────────┐ │ FL / FR / RL / RR │
└─────────────────────┘ │ └──────────────────────┘
↑ 460800 baud binary │
↓ inter-board protocol │
┌─────────────────────────┘
│ ESP32-S3 IO (bare board)
│ JTAG USB (debug)
│ UART0 ── TBS Crossfire RX (CRSF, 420000)
│ UART2 ── ELRS receiver (CRSF failover, 420000)
│ PWM ──── 4× BTS7960 motor drivers
│ I2C ──── NFC + Baro + ToF sensors
│ GPIO ─── WS2812B LEDs
│ GPIO ─── Horn / Headlight / Fan / Buzzer
└─────────────────────────────────────────────
```
---
## 9. Power Architecture
```
36V BATTERY
├── VESCs (36V direct) ──── 4× Hub motors
├── BTS7960 boards (36V → motor logic 5V via onboard reg)
├── DC-DC 12V ──── Fan / Headlight / Accessories
└── DC-DC 5V ─┬── Jetson Orin (USB-C PD or barrel)
├── ESP32-S3 BALANCE (USB 5V or VIN)
├── ESP32-S3 IO (USB 5V or VIN)
├── TBS Crossfire RX (5V)
├── ELRS RX (5V)
├── WS2812B strip (5V)
├── RPLIDAR A1M8 (5V via USB)
└── Sensors / NFC / ToF / Baro (3.3V LDO from ESP32)
```
---
## 10. Device Nodes (Orin)
| Device | Node | Notes |
|--------|------|-------|
| CANable 2.0 | `can0` | `ip link set can0 up type can bitrate 500000` |
| RealSense D435i | `/dev/bus/usb/...` | realsense-ros driver |
| RPLIDAR A1M8 | `/dev/rplidar` | udev symlink from ttyUSB* |
| SIM7600A 4G | `/dev/ttyUSB02` | AT, PPP, GNSS NMEA |
| IMX219 cameras | `/dev/video0,2,4,6` | CSI-A: 0/2, CSI-B: 4/6 |
| ESP32-S3 BAL debug | `/dev/ttyACM0` or `/dev/esp32-balance` | CH343 CDC |
| ESP32-S3 IO debug | `/dev/ttyACM1` or `/dev/esp32-io` | JTAG/CDC |
---
## 11. Safety Systems
| System | Trigger | Action |
|--------|---------|--------|
| **HW kill switch** | Big red button (NC inline with 36V) | Cuts all power instantly |
| **Tilt cutoff** | `|pitch| > 25°` | Motors off → DISARM, manual re-arm required |
| **RC failsafe** | No RC frame > 300 ms | Motors off → DISARM |
| **CAN watchdog** | No Orin heartbeat > 500 ms | Drop to RC-only mode |
| **ESTOP CAN** | CAN frame 0x303 (magic 0xE5) | Immediate motor off, DISARM |
| **ESTOP inter-board** | Type 0xFF heartbeat missing > 200 ms | IO board stops BTS7960 enables |
| **Startup arming** | Cold power-on | Motors NEVER spin; need deliberate ARM |
---
## 12. Firmware Repository Layout
```
esp32/
├── balance/ — ESP32-S3 BALANCE firmware (PlatformIO)
│ ├── src/
│ │ ├── main.cpp
│ │ ├── config.h ← GPIO assignments live here
│ │ ├── imu_qmi8658.cpp/.h
│ │ ├── can_vesc.cpp/.h
│ │ └── protocol.cpp/.h
│ └── platformio.ini
├── io/ — ESP32-S3 IO firmware (PlatformIO)
│ ├── src/
│ │ ├── main.cpp
│ │ ├── config.h ← GPIO assignments live here
│ │ ├── rc_crsf.cpp/.h
│ │ ├── motor_bts7960.cpp/.h
│ │ └── protocol.cpp/.h
│ └── platformio.ini
└── shared/
└── protocol.h — inter-board frame types (authoritative)
src/ — LEGACY STM32 firmware (ARCHIVED — do not extend)
include/ — LEGACY STM32 headers (ARCHIVED — do not extend)
```
---
## 13. Open Questions / TBDs
| Item | Owner | Status |
|------|-------|--------|
| GPIO assignments for CAN TX/RX on BALANCE board | sl-firmware | **TBD** |
| GPIO assignments for IO board (all external pins) | sl-firmware | **TBD** |
| Inter-board protocol message type table (finalized) | sl-firmware | **TBD** |
| BTS7960 wiring — 4WD vs 2WD mode (all 4 or front 2 only) | max | **TBD** |
| UWB ESP-NOW receiver — BALANCE or IO board? | sl-uwb + max | **TBD** |
| VESC CAN IDs confirmed (68/56 left/right) | max | ✅ Confirmed |
| Robot dimensions 870×510×550 mm, 23 kg | max | ✅ Confirmed |
---
_Last updated: 2026-04-04. Contact max or hal on MQTT for corrections._

View File

@ -1,13 +1,20 @@
# SaltyLab Wiring Diagram
# SaltyLab / SAUL-TEE Wiring Reference
## System Overview
> ⚠️ **ARCHITECTURE CHANGE (2026-04-03):** Mamba F722S / STM32 retired.
> New stack: **ESP32-S3 BALANCE** + **ESP32-S3 IO** + VESCs on 500 kbps CAN.
> **Authoritative reference:** [`docs/SAUL-TEE-SYSTEM-REFERENCE.md`](SAUL-TEE-SYSTEM-REFERENCE.md)
> Historical STM32/Mamba wiring below is **obsolete** — retained for reference only.
---
## ~~System Overview~~ (OBSOLETE — see SAUL-TEE-SYSTEM-REFERENCE.md)
```
┌─────────────────────────────────────────────────────────────────────┐
│ ORIN NANO SUPER │
│ (Top Plate — 25W) │
│ │
│ USB-C ──── ESP32 CDC (/dev/esp32-bridge, 921600 baud) │
│ USB-C ──── STM32 CDC (/dev/stm32-bridge, 921600 baud) │
│ USB-A1 ─── RealSense D435i (USB 3.1) │
│ USB-A2 ─── RPLIDAR A1M8 (via CP2102 adapter, 115200) │
│ USB-C* ─── SIM7600A 4G/LTE modem (ttyUSB0-2, AT cmds + PPP) │
@ -25,7 +32,7 @@
│ 921600 baud │ 921600 baud, 3.3V
▼ ▼
┌─────────────────────────────────────────────────────────────────────┐
ESP32 BALANCE (FC) │
MAMBA F722S (FC) │
│ (Middle Plate — foam mounted) │
│ │
│ USB-C ──── Orin (CDC serial, primary link) │
@ -72,7 +79,7 @@
|------|----|-----------|-------|
| Orin USB-C port | FC USB-C port | USB cable | Data only, FC powered from 5V bus |
- Device: `/dev/ttyACM0` → symlink `/dev/esp32-bridge`
- Device: `/dev/ttyACM0` → symlink `/dev/stm32-bridge`
- Baud: 921600, 8N1
- Protocol: JSON telemetry (FC→Orin), ASCII commands (Orin→FC)
@ -139,7 +146,7 @@ BATTERY (36V) ──┬── Hoverboard ESC (36V direct)
| 1TB NVMe | PCIe Gen3 ×4 | M.2 Key M | `/dev/nvme0n1` |
## FC UART Summary (ESP32 BALANCE)
## FC UART Summary (MAMBA F722S — OBSOLETE)
| UART | Pins | Baud | Assignment | Notes |
|------|------|------|------------|-------|
@ -149,7 +156,7 @@ BATTERY (36V) ──┬── Hoverboard ESC (36V direct)
| UART4 | PA0=TX, PA1=RX | 420000 | ELRS RX (CRSF) | RC control |
| UART5 | PC12=TX, PD2=RX | 115200 | Debug serial | Optional |
| USART6 | PC6=TX, PC7=RX | 921600 | Jetson UART | Fallback link |
| USB CDC | USB-C | 921600 | Jetson primary | `/dev/esp32-bridge` |
| USB CDC | USB-C | 921600 | Jetson primary | `/dev/stm32-bridge` |
### 7. ReSpeaker 2-Mic HAT (on Orin 40-pin header)
@ -209,7 +216,7 @@ BATTERY (36V) ──┬── Hoverboard ESC (36V direct)
| Device | Interface | Power Draw |
|--------|-----------|------------|
| ESP32 BALANCE (CDC) | USB-C | ~0.5W (data only, FC on 5V bus) |
| STM32 FC (CDC) | USB-C | ~0.5W (data only, FC on 5V bus) |
| RealSense D435i | USB-A | ~1.5W (3.5W peak) |
| RPLIDAR A1M8 | USB-A | ~2.6W (motor on) |
| SIM7600A | USB | ~1W idle, 3W TX peak |
@ -234,7 +241,7 @@ Orin Nano Super delivers up to 25W — USB peripherals are well within budget.
└──────┬───────┘
│ UART4
┌────────────▼────────────┐
ESP32 BALANCE
MAMBA F722S
│ │
│ MPU6000 → Balance PID │
│ CRSF → Mode Manager │