mirror of https://github.com/ArduPilot/ardupilot
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 {
|
} else {
|
||||||
inhibitGndState = false;
|
inhibitGndState = false;
|
||||||
}
|
}
|
||||||
// Don't update focal length offset state if there is no range finder
|
// Don't update focal length offset state if there is no range finder or flying at low velocity
|
||||||
if (!useRngFinder()) {
|
if (!useRngFinder() || !highGndSpdStage2) {
|
||||||
fScaleInhibit = true;
|
fScaleInhibit = true;
|
||||||
} else {
|
} else {
|
||||||
fScaleInhibit = false;
|
fScaleInhibit = false;
|
||||||
|
|
Loading…
Reference in New Issue