Three bugs prevented mpu6000_is_calibrated() from returning true,
blocking arming and balance mode:
1. WHO_AM_I single-attempt: one SPI glitch returning 0x00 caused
icm42688_init() to return -128, skipping mpu6000_calibrate()
entirely. Fix: retry WHO_AM_I up to 3 times with 10ms gaps.
2. icm42688_read() rx[15] uninitialized: if HAL_SPI_TransmitReceive()
failed, garbage stack data was accumulated as gyro bias. Fix: zero-
init rx[15] so failed transfers produce zero data.
3. mpu6000_calibrate() raw uninitialized: UB if icm42688_read() is
a no-op (imu_type mismatch). Fix: zero-init raw each iteration.
Also add SCB_InvalidateDCache_by_Addr() on SPI rx buffers in rreg()
and icm42688_read() for DCache coherency. Currently a no-op (DCache
is not enabled), but required if SCB_EnableDCache() is added — stack
buffers in SRAM2 are in the cacheable memory region on STM32F7.
Fix misleading DCache comment in icm42688.c (claimed DCache was
disabled by main.c; actually SCB_EnableDCache() is never called).
Build: 59904 bytes Flash (+512), 17100 bytes RAM — SUCCESS
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
- esc_hoverboard.c: huart2 static in production; non-static only under
#ifdef DEBUG_MOTOR_TEST (needed by R command in jetson_uart.c)
- esc_hoverboard.c: UART5 diagnostic in hoverboard_backend_init() and
per-packet printf in hoverboard_backend_send() guarded by same flag
- esc_hoverboard.c: #include <stdio.h> also guarded (not needed in production)
- jetson_uart.c: R (baud sweep) and X (GPIO test) commands guarded by
#ifdef DEBUG_MOTOR_TEST — not compiled into production firmware
Production build: no debug output, static huart2, no R/X commands.
Debug build: define DEBUG_MOTOR_TEST to re-enable all diagnostics.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
USART1 IDLE interrupt (DMA circular RX) was calling HAL_UART_IRQHandler
mid-frame during polling HAL_UART_Transmit, resetting gState and causing
leading nulls / truncated frames on the Jetson telemetry link at 921600 baud.
Fix: introduce jlink_tx_locked() which disables USART1_IRQn around every
blocking HAL_UART_Transmit call, preventing IRQHandler from corrupting
gState while the TX loop is running. A s_tx_busy flag drops any
re-entrant caller (ESC debug, future USART6/VESC paths).
Both jlink_send_telemetry (50 Hz) and jlink_send_power_telemetry (1 Hz)
now use jlink_tx_locked(). Also correct the stale config.h comment that
misidentified the Jetson link as USART6 (it moved to USART1 in Issue #120).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
- Detect if MCU was reset by IWDG watchdog timeout at startup
- Log watchdog reset events to debug terminal (USB CDC)
- Store watchdog reset flag for status reporting to Jetson
- Watchdog timer configured with 2-second timeout in safety_init()
- Main loop calls safety_refresh() to kick the watchdog every iteration
The IWDG (Independent Watchdog) resets the MCU if the main loop
hangs and fails to call safety_refresh() within the timeout window.
This provides hardware-enforced detection of software failures.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Adds #include "bno055.h" to src/main.c to resolve implicit declaration
warnings for bno055_read(), bno055_calib_status(), and bno055_temperature().
Functions were properly implemented but header was missing from includes.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Add coulomb counter for accurate SoC estimation independent of load:
- New coulomb_counter module: integrate current over time to track Ah consumed
* coulomb_counter_init(capacity_mah) initializes with battery capacity
* coulomb_counter_accumulate(current_ma) integrates current at 100 Hz
* coulomb_counter_get_soc_pct() returns SoC 0-100% (255 = invalid)
* coulomb_counter_reset() for charge-complete reset
- Battery module integration:
* battery_accumulate_coulombs() reads motor INA219 currents and accumulates
* battery_get_soc_coulomb() returns coulomb-based SoC with fallback to voltage
* Initialize coulomb counter at startup with DEFAULT_BATTERY_CAPACITY_MAH
- Telemetry updates:
* JLink STATUS: use coulomb SoC if available, fallback to voltage-based
* CRSF battery frame: now includes remaining capacity in mAh (from coulomb counter)
* CRSF capacity field was always 0; now reflects actual remaining mAh
- Mainloop integration:
* Call battery_accumulate_coulombs() every tick for continuous integration
* INA219 motor currents + 200 mA subsystem baseline = total battery draw
Motor current sources (INA219 addresses 0x40/0x41) provide most power draw;
Jetson ROS2 battery_node already prioritizes coulomb-based soc_pct from STATUS frame.
Default capacity: 2200 mAh (typical lab 3S LiPo); configurable via firmware parameter.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
- Replace safety.c's direct IWDG initialization with watchdog module API
- Use watchdog_init(2000) for ~2s timeout in safety_init()
- Use watchdog_kick() in safety_refresh() to feed the watchdog
- Remove unused watchdog_get_divider() helper function
- Watchdog now configured with automatic prescaler selection
The watchdog module provides a clean, flexible IWDG interface that:
- Automatically calculates prescaler and reload values
- Detects watchdog-triggered resets via watchdog_was_reset_by_watchdog()
- Supports timeout range of ~1ms to ~32 seconds
- Integrates seamlessly with existing safety system
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Real-time motor current visualization with:
- Subscribes to /saltybot/motor_currents for dual-motor current data
- Rolling 60-second history window with automatic data culling
- Dual-axis line chart for left (cyan) and right (amber) motor amps
- Canvas-based rendering for performance
- Thermal warning threshold line (25A, configurable)
- Real-time statistics:
* Current draw for left and right motors
* Peak current tracking over 60-second window
* Average current calculation
* Thermal status indicator with warning badge
- Color-coded thermal alerts:
* Red background when threshold exceeded
* Warning indicator and message
- Grid overlay, axis labels, time labels, legend
- Takes absolute value of currents (handles reverse direction)
Integrated into TELEMETRY tab group as 'Motor Current' tab.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Implements STM32F722 driver for WS2812 NeoPixel 8-LED ring with finite state machine.
Features:
- 8 operational states with animations:
* BOOT: Blue pulse (0.5 Hz)
* IDLE: Green breathe (0.5 Hz)
* ARMED: Solid green
* NAV: Cyan spin (1 Hz)
* ERROR: Red flash (2 Hz)
* LOW_BATT: Orange blink (1 Hz)
* CHARGING: Green fill (1 Hz)
* ESTOP: Red solid
- Non-blocking tick-based animation system
- State transitions via API
- PWM control on PB4 (TIM3_CH1) at 800 kHz
- Color interpolation for smooth effects
All 25 unit tests passing covering state transitions, animations, timing, and edge cases.
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Implements STM32F722 driver for brushless cooling fan on PA9 using TIM1_CH2 PWM.
Features:
- Temperature-based speed curve: off <40°C, 30% at 50°C, 100% at 70°C
- Smooth speed ramp transitions with configurable rate (default 0.05%/ms)
- Linear interpolation between curve points
- PWM duty cycle control (0-100%)
- State transitions and edge case handling
All 51 unit tests passing:
- Temperature curve verification (6 test zones)
- Speed boundaries and transitions
- Ramp timing and rate control
- PWM duty cycle calculation
- Temperature extremes and boundary conditions
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Implements complete I2C1 driver for TI INA219 power monitoring IC supporting:
- Dual sensors on I2C1 (left motor @ 0x40, right motor @ 0x41)
- Auto-calibration for 5A max current, 0.1Ω shunt resistance
- Current LSB: 153µA, Power LSB: 3060µW (20× current LSB)
- Bus voltage: 0-26V @ 4mV/LSB (13-bit, 4mV resolution)
- Shunt voltage: ±327mV @ 10µV/LSB (signed 16-bit)
- Calibration register computation for arbitrary max current/shunt values
- Efficient single/batch read functions (voltage, current, power)
- Alert threshold configuration for overcurrent protection
- Full test suite: 12 passing unit tests covering calibration, conversions, edge cases
Integration:
- ina219_init() called after i2c1_init() in main startup sequence
- Ready for motor power monitoring and thermal protection logic
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Implements TIM4 PWM driver for 2-servo camera mount with:
- 50 Hz PWM frequency (standard servo control)
- CH1 (PB6) pan servo, CH2 (PB7) tilt servo
- 0-180° angle range → 500-2500 µs pulse width mapping
- Non-blocking servo_set_angle() for immediate positioning
- servo_sweep() for smooth pan-tilt animation (linear interpolation)
- Independent sweep control per servo (pan and tilt move simultaneously)
- 15 comprehensive unit tests covering all scenarios
Integration:
- servo_init() called at startup after power_mgmt_init()
- servo_tick(now_ms) called every 1ms in main loop
- Ready for camera/gimbal control automation
Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
Adds STM32F7 STOP-mode power management with <10ms wake latency:
- power_mgmt.c: state machine (ACTIVE→SLEEP_PENDING→SLEEPING→WAKING),
30s idle timeout (PM_IDLE_TIMEOUT_MS), 3s LED fade before STOP,
gate SPI3/I2S3+SPI2+USART6+UART5 on sleep (clock-only, state preserved),
EXTI1(PA1/CRSF)+EXTI7(PB7/JLink)+EXTI4(PC4/IMU) wake sources,
PLL restore after STOP (PLLM=8/N=216/P=2 → 216MHz), uwTick save/restore
- Peripheral gating: I2S3, SPI2(OSD), USART6, UART5 disabled during STOP;
SPI1(IMU), UART4(CRSF), USART1(JLink), I2C1 remain active as wake sources
- Sleep LED: triangle-wave pulse (2s period) on LED1 during SLEEP_PENDING,
software PWM in main loop (1-bit, pm_pwm_phase vs brightness)
- IWDG: fed just before WFI; <10ms wake << 50ms WATCHDOG_TIMEOUT_MS
- JLink: JLINK_CMD_SLEEP=0x09, JLINK_TLM_POWER=0x81 (11-byte power frame
at 1Hz: power_state, est_total_ma, est_audio_ma, est_osd_ma, idle_ms)
- main.c: power_mgmt_init(), activity() on CRSF/JLink/armed, tick() when
disarmed, sleep_req handler, LED PWM, JLINK_TLM_POWER telemetry
- config.h: PM_* constants, PM_CURRENT_*_MA estimates, PM_TLM_HZ
- test_power_mgmt.py: 72 tests passing (state machine, LED, gating,
current estimates, JLink protocol, wake latency, hardware constants)
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
i%40==39 fired the first IWDG refresh only after 40ms of calibration.
Combined with ~10ms of main loop overhead before entering calibrate(),
total elapsed since last refresh could exceed the 50ms IWDG window.
Change to i%40==0: first refresh fires at i=0 (<1ms after entry),
subsequent refreshes every 40ms — safely within the 50ms window.
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>
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>