AP_NavEKF2: init rngOnGnd to 5cm to avoid div-by-zero

This commit is contained in:
Randy Mackay 2021-08-25 22:02:09 +09:00
parent e5ea7e6196
commit 54d6cf15e5

View File

@ -194,6 +194,7 @@ void NavEKF2_core::InitialiseVariables()
gpsPosAccuracy = 0.0f;
gpsHgtAccuracy = 0.0f;
baroHgtOffset = 0.0f;
rngOnGnd = 0.05f;
yawResetAngle = 0.0f;
lastYawReset_ms = 0;
tiltErrFilt = 1.0f;