AP_NavEKF: Prevent potential repeated use of optical flow data

This commit is contained in:
priseborough 2015-01-07 22:58:29 +11:00 committed by Andrew Tridgell
parent b0c703e4f7
commit d0d49065e7

View File

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