mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF : Don't estimate focal length scale factor without reliable velocity
This commit is contained in:
parent
4c92a5f23f
commit
e09ff84218
@ -3689,8 +3689,8 @@ void NavEKF::SetFlightAndFusionModes()
|
||||
} else {
|
||||
inhibitGndState = false;
|
||||
}
|
||||
// Don't update focal length offset state if there is no range finder
|
||||
if (!useRngFinder()) {
|
||||
// Don't update focal length offset state if there is no range finder or GPS, or we are flying slowly
|
||||
if (!useRngFinder() || _fusionModeGPS == 3 || gndSpdSq < 5.0f) {
|
||||
fScaleInhibit = true;
|
||||
} else {
|
||||
fScaleInhibit = false;
|
||||
|
Loading…
Reference in New Issue
Block a user