Browse Source

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

master
priseborough 10 years ago committed by Andrew Tridgell
parent
commit
b1d3d5d9a3
  1. 4
      libraries/AP_NavEKF/AP_NavEKF.cpp

4
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -3674,8 +3674,8 @@ void NavEKF::SetFlightAndFusionModes() @@ -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…
Cancel
Save