AP_AHRS: removed limit on normalisation of accel reference vectors
this could lead to a bias in the accel drift correction
This commit is contained in:
parent
f9c72f9dbf
commit
a69ecfa06b
@ -561,14 +561,12 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
|
|
||||||
// calculate the error term in earth frame.
|
// calculate the error term in earth frame.
|
||||||
Vector3f GA_b = _ra_sum / (_ra_deltat * GRAVITY_MSS);
|
Vector3f GA_b = _ra_sum / (_ra_deltat * GRAVITY_MSS);
|
||||||
float length = GA_b.length();
|
GA_b.normalize();
|
||||||
if (length > 1.0f) {
|
if (GA_b.is_inf()) {
|
||||||
GA_b /= length;
|
// wait for some non-zero acceleration information
|
||||||
if (GA_b.is_inf()) {
|
return;
|
||||||
// wait for some non-zero acceleration information
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3f error = GA_b % GA_e;
|
Vector3f error = GA_b % GA_e;
|
||||||
|
|
||||||
#define YAW_INDEPENDENT_DRIFT_CORRECTION 0
|
#define YAW_INDEPENDENT_DRIFT_CORRECTION 0
|
||||||
|
Loading…
Reference in New Issue
Block a user