AP_NavEKF2: support higher optical flow updates rates

This commit is contained in:
Randy Mackay 2019-04-16 11:36:22 +09:00
parent 5c99f02c15
commit e19d638c0f
2 changed files with 2 additions and 1 deletions

View File

@ -73,7 +73,7 @@ bool NavEKF2_core::setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _c
if(!storedTAS.init(OBS_BUFFER_LENGTH)) {
return false;
}
if(!storedOF.init(OBS_BUFFER_LENGTH)) {
if(!storedOF.init(FLOW_BUFFER_LENGTH)) {
return false;
}
// Note: the use of dual range finders potentially doubles the amount of to be stored

View File

@ -755,6 +755,7 @@ private:
// Length of FIFO buffers used for non-IMU sensor data.
// Must be larger than the time period defined by IMU_BUFFER_LENGTH
static const uint32_t OBS_BUFFER_LENGTH = 5;
static const uint32_t FLOW_BUFFER_LENGTH = 15;
// Variables
bool statesInitialised; // boolean true when filter states have been initialised