Adds prototype_baseplate.scad — a laser-cuttable / CNC-routable flat
base plate for the self-balancing robot using caliper-verified axle
dimensions from the wiki (replaces placeholder values in PR #7):
Axle base dia: 16.11 mm (was 14 mm)
D-cut OD: 15.95 mm (new)
D-cut flat chord: 13.00 mm (new)
Total protrusion: 65.50 mm
Bearing seat OD: 37.80 mm
Tire OD: 254 mm (10x2.125")
Axle CL height: 127 mm (was wrong 310 mm)
Design:
- Single flat plate (6 mm Al / 8 mm acrylic), 680x220 mm blank
- Open fork slots (16.51 mm, semicircular tip) at each axle end
- Bearing seat relief cutout prevents Ø37.8 mm collar binding on edge
- Two-piece dropout clamp: lower (round bore) + upper (D-cut bore)
- D-cut profile computed from chord geometry with 0.3 mm all-round clearance
- MAMBA F722S FC holes (30.5x30.5 mm M3), battery mount holes (M4)
- Lightening slots, corner radii via minkowski
- RENDER param switches between 3-D assembly and 2-D DXF projections
for each of the three laser-cut parts
Updates BOM.md to Rev B: measurement delta table, prototype BOM section,
updated motor entry with verified axle spec.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
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>
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>
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>
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>