mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF3: init rngOnGnd to 5cm to avoid div-by-zero
This commit is contained in:
parent
126456742a
commit
02f6ca51bc
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user