mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_NavEKF: Modify initial values to make startup behaviour more consistent
This commit is contained in:
parent
a63af34d8f
commit
5d1de79f08
@ -4340,21 +4340,21 @@ void NavEKF::ZeroVariables()
|
|||||||
lastHealthyMagTime_ms = imuSampleTime_ms;
|
lastHealthyMagTime_ms = imuSampleTime_ms;
|
||||||
TASmsecPrev = imuSampleTime_ms;
|
TASmsecPrev = imuSampleTime_ms;
|
||||||
BETAmsecPrev = imuSampleTime_ms;
|
BETAmsecPrev = imuSampleTime_ms;
|
||||||
lastMagUpdate = imuSampleTime_ms;
|
lastMagUpdate = 0;
|
||||||
lastHgtMeasTime = imuSampleTime_ms;
|
lastHgtMeasTime = imuSampleTime_ms;
|
||||||
lastHgtTime_ms = imuSampleTime_ms;
|
lastHgtTime_ms = 0;
|
||||||
lastAirspeedUpdate = imuSampleTime_ms;
|
lastAirspeedUpdate = 0;
|
||||||
velFailTime = imuSampleTime_ms;
|
velFailTime = imuSampleTime_ms;
|
||||||
posFailTime = imuSampleTime_ms;
|
posFailTime = imuSampleTime_ms;
|
||||||
hgtFailTime = imuSampleTime_ms;
|
hgtFailTime = imuSampleTime_ms;
|
||||||
tasFailTime = imuSampleTime_ms;
|
tasFailTime = imuSampleTime_ms;
|
||||||
lastStateStoreTime_ms = imuSampleTime_ms;
|
lastStateStoreTime_ms = imuSampleTime_ms;
|
||||||
lastFixTime_ms = imuSampleTime_ms;
|
lastFixTime_ms = 0;
|
||||||
secondLastFixTime_ms = imuSampleTime_ms;
|
secondLastFixTime_ms = 0;
|
||||||
lastDecayTime_ms = imuSampleTime_ms;
|
lastDecayTime_ms = imuSampleTime_ms;
|
||||||
timeAtLastAuxEKF_ms = imuSampleTime_ms;
|
timeAtLastAuxEKF_ms = imuSampleTime_ms;
|
||||||
flowValidMeaTime_ms = imuSampleTime_ms;
|
flowValidMeaTime_ms = imuSampleTime_ms;
|
||||||
flowMeaTime_ms = imuSampleTime_ms;
|
flowMeaTime_ms = 0;
|
||||||
prevFlowFusionTime_ms = imuSampleTime_ms;
|
prevFlowFusionTime_ms = imuSampleTime_ms;
|
||||||
rngMeaTime_ms = imuSampleTime_ms;
|
rngMeaTime_ms = imuSampleTime_ms;
|
||||||
ekfStartTime_ms = imuSampleTime_ms;
|
ekfStartTime_ms = imuSampleTime_ms;
|
||||||
|
Loading…
Reference in New Issue
Block a user