diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 2a9d38b42e..9217bc4ae6 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -4340,21 +4340,21 @@ void NavEKF::ZeroVariables() lastHealthyMagTime_ms = imuSampleTime_ms; TASmsecPrev = imuSampleTime_ms; BETAmsecPrev = imuSampleTime_ms; - lastMagUpdate = imuSampleTime_ms; + lastMagUpdate = 0; lastHgtMeasTime = imuSampleTime_ms; - lastHgtTime_ms = imuSampleTime_ms; - lastAirspeedUpdate = imuSampleTime_ms; + lastHgtTime_ms = 0; + lastAirspeedUpdate = 0; velFailTime = imuSampleTime_ms; posFailTime = imuSampleTime_ms; hgtFailTime = imuSampleTime_ms; tasFailTime = imuSampleTime_ms; lastStateStoreTime_ms = imuSampleTime_ms; - lastFixTime_ms = imuSampleTime_ms; - secondLastFixTime_ms = imuSampleTime_ms; + lastFixTime_ms = 0; + secondLastFixTime_ms = 0; lastDecayTime_ms = imuSampleTime_ms; timeAtLastAuxEKF_ms = imuSampleTime_ms; flowValidMeaTime_ms = imuSampleTime_ms; - flowMeaTime_ms = imuSampleTime_ms; + flowMeaTime_ms = 0; prevFlowFusionTime_ms = imuSampleTime_ms; rngMeaTime_ms = imuSampleTime_ms; ekfStartTime_ms = imuSampleTime_ms;