mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_NavEKF : Don't update focal length scale factor at low speeds
This commit is contained in:
parent
8dd1081f54
commit
b1d3d5d9a3
@ -3674,8 +3674,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 flying at low velocity
|
||||
if (!useRngFinder() || !highGndSpdStage2) {
|
||||
fScaleInhibit = true;
|
||||
} else {
|
||||
fScaleInhibit = false;
|
||||
|
Loading…
Reference in New Issue
Block a user