AP_NavEKF: Remove bug preventing external selection of optical flow mode

This commit is contained in:
Paul Riseborough 2015-05-09 14:01:27 +10:00 committed by Andrew Tridgell
parent d61848817b
commit cb59570938
1 changed files with 1 additions and 1 deletions

View File

@ -3700,11 +3700,11 @@ uint8_t NavEKF::setInhibitGPS(void)
return 0;
}
if (optFlowDataPresent()) {
_fusionModeGPS = 3;
return 2;
} else {
return 1;
}
_fusionModeGPS = 3;
}
// return the horizontal speed limit in m/s set by optical flow sensor limits