mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 02:44:00 -04:00
AP_NavEKF: Initialise timeout status to true
This status will be cleared when data arrives and is fused successfully
This commit is contained in:
parent
363c1e393d
commit
a535b73a6d
@ -4355,11 +4355,11 @@ void NavEKF::ZeroVariables()
|
|||||||
rngMeaTime_ms = imuSampleTime_ms;
|
rngMeaTime_ms = imuSampleTime_ms;
|
||||||
|
|
||||||
gpsNoiseScaler = 1.0f;
|
gpsNoiseScaler = 1.0f;
|
||||||
velTimeout = false;
|
velTimeout = true;
|
||||||
posTimeout = false;
|
posTimeout = true;
|
||||||
hgtTimeout = false;
|
hgtTimeout = true;
|
||||||
magTimeout = false;
|
magTimeout = true;
|
||||||
tasTimeout = false;
|
tasTimeout = true;
|
||||||
badMag = false;
|
badMag = false;
|
||||||
badIMUdata = false;
|
badIMUdata = false;
|
||||||
firstArmComplete = false;
|
firstArmComplete = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user