From a0a6c0362f62ee3f9e9d9928e7f4961b43029650 Mon Sep 17 00:00:00 2001 From: priseborough Date: Sun, 21 Dec 2014 15:13:07 +1100 Subject: [PATCH] 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. --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index e5f12d72a9..b5c1a719d7 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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;