Skip to content

Fix pan axis drift: soft-iron bug + gyro calibration improvements#244

Open
sorcerdu wants to merge 2 commits into
headtracker:masterfrom
sorcerdu:fix/sensor-improvements
Open

Fix pan axis drift: soft-iron bug + gyro calibration improvements#244
sorcerdu wants to merge 2 commits into
headtracker:masterfrom
sorcerdu:fix/sensor-improvements

Conversation

@sorcerdu
Copy link
Copy Markdown

Problem

On Seeed XIAO BLE Sense, the pan (yaw) axis exhibits ~0.1°/s cumulative drift even when the device is completely stationary. While the center-reset button can temporarily correct it, the continuous drift significantly degrades the user experience during extended sessions.

Root Cause Analysis

Two independent sources of drift were identified. Controlled testing on Seeed XIAO BLE Sense (stationary, bench-mounted):

Fix applied Pan drift Improvement
None (original) ~0.1°/s (6°/min)
Soft-iron fix only ~0.005°/s (0.1° per 20s, ~0.3°/min) 20×
Soft-iron + gyro improvements <1° per hour (~0.017°/min) 360×

Bug 1: Soft-iron matrix in-place overwrite

The 3×3 soft-iron compensation matrix was applied in-place:

magx = (magx * magsioff[0]) + (magy * magsioff[1]) + (magz * magsioff[2]);
magy = (magx * magsioff[3]) + (magy * magsioff[4]) + (magz * magsioff[5]);  // uses updated magx!
magz = (magx * magsioff[6]) + (magy * magsioff[7]) + (magz * magsioff[8]);  // uses updated magx, magy!

Each row used already-overwritten values from previous rows. Even at rest, magnetometer noise combined with this wrong transform produced a fluctuating heading reference that the Madgwick filter integrated into slow yaw drift.

Bug 2: Noisy gyro bias estimate

The EMA-based bias estimator (alpha=0.05) effectively only averaged the last ~20 samples, leaving significant noise in the zero-bias estimate. Any residual error in the bias integrates directly into yaw over time.

Changes

  • fix(sensor): Use temporary variables for soft-iron matrix multiplication (commit 1)
  • feat(sensor): (commit 2)
    • Replace EMA with arithmetic mean over 1000 samples (~31× noise reduction on bias estimate)
    • Add automatic re-calibration when device is stationary for >5s (rate-limited to once per 5 minutes) to compensate for thermal drift
    • Add manual re-calibration on center-reset button press
    • Clamp Madgwick delta-t to handle thread scheduling delays and 32-bit timer wraparound

Testing Scope

Verified on Seeed XIAO BLE Sense only. The changes are board-agnostic (no platform-specific code modified). Testing on other supported boards (Arduino Nano 33 BLE, ESP32-C3 DevkitM, M5StickC Plus, RPi Pico W, DTQSys HT, Licardo HT) is welcomed from the community.

Notes

  • GYRO_STABLE_SAMPLES increased from 400 to 1000, adding ~4s to boot calibration time (now ~6.7s @ 150Hz)
  • Auto-recalibration only triggers when the device has been physically stationary for >5s; it will not interrupt active headtracking use
  • Auto-recalibration uses raw sensor values with a generous threshold (5 dps) as a pre-filter; the precise stability check remains in gyroCalibrate() using board-specific GYRO_STABLE_DIFF
  • No changes to the communication protocol, configuration interface, or saved flash format

sorcerdu added 2 commits May 11, 2026 18:41
The soft-iron compensation computed the 3x3 matrix-vector product
in-place: each row overwrote magx/magy/magz before subsequent rows
could read the original values. This introduced a heading-dependent
bias that contributed to pan axis drift.

Fix: use temporary variables for the full multiplication before
writing back.
The original EMA-based bias estimator (alpha=0.05) effectively only
averaged the last ~20 samples, leaving significant noise in the bias
estimate. Combined with the soft-iron bug, this caused ~0.1°/s
cumulative drift on the pan axis during normal use.

Changes:
- Replace EMA with arithmetic mean over 1000 samples (~6.7s at 150Hz),
  reducing bias noise by ~31x
- Add automatic re-calibration: when the device is stationary for >5s,
  silently re-estimate gyro bias (at most once per 60s) to compensate
  for thermal drift
- Add manual re-calibration on center-reset button press
- Clamp Madgwick filter delta-t to prevent integration overshoot from
  thread scheduling delays

Tested on Seeed XIAO BLE Sense: pan drift reduced from ~0.1°/s to
<1° over one hour of stationary operation.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant