Browse Source

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

zr-v5.1
Randy Mackay 4 years ago
parent
commit
cede4bb028
  1. 1
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

1
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -194,6 +194,7 @@ void NavEKF2_core::InitialiseVariables() @@ -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;

Loading…
Cancel
Save