diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 8f16ba46131e8..81c09dc7d92a9 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -340,8 +340,15 @@ void AP_AHRS::reset_gyro_drift(void) */ void AP_AHRS::update_state(void) { + const uint8_t primary_gyro = _get_primary_gyro_index(); +#if AP_INERTIALSENSOR_ENABLED + // tell the IMUS about primary changes + if (primary_gyro != state.primary_gyro) { + AP::ins().set_primary(primary_gyro); + } +#endif state.primary_IMU = _get_primary_IMU_index(); - state.primary_gyro = _get_primary_gyro_index(); + state.primary_gyro = primary_gyro; state.primary_accel = _get_primary_accel_index(); state.primary_core = _get_primary_core_index(); state.wind_estimate_ok = _wind_estimate(state.wind_estimate); @@ -361,6 +368,7 @@ void AP_AHRS::update_state(void) state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED); } +// update run at loop rate void AP_AHRS::update(bool skip_ins_update) { // periodically checks to see if we should update the AHRS diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 24f2c51287c99..25ff1dcc0fcc0 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1891,6 +1891,12 @@ void AP_InertialSensor::HarmonicNotch::update_params(uint8_t instance, bool conv } #endif +// notify IMUs of the new primary +void AP_InertialSensor::set_primary(uint8_t instance) +{ + _primary = instance; +} + /* update gyro and accel values from backends */ @@ -1963,6 +1969,9 @@ void AP_InertialSensor::update(void) for (uint8_t i=0; i +#include "AP_InertialSensor_rate_config.h" #include "AP_InertialSensor_Invensensev3.h" #include #include @@ -170,7 +171,20 @@ struct PACKED FIFODataHighRes { static_assert(sizeof(FIFOData) == 16, "FIFOData must be 16 bytes"); static_assert(sizeof(FIFODataHighRes) == 20, "FIFODataHighRes must be 20 bytes"); +/* + 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 / 2x loop rate, + 4k/400 or 10 samples in the extreme case we are trying to support. We need double this to account for the + fact that we might only have 9 samples at the time the fifo is read and hence the next time it is read we + could have 19 sample + */ +#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_HAL::OwnPtr _dev, @@ -400,6 +414,21 @@ bool AP_InertialSensor_Invensensev3::update() return true; } +void AP_InertialSensor_Invensensev3::set_primary(bool _is_primary) +{ +#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED + if (_imu.is_dynamic_fifo_enabled(gyro_instance)) { + if (_is_primary) { + dev->adjust_periodic_callback(periodic_handle, backend_period_us); + } else { + // scale down non-primary to 2x loop rate, but no greater than the default sampling rate + dev->adjust_periodic_callback(periodic_handle, + 1000000UL / constrain_int16(get_loop_rate_hz() * 2, 400, 1000)); + } + } +#endif +} + /* accumulate new samples */ @@ -556,7 +585,9 @@ void AP_InertialSensor_Invensensev3::read_fifo() // adjust the periodic callback to be synchronous with the incoming data // this means that we rarely run read_fifo() without updating the sensor data - dev->adjust_periodic_callback(periodic_handle, backend_period_us); + if (is_primary) { + dev->adjust_periodic_callback(periodic_handle, backend_period_us); + } while (n_samples > 0) { uint8_t n = MIN(n_samples, INV3_FIFO_BUFFER_LEN); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h index 889fda4f76c86..2ea558b3fddda 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h @@ -45,6 +45,9 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend // acclerometers on Invensense sensors will return values up to 32G const uint16_t multiplier_accel = INT16_MAX/(32*GRAVITY_MSS); +protected: + void set_primary(bool _is_primary) override; + private: AP_InertialSensor_Invensensev3(AP_InertialSensor &imu, AP_HAL::OwnPtr dev, diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp index fa71deadd954c..a86ad4ebe8d25 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp @@ -196,8 +196,7 @@ void AP_InertialSensor::write_notch_log_messages() const // ask the HarmonicNotchFilter object for primary gyro to // log the actual notch centers - const uint8_t primary_gyro = AP::ahrs().get_primary_gyro_index(); - notch.filter[primary_gyro].log_notch_centers(i, now_us); + notch.filter[_primary].log_notch_centers(i, now_us); } } #endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED diff --git a/libraries/AP_InertialSensor/FastRateBuffer.cpp b/libraries/AP_InertialSensor/FastRateBuffer.cpp index 29601965d38ed..44ef58513982e 100644 --- a/libraries/AP_InertialSensor/FastRateBuffer.cpp +++ b/libraries/AP_InertialSensor/FastRateBuffer.cpp @@ -79,6 +79,16 @@ bool AP_InertialSensor::is_rate_loop_gyro_enabled(uint8_t instance) const return fast_rate_buffer->use_rate_loop_gyro_samples() && instance == AP::ahrs().get_primary_gyro_index(); } +// whether or not to use the dynamic fifo +bool AP_InertialSensor::is_dynamic_fifo_enabled(uint8_t instance) const +{ + if (!fast_rate_buffer_enabled || fast_rate_buffer == nullptr) { + return false; + } + return (_fast_sampling_mask & (1U<use_rate_loop_gyro_samples(); +} + // get the next available gyro sample from the fast rate buffer bool AP_InertialSensor::get_next_gyro_sample(Vector3f& gyro) {