AP_NavEKF3: flowDataToFuse moved to local variable

This variable is never used outside the SelectFlowFusion() method
This variable is always updated at the top of the function meaning subsequent calls to the function will always overwrite its previous value
This commit is contained in:
Randy Mackay 2020-08-18 11:46:57 +09:00
parent 41acf555bf
commit c4b7a1c41a
2 changed files with 1 additions and 4 deletions

View File

@ -31,7 +31,7 @@ void NavEKF3_core::SelectFlowFusion()
}
// Check for data at the fusion time horizon
flowDataToFuse = storedOF.recall(ofDataDelayed, imuDataDelayed.time_ms);
const bool flowDataToFuse = storedOF.recall(ofDataDelayed, imuDataDelayed.time_ms);
// Perform Data Checks
// Check if the optical flow data is still valid
@ -63,8 +63,6 @@ void NavEKF3_core::SelectFlowFusion()
// Fuse the optical flow X and Y axis data into the main filter sequentially
FuseOptFlow();
}
// reset flag to indicate that no new flow data is available for fusion
flowDataToFuse = false;
}
// stop the performance timer

View File

@ -1195,7 +1195,6 @@ private:
of_elements ofDataNew; // OF data at the current time horizon
of_elements ofDataDelayed; // OF data at the fusion time horizon
uint8_t ofStoreIndex; // OF data storage index
bool flowDataToFuse; // true when optical flow data has is ready for fusion
bool flowDataValid; // true while optical flow data is still fresh
Vector2f auxFlowObsInnov; // optical flow rate innovation from 1-state terrain offset estimator
uint32_t flowValidMeaTime_ms; // time stamp from latest valid flow measurement (msec)