58 Commits

Author SHA1 Message Date
80a41e5008 feat: motor driver layer — differential drive, steer ramp, estop
Adds motor_driver.c/h between the balance PID and the raw
hoverboard UART driver:

- Differential drive: balance_cmd → speed, steer_cmd → steer
- Steer-only ramping at MOTOR_STEER_RAMP_RATE (balance PID keeps
  full immediate authority — no ramp on speed channel)
- Headroom clamp: reduces steer so |speed|+|steer|<=MOTOR_CMD_MAX
  ensuring ESC never clips the balance command
- Emergency stop: latches on TILT_FAULT, clears on BALANCE_DISARMED;
  send path stays in 50Hz ESC tick to avoid flooding UART

main.c: replace bare hoverboard_send() with motor_driver_update();
config.h: MOTOR_CMD_MAX=1000, MOTOR_STEER_RAMP_RATE=20 counts/ms

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 17:15:40 -05:00
6513b04e4e fix: correct roll axis mapping + add yaw telemetry (issues #12, #13)
Issue #12 — Roll displayed as pitch:
- Firmware was sending r=pitch_rate (wrong). Changed to r=roll_deg*10.
- mpu6000.c: add roll complementary filter (accel atan2(ay,az) +
  gyro gy integration, same COMP_ALPHA=0.98 as pitch).
- IMUData: add roll and yaw fields.
- UI: updateIMU() now uses data.r/10 for roll (not client-side filter
  that computed from ax/ay/az which firmware never sent).
- Three.js: roll -> rotation.z (banking), pitch -> rotation.x (tipping)
  — axes were already correct, fix was the firmware data.

Issue #13 — Add yaw telemetry:
- Firmware: gyro Z integration (gz * dt) → s_yaw, sent as y=yaw_deg*10.
  Gyro-only, drifts — no magnetometer.
- IMUData: yaw field added.
- UI: yaw -> rotation.y (spinning on vertical axis). Displayed in HUD.
- UI: YAW RESET button captures current yaw as new zero reference
  (client-side offset, no new firmware command needed).

Closes #12, #13.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 15:07:04 -05:00
81d76e4770 fix(usb): MPU non-cacheable region + IWDG ordering fix (bd-3ulu)
Root cause 1 (IWDG reset loop): safety_init() was called before
mpu6000_init() — IWDG 50ms timeout fires during ~510ms IMU init,
causing infinite MCU reset. Moved safety_init() to after all
peripheral inits (IMU, hoverboard, balance).

Root cause 2 (DCache coherency): USB TX/RX buffers merged into a
single 512B-aligned struct in usbd_cdc_if.c. MPU Region 0 configured
non-cacheable (TEX=1, C=0, B=0) in usbd_conf.c USBD_LL_Init() before
HAL_PCD_Init(). DCache stays ON globally — MPU handles coherency.
Removed SCB_DisableDCache() from main.c (caused boot crash).

Also: fix safety.c IWDG_RELOAD macro (float literals not valid in
#if); add crsf.c stub so crsf_state links (UART not yet wired).

Fixes issue #9.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 13:51:02 -05:00
4dd52b47dc feat(safety): IWDG watchdog, arm hold interlock, tilt alert (bd-3qh)
Safety systems implementation:

IWDG Hardware Watchdog (50ms timeout, config.h WATCHDOG_TIMEOUT_MS):
- safety_init() configures IWDG at PSC/32 (0.8ms tick), reload=62
- safety_refresh() must be called every loop iteration
- Cannot be disabled once started — MCU resets if loop hangs
- Started after 3s USB init delay (avoids spurious startup reset)

Arm Hold Interlock (3s, config.h ARMING_HOLD_MS):
- Arm command starts a hold timer, not immediate motor enable
- Motors only enable after ARMING_HOLD_MS consecutive hold
- Disarm or tilt > 10° cancels pending arm
- Prevents accidental arm from single keypress

Tilt Fault Alert:
- safety_alert_tilt_fault() fires one-shot buzzer on TILT_FAULT edge
- Rider hears alarm when tilt cutoff triggers
- Edge-detected (buzzer only fires once per fault event)

RC Timeout (infrastructure):
- safety_rc_alive() checks crsf_state.last_rx_ms vs RC_TIMEOUT_MS
- RC disarm wired but guarded (no CRSF yet) — remove guard when wired
- Compatible with future CRSF implementation

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 13:11:43 -05:00
34fdb5d11b feat(pid): runtime PID tuning via USB + improved telemetry (bd-18i)
Add USB command interface for live PID gain adjustment without reflashing:
  P<kp>  I<ki>  D<kd>  T<setpoint_deg>  M<max_speed>  ?

Command parsing runs in main loop (sscanf-safe), not in USB IRQ.
USB IRQ copies command to shared volatile buffer (cdc_cmd_buf), sets flag.
Acknowledgement echoes current gains: {"kp":...,"ki":...,"kd":...}

Bounds checking: kp 0-500, ki/kd 0-50, setpoint ±20°, max_speed 0-1000.
Gains validated before write — silently ignored if out of range.

Telemetry updated from raw counts to physical tuning signals:
  pitch (°x10), pitch_rate (°/s x10), error (°x10),
  integral (x10 for windup monitoring), motor_cmd, state

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 13:10:32 -05:00
398cbb9a55 feat(imu): MPU6000 sensor fusion with complementary filter
Add src/mpu6000.c implementing a complementary filter (α=0.98) on top of
the existing icm42688 SPI driver. Fixes wrong scale factors in balance.c
(was ±250°/s / ±2g; hardware is configured ±2000°/s / ±16g). Fusion now
lives in the IMU driver layer; balance_update() consumes IMUData directly.

- mpu6000_init(): calls icm42688_init(), seeds filter state
- mpu6000_read(): reads raw SPI, applies complementary filter, returns
  fused pitch (degrees) + pitch_rate (°/s) + accel_x/z (g)
- balance.c: removes duplicated fusion code, uses IMUData.pitch
- main.c: switches to mpu6000_init()/mpu6000_read(), updates telemetry

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 13:09:18 -05:00
0bfd617c44 fix(usb): resolve USB CDC TX failure caused by three independent bugs
Bug 1 (PRIMARY — DCache/USB coherency):
SCB_DisableDCache() was buried inside icm42688_init(), called ~3.5s
after USB starts. STM32F7 DCache/USB coherency issue: when DCache is
on (enabled by SystemInit()), CPU writes to TX buffers stay in cache
and the USB hardware reads stale SRAM data. Moved SCB_DisableDCache()
to main() before HAL_Init(), ensuring coherency for all USB transfers.

Bug 2 (USB TX corruption):
CDC_Transmit() passed the caller's stack-allocated buf pointer directly
to the USB stack. The USB TXFE interrupt fires asynchronously; by then
the stack buffer may have been modified by the next loop iteration.
CDC_Transmit() now copies into the static UserTxBuffer before handing
off to the USB hardware, ensuring the buffer is stable for the transfer.

Bug 3 (IMU type mismatch → wrong data to balance):
main.c called icm42688_init()/icm42688_read() directly, passing
icm42688_data_t* (raw int16 ax/ay/az/gx/gy/gz) to balance_update()
which expects IMUData* (float pitch/pitch_rate from complementary
filter). Type mismatch produced garbage balance values. Fixed by using
mpu6000_init()/mpu6000_read() which wraps icm42688 + sensor fusion.
Telemetry updated to report fused pitch/rate instead of raw ADC counts.

Also fix icm42688_init() returning 0 on who==0 (no SPI response),
which falsely indicated IMU success.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 12:37:24 -05:00
Sebastien Vayrette
ba3e1161b9 Balance firmware + USB CDC bug 2026-02-28 11:58:23 -05:00