AP_NavEKF : Don't update focal length scale factor at low speeds

This commit is contained in:
priseborough 2014-10-16 16:03:37 +11:00 committed by Andrew Tridgell
parent 8dd1081f54
commit b1d3d5d9a3
1 changed files with 2 additions and 2 deletions

View File

@ -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;