mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: initialise gpsSpdAccuracy
This commit is contained in:
parent
98c32012fa
commit
3165c43dfe
|
@ -4474,6 +4474,7 @@ void NavEKF::InitialiseVariables()
|
|||
flowXfailed = false;
|
||||
haveDeltaAngles = false;
|
||||
validOrigin = false;
|
||||
gpsSpdAccuracy = 0.0f;
|
||||
}
|
||||
|
||||
// return true if we should use the airspeed sensor
|
||||
|
|
Loading…
Reference in New Issue