Replace generic flat PCB with a standing two-wheeled balancing robot:
- Vertical navy body (1.2 tall) rising above wheel axle at y=0
- Two wheels with blue rim accents, aligned to axle
- Front display panel and status LED
- Sensor stem + head on top
Camera repositioned to frame the taller robot.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Remove erroneous negate on targetYaw — yaw was spinning opposite to
physical rotation. Update resetYaw() formula to match (+ instead of -).
Pitch and roll were unaffected.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Add 'G' CDC command that disarms and re-runs gyro bias calibration.
safety_refresh() added to calibration loop (every 40ms) so IWDG
does not trip during the 1s blocking re-cal when watchdog is running.
GYRO CAL button in ui/index.html sends 'G' and shows status feedback.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
- bmp280.c: detect BME280 (chip_id 0x60) vs BMP280 (0x58) at init
- bmp280.c: read humidity calibration (dig_H1–H6) from 0xA1 and 0xE1–0xE7
- bmp280.c: set ctrl_hum (0xF2, osrs_h=×16) before ctrl_meas — hardware req
- bmp280.c: add bmp280_read_humidity() — float compensation (FPv5-SP FPU),
returns %RH × 10; -1 if chip is BMP280 or not initialised
- bmp280.h: add bmp280_read_humidity() declaration + timeout note
- main.c: baro_ok → baro_chip (stores chip_id for BME280 detection)
- main.c: telemetry adds t (°C×10), pa (hPa×10) for all barometers;
adds h (%RH×10) for BME280 only; alt unchanged
- ui/index.html: hidden TEMP/HUMIDITY/PRESSURE rows, revealed on first
packet containing t/h/pa fields; values shown with 1 dp
I2C hang safety: all HAL_I2C_Mem_Read/Write use 100ms timeouts, so
missing hardware (NAK) returns in <1ms, not after a hang.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Shared I2C1 bus (i2c1.c/h, PB8=SCL PB9=SDA 100kHz):
- i2c1_init() called once in main() before sensor probes.
- hi2c1 exported globally; baro and mag drivers use it directly.
Barometer (bmp280.c):
- Probes I2C1 at 0x76 then 0x77 (covers both SDO options).
- bmp280_init() returns chip_id (0x58/0x60) on success, neg if absent.
- Added bmp280_pressure_to_alt_cm() — ISA barometric formula.
- Added bmp280.h (was missing).
Magnetometer (mag.c / mag.h):
- Auto-detects QMC5883L (0x0D, id=0xFF), HMC5883L (0x1E, id='H43'),
IST8310 (0x0E, id=0x10) in that order.
- mag_read_heading() returns degrees×10 (0–3599) or -1 if not ready.
- HMC5883L: correct XZY byte order applied.
- IST8310: single-measurement trigger mode.
main.c:
- i2c1_init() + bmp280_init() + mag_init() after all other inits.
- Both skip gracefully (baro_ok=0, mag_type=MAG_NONE) if not present.
- Telemetry JSON: incremental builder appends ",\"hd\":<n>" when mag
found and ",\"alt\":<n>" when baro found. No extra bytes when absent.
UI (index.html):
- HEADING and ALT rows hidden until first packet with that field.
- Heading shown in degrees, alt in metres (firmware sends cm).
Closes#24.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
New LED behavior (active-low, PC15=LED1, PC14=LED2):
Disarmed, IMU OK : LED1 solid ON + LED2 off
Armed : LED1 solid ON + LED2 solid ON
Tilt fault : LED1 blink 1Hz + LED2 blink 1Hz
IMU error : LED1 blink 1Hz + LED2 solid ON
Rule: solid = good, slow blink (~1Hz) = needs attention.
Removed the confusing fast-blink-at-5Hz-for-error and the
baro-flash-every-5s patterns.
status_update() signature changed: baro_ok → armed + tilt_fault
so the LED pattern can reflect arm state directly.
Closes#22.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
On boot, before the main loop, sample 1000 gyro readings (~1s) while
board is held still. Compute per-axis mean offset (sensor-frame raw LSBs)
and subtract from all subsequent readings in mpu6000_read().
- mpu6000_calibrate(): LED1+LED2 solid ON during 1s sample window,
resets filter state to zero once bias is known
- mpu6000_is_calibrated(): gate; main loop blocks arming and USB
streaming until calibration completes
- Bias subtracted in sensor frame before CW270 axis transform + scale,
so all three axes (pitch/roll/yaw rate) benefit
- config.h: GYRO_CAL_SAMPLES=1000
- No flash storage — recalibrate fresh each boot (bias varies with temp)
Closes#21 (3.5°/s yaw drift), #23 (gyro bias calibration on boot).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
On boot, before the main loop, sample 1000 gyro readings (~1s) while
board is held still. Compute per-axis mean offset (sensor-frame raw LSBs)
and subtract from all subsequent readings in mpu6000_read().
- mpu6000_calibrate(): LED1+LED2 solid ON during 1s sample window,
resets filter state to zero once bias is known
- mpu6000_is_calibrated(): gate; main loop blocks arming and USB
streaming until calibration completes
- Bias subtracted in sensor frame before CW270 axis transform + scale,
so all three axes (pitch/roll/yaw rate) benefit
- config.h: GYRO_CAL_SAMPLES=1000
- No flash storage — recalibrate fresh each boot (bias varies with temp)
Closes#21 (3.5°/s yaw drift), #23 (gyro bias calibration on boot).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
The MAMBA F722S mounts MPU6000 at CW270 (clockwise 270°) which applies
rotation matrix R = [[0,1,0],[-1,0,0],[0,0,1]] to transform sensor axes
to board axes (Betaflight convention).
Firmware (mpu6000.c):
- accel_pitch: was atan2(ax, az) → now atan2(ay, az)
board_forward = sensor_Y, so ay drives pitch not ax
- accel_roll: was atan2(ay, az) → now atan2(-ax, az)
board_right = -sensor_X, so -ax drives roll not ay
- gyro_pitch_rate: was +raw.gx → now -raw.gx
board_gy (pitch) = -sensor_gx after R_CW270 transform
- gyro_roll_rate: raw.gy unchanged (board_gx = sensor_gy ✓)
- gyro_yaw_rate: raw.gz unchanged ✓
UI (index.html) rotation sign fixes:
- roll → -rotation.z: Three.js +z = CCW from camera = left bank;
our convention is right-bank-positive so negate
- yaw → -rotation.y: Three.js +y = CCW from above; sensor_Z points
down on MAMBA (az ≈ +1g when level) so gz+ = CW physical; negate
- pitch → +rotation.x: correct as-is (Three.js +x tilts nose up ✓)
Closes#15.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
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>
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>
ARCHITECTURE CHANGE: batteries no longer sit flat on the base plate.
They mount VERTICALLY on a central mast via a height-adjustable carousel.
CG is tuned by sliding the carousel up/down the stem.
Part A — prototype_baseplate.scad (Rev C):
- PLATE_DEPTH: 210mm → 130mm (no battery footprint constraint)
- Removed all battery tray geometry (holes, strap slots, expansion mounts)
- Added central stem socket: Ø38.6mm bore + 4x M5 flange bolt holes on Ø66mm BC
- Added stem_flange() module: laser-cut ring (qty 2, one each side of plate)
- Wiring pass-through slots flanking stem centre
- FC mount relocated to FC_X_OFFSET = -40mm (front of plate, clear of stem)
- New RENDER="stem_flange_2d" DXF export option
Part B — stem_battery_clamp.scad (new):
- Collar: two 3D-printed D-shaped halves, split at Y=0
- Ø38.6mm bore (1.5" EMT / 6061-T6 tube)
- 4x M6 clamping bolts + hex nut pockets
- 1x M6 set screw per half for height/rotation lock
- Arm attachment pads with M4 through-holes + nut pockets
- Arms: flat bars, laser-cut or printed, ARM_REACH=55mm
- Battery cradles: U-channel, open top, Velcro strap slots at 30% + 65% height
- BATT_COUNT param: 2 (180°), 3 (120°), or 4 (90°) radial batteries
- ARM_START_ANGLE chosen per BATT_COUNT to keep all arms clear of Y=0 split
- Battery ghosts in assembly for visualisation
- Full RENDER control: assembly / collar_half / arm / arm_2d / cradle
- Assembly sequence + CG tuning notes in file footer
BOM.md → Rev C:
- Part A table updated (5 laser-cut parts + stem tube)
- Part B table added (collar halves, arms, cradles, fasteners)
- Battery section: flat-deck layout replaced with vertical stem guide
- Fastener table updated to match new architecture
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
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>