AP_NavEKF: Relax timeout check applied to optical flow data

200 msec was too short and could lead to false positives. 5000 msec is the largest time we can go free inertial.
This commit is contained in:
priseborough 2014-12-21 15:13:07 +11:00 committed by Randy Mackay
parent 5bd4ee9715
commit a0a6c0362f

View File

@ -4418,7 +4418,7 @@ bool NavEKF::useRngFinder(void) const
// return true if optical flow data is available
bool NavEKF::optFlowDataPresent(void) const
{
if (imuSampleTime_ms - flowMeaTime_ms < 200) {
if (imuSampleTime_ms - flowMeaTime_ms < 5000) {
return true;
} else {
return false;