From 0337d44b2e1552b37162501ab4834edbd717dd60 Mon Sep 17 00:00:00 2001
From: priseborough <p_riseborough@live.com.au>
Date: Fri, 16 May 2014 21:11:39 +1000
Subject: [PATCH] AP_NavEKF: Fix bug causing immediate clearing of diverged
 status on reset

---
 libraries/AP_NavEKF/AP_NavEKF.cpp | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp
index 00d87bba1..0b49a5138 100644
--- a/libraries/AP_NavEKF/AP_NavEKF.cpp
+++ b/libraries/AP_NavEKF/AP_NavEKF.cpp
@@ -355,6 +355,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
     IMU1_weighting = 0.5f;
     lastDivergeTime_ms = 0;
     filterDiverged = false;
+    memset(&faultStatus, 0, sizeof(faultStatus));
 }
 
 // Check basic filter health metrics and return a consolidated health status
@@ -3299,7 +3300,6 @@ void NavEKF::ZeroVariables()
     velTimeout = false;
     posTimeout = false;
     hgtTimeout = false;
-    filterDiverged = false;
     lastStateStoreTime_ms = 0;
     lastFixTime_ms = 0;
     secondLastFixTime_ms = 0;
@@ -3320,7 +3320,6 @@ void NavEKF::ZeroVariables()
     dt = 0;
     hgtMea = 0;
     storeIndex = 0;
-    memset(&faultStatus, 0, sizeof(faultStatus));
     lastGyroBias.zero();
 	prevDelAng.zero();
     lastAngRate.zero();
-- 
GitLab