Quaternion: use gyro drift value from sensor driver

This commit is contained in:
Andrew Tridgell 2012-03-09 09:02:46 +11:00
parent 3989fe2c2c
commit eff6778515
1 changed files with 4 additions and 0 deletions

View File

@ -25,6 +25,10 @@ public:
b_x = 0;
b_z = -1;
// limit the drift to the drift rate reported by the
// sensor driver
gyroMeasDrift = imu->get_gyro_drift_rate();
// scaled gyro drift limits
beta = sqrt(3.0f / 4.0f) * gyroMeasError;
zeta = sqrt(3.0f / 4.0f) * gyroMeasDrift;