AP_NavEKF: initialise gpsSpdAccuracy

This commit is contained in:
Andrew Tridgell 2015-03-28 11:43:55 -07:00
parent 98c32012fa
commit 3165c43dfe

View File

@ -4474,6 +4474,7 @@ void NavEKF::InitialiseVariables()
flowXfailed = false; flowXfailed = false;
haveDeltaAngles = false; haveDeltaAngles = false;
validOrigin = false; validOrigin = false;
gpsSpdAccuracy = 0.0f;
} }
// return true if we should use the airspeed sensor // return true if we should use the airspeed sensor