diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_rate_config.h b/libraries/AP_InertialSensor/AP_InertialSensor_rate_config.h index b7305e76964a09..8bf45fecab7f05 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_rate_config.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_rate_config.h @@ -7,7 +7,3 @@ #ifndef AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED #define AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED (AP_INERTIALSENSOR_ENABLED && HAL_INS_RATE_LOOP && AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED && APM_BUILD_TYPE(APM_BUILD_ArduCopter)) #endif - -#ifndef AP_INERTIALSENSOR_DYNAMIC_FIFO_MASK -#define AP_INERTIALSENSOR_DYNAMIC_FIFO_MASK 127 -#endif diff --git a/libraries/AP_InertialSensor/FastRateBuffer.cpp b/libraries/AP_InertialSensor/FastRateBuffer.cpp index b47450493d41ea..44ef58513982ef 100644 --- a/libraries/AP_InertialSensor/FastRateBuffer.cpp +++ b/libraries/AP_InertialSensor/FastRateBuffer.cpp @@ -85,8 +85,7 @@ bool AP_InertialSensor::is_dynamic_fifo_enabled(uint8_t instance) const if (!fast_rate_buffer_enabled || fast_rate_buffer == nullptr) { return false; } - return ((1U<use_rate_loop_gyro_samples(); }