feat: Boot gyro calibration — eliminates yaw drift (#21, #23) #25

Merged
seb merged 1 commits from sl-controls/gyro-calibration into main 2026-02-28 18:45:18 -05:00
Collaborator

Summary

  • Issue #21: Yaw drifts ~3.5°/s CCW when stationary — caused by gyro Z-axis bias
  • Issue #23: No gyro bias calibration on boot — bias varies with temperature so must be measured fresh

On every boot, before the main loop enters, mpu6000_calibrate() samples 1000 gyro readings over ~1s with the board held still, computes the per-axis mean offset in sensor-frame raw LSBs, and stores it. All subsequent mpu6000_read() calls subtract the bias before the CW270 axis transform and scale — so all three axes (pitch rate, roll rate, yaw rate) are corrected.

Changes

  • src/mpu6000.c: mpu6000_calibrate() — LED1+LED2 solid ON during 1s window, int32 accumulation (avoids float error), resets filter state to zero after; mpu6000_is_calibrated() gate; bias subtraction before axis transform
  • include/mpu6000.h: declares the two new functions with doc comments
  • src/main.c: calls mpu6000_calibrate() immediately after mpu6000_init() (before safety_init() so IWDG is not yet running); gates arming and USB streaming on mpu6000_is_calibrated()
  • include/config.h: GYRO_CAL_SAMPLES=1000

No flash storage — bias recalibrated fresh each boot (temperature-dependent).

Test plan

  • Build passes
  • On power-on: LED1+LED2 solid for ~1s, then return to normal blink pattern
  • Arm command ignored during calibration window
  • USB stream does not start until calibration complete
  • Stationary yaw rate ≈ 0 (vs ~3.5°/s before)
  • Pitch/roll stable at 0° when level and still
  • Reboot with board tilted: calibration still completes (bias is gyro offset, not accel)

Closes #21, #23.

🤖 Generated with Claude Code

## Summary - **Issue #21**: Yaw drifts ~3.5°/s CCW when stationary — caused by gyro Z-axis bias - **Issue #23**: No gyro bias calibration on boot — bias varies with temperature so must be measured fresh On every boot, before the main loop enters, `mpu6000_calibrate()` samples 1000 gyro readings over ~1s with the board held still, computes the per-axis mean offset in sensor-frame raw LSBs, and stores it. All subsequent `mpu6000_read()` calls subtract the bias before the CW270 axis transform and scale — so all three axes (pitch rate, roll rate, yaw rate) are corrected. ## Changes - `src/mpu6000.c`: `mpu6000_calibrate()` — LED1+LED2 solid ON during 1s window, int32 accumulation (avoids float error), resets filter state to zero after; `mpu6000_is_calibrated()` gate; bias subtraction before axis transform - `include/mpu6000.h`: declares the two new functions with doc comments - `src/main.c`: calls `mpu6000_calibrate()` immediately after `mpu6000_init()` (before `safety_init()` so IWDG is not yet running); gates arming and USB streaming on `mpu6000_is_calibrated()` - `include/config.h`: `GYRO_CAL_SAMPLES=1000` **No flash storage** — bias recalibrated fresh each boot (temperature-dependent). ## Test plan - [ ] Build passes - [ ] On power-on: LED1+LED2 solid for ~1s, then return to normal blink pattern - [ ] Arm command ignored during calibration window - [ ] USB stream does not start until calibration complete - [ ] Stationary yaw rate ≈ 0 (vs ~3.5°/s before) - [ ] Pitch/roll stable at 0° when level and still - [ ] Reboot with board tilted: calibration still completes (bias is gyro offset, not accel) Closes #21, #23. 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-controls added 1 commit 2026-02-28 17:42:56 -05:00
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>
seb approved these changes 2026-02-28 18:45:17 -05:00
seb left a comment
Owner

Flash-tested all 3 together. Gyro cal eliminates yaw drift, LEDs solid, I2C probe clean.

Flash-tested all 3 together. Gyro cal eliminates yaw drift, LEDs solid, I2C probe clean.
seb merged commit 1bf30a0262 into main 2026-02-28 18:45:18 -05:00
Sign in to join this conversation.
No Reviewers
No Label
2 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#25
No description provided.