From d0d49065e7d92e5481de1d8d4e4633d9743456e4 Mon Sep 17 00:00:00 2001 From: priseborough Date: Wed, 7 Jan 2015 22:58:29 +1100 Subject: [PATCH] AP_NavEKF: Prevent potential repeated use of optical flow data --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 367805faee..fbf5890e7e 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -988,6 +988,8 @@ void NavEKF::SelectFlowFusion() FuseOptFlow(); // Reset the measurement axis index to prevent further fusion of this data flow_state.obsIndex = 0; + // reset flag to indicate that no new flow data is available for fusion + newDataFlow = false; // indicate that flow fusion has been performed. This is used for load spreading. flowFusePerformed = true; }