AP_NavEKF: Modify initial values to make startup behaviour more consistent

This commit is contained in:
priseborough 2014-12-22 08:12:21 +11:00 committed by Randy Mackay
parent a63af34d8f
commit 5d1de79f08
1 changed files with 6 additions and 6 deletions

View File

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