mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF2: init rngOnGnd to 5cm to avoid div-by-zero
This commit is contained in:
parent
ff58054d1b
commit
b524094216
@ -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…
Reference in New Issue
Block a user