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

This commit is contained in:
Randy Mackay 2021-05-27 13:48:07 +09:00
parent 126456742a
commit 02f6ca51bc
1 changed files with 1 additions and 0 deletions

View File

@ -277,6 +277,7 @@ void NavEKF3_core::InitialiseVariables()
gpsPosAccuracy = 0.0f;
gpsHgtAccuracy = 0.0f;
baroHgtOffset = 0.0f;
rngOnGnd = 0.05f;
yawResetAngle = 0.0f;
lastYawReset_ms = 0;
tiltErrorVariance = sq(M_2PI);