mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Ensure bad mag data cannot cause the heading to reset too often
This commit is contained in:
parent
930f730612
commit
8cfde42e15
|
@ -5232,6 +5232,8 @@ bool NavEKF::calcGpsGoodToAlign(void)
|
|||
Vector3f eulerAngles;
|
||||
getEulerAngles(eulerAngles);
|
||||
state.quat = calcQuatAndFieldStates(eulerAngles.x, eulerAngles.y);
|
||||
// reset timer to ensure that bad magnetometer data cannot cause a heading reset more often than every 5 seconds
|
||||
magYawResetTimer_ms = imuSampleTime_ms;
|
||||
}
|
||||
|
||||
// fail if magnetometer innovations are outside limits indicating bad yaw
|
||||
|
|
Loading…
Reference in New Issue