AP_InertialSensor: only increase FIFO buffer when compiled with fast rate

This commit is contained in:
Andy Piper 2024-12-21 20:39:41 +00:00
parent ed0eb5924c
commit c3da111e9f
1 changed files with 12 additions and 1 deletions

View File

@ -171,7 +171,18 @@ struct PACKED FIFODataHighRes {
static_assert(sizeof(FIFOData) == 16, "FIFOData must be 16 bytes"); static_assert(sizeof(FIFOData) == 16, "FIFOData must be 16 bytes");
static_assert(sizeof(FIFODataHighRes) == 20, "FIFODataHighRes must be 20 bytes"); static_assert(sizeof(FIFODataHighRes) == 20, "FIFODataHighRes must be 20 bytes");
#define INV3_FIFO_BUFFER_LEN 16 /*
Ideally we would like the fifo buffer to be big enough to hold all of the packets that might have been
accumulated between reads. This is so that they can all be read in a single SPI transaction and avoid
the overhead of multiple reads. The maximum number of samples for 20-bit high res that can be store in the
fifo is 2k/20, or 105 samples. The likely maximum required for dynamic fifo is the output data rate / loop rate,
4k/200 or 20 samples in the extreme case we are trying to support.
*/
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
#define INV3_FIFO_BUFFER_LEN 24
#else
#define INV3_FIFO_BUFFER_LEN 8
#endif
AP_InertialSensor_Invensensev3::AP_InertialSensor_Invensensev3(AP_InertialSensor &imu, AP_InertialSensor_Invensensev3::AP_InertialSensor_Invensensev3(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::Device> _dev, AP_HAL::OwnPtr<AP_HAL::Device> _dev,