Browse Source

AP_NavEKF : Don't estimate focal length scale factor without reliable velocity

mission-4.1.18
priseborough 10 years ago committed by Andrew Tridgell
parent
commit
e09ff84218
  1. 4
      libraries/AP_NavEKF/AP_NavEKF.cpp

4
libraries/AP_NavEKF/AP_NavEKF.cpp

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