Skip to content

fix(imu_orientation): use correct gyro axis per bias#9

Open
mvanhorn wants to merge 1 commit into
malloch:mainfrom
mvanhorn:osc/7-fix-gyro-bias-axes
Open

fix(imu_orientation): use correct gyro axis per bias#9
mvanhorn wants to merge 1 commit into
malloch:mainfrom
mvanhorn:osc/7-fix-gyro-bias-axes

Conversation

@mvanhorn

Copy link
Copy Markdown

Summary

Closes #7. imu_orientation.cpp lines 90-91 update gyro_bias.y and gyro_bias.z using gyro.x for both, instead of gyro.y and gyro.z respectively. Result: the per-axis bias estimate for Y and Z is driven by X-axis sensor input, so the corrections applied a few lines later (gyro.y -= gyro_bias.y, gyro.z -= gyro_bias.z) drift instead of converging to the actual per-axis bias. Reading the correct axis per line fixes it.

Why this matters

The complementary filter pattern is "running average of axis input -> bias estimate -> subtract from raw axis." Lines 89-91 implement that pattern for each of the three axes, but a copy-paste duplicated gyro.x across all three. The X-axis line is correct; Y and Z are bugged.

Downstream consumers reading the resulting orientation get a Y/Z gyro bias that tracks X-axis motion. Any device whose X axis sees a different angular-velocity profile from Y/Z (any real-world IMU placement) ends up with growing orientation drift on Y and Z that does not converge.

Changes

  • imu_orientation.cpp:90 - gyro.x -> gyro.y for the Y-axis bias update.
  • imu_orientation.cpp:91 - gyro.x -> gyro.z for the Z-axis bias update.

No public API change. The two-line correction makes the existing bias-removal block (gyro.x -= gyro_bias.x / .y / .z at lines 93-95) actually correct per axis.

How to test

This repo is header + cpp, no test suite. Compilation is unaffected (only two operand swaps in identical-shape expressions). The Y/Z bias correctness is verifiable in a runtime test: feed a stream of (omega_x = 0, omega_y = const, omega_z = const) to IMU_Orientation::update() over many iterations. Before this PR, gyro_bias.y and gyro_bias.z decay toward zero (tracking the zero X input). After this PR, they converge to the actual Y/Z bias.

Fixes #7

AI-assisted.

Lines 90-91 of `gyro_bias` adjustment read `gyro.x` for both the Y and Z
axes, so the running per-axis bias estimate for Y and Z was driven by
the X-axis gyro reading instead of its own axis. Result: Y and Z bias
diverge from the actual sensor bias, and downstream `gyro.y -= gyro_bias.y`
/ `gyro.z -= gyro_bias.z` corrections drift instead of converge.

Read `gyro.y` for the Y bias update and `gyro.z` for the Z update, so
each axis's complementary-filter bias estimator uses its own measurement,
matching the X-axis line and the gyro-bias bookkeeping that follows on
lines 93-95.

Fixes malloch#7
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.

Typo in gyroscope adjust

1 participant