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

This commit is contained in:
priseborough 2014-10-24 20:24:32 +11:00 committed by Andrew Tridgell
parent 4c92a5f23f
commit e09ff84218

View File

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