AHRS: if we don't have gps correction enabled, zero the yaw correction
This commit is contained in:
parent
613849a8df
commit
5f5ab9c07c
@ -489,9 +489,13 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
// to reduce the impact of two competing yaw controllers, we
|
// to reduce the impact of two competing yaw controllers, we
|
||||||
// reduce the impact of the gps/accelerometers on yaw when we are
|
// reduce the impact of the gps/accelerometers on yaw when we are
|
||||||
// flat, but still allow for yaw correction using the
|
// flat, but still allow for yaw correction using the
|
||||||
// accelerometers at high roll angles.
|
// accelerometers at high roll angles as long as we have a GPS
|
||||||
if (_compass && _compass->use_for_yaw()) {
|
if (_compass && _compass->use_for_yaw()) {
|
||||||
error.z *= sin(fabs(roll));
|
if (_gps && _gps->status() == GPS::GPS_OK && gps_gain == 1.0) {
|
||||||
|
error.z *= sin(fabs(roll));
|
||||||
|
} else {
|
||||||
|
error.z = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert the error term to body frame
|
// convert the error term to body frame
|
||||||
|
Loading…
Reference in New Issue
Block a user