mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF: initialise gpsSpdAccuracy
This commit is contained in:
parent
98c32012fa
commit
3165c43dfe
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user