AP_NavEKF: Ensure bad mag data cannot cause the heading to reset too often

This commit is contained in:
Paul Riseborough 2015-09-15 17:17:05 +10:00 committed by Randy Mackay
parent 930f730612
commit 8cfde42e15
1 changed files with 2 additions and 0 deletions

View File

@ -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