AP_NavEKF : Explicitly initialise gpsNoiseScaler to default value

This commit is contained in:
priseborough 2014-09-24 14:19:55 +10:00 committed by Andrew Tridgell
parent b61a6c64d7
commit 8223a0d193
1 changed files with 1 additions and 0 deletions

View File

@ -3402,6 +3402,7 @@ void NavEKF::ZeroVariables()
secondLastFixTime_ms = imuSampleTime_ms;
lastDecayTime_ms = imuSampleTime_ms;
gpsNoiseScaler = 1.0f;
velTimeout = false;
posTimeout = false;
hgtTimeout = false;