From 8cfde42e157f23a711d81c2f7544db0640536edf Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Tue, 15 Sep 2015 17:17:05 +1000 Subject: [PATCH] AP_NavEKF: Ensure bad mag data cannot cause the heading to reset too often --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index dbc1bdae8e..8d7212bcb3 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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