AP_InertialSensor: remove changes to primary accel since it is always the same as the gyro

This commit is contained in:
Andy Piper 2025-01-23 11:36:33 +00:00 committed by Andrew Tridgell
parent 9da365398a
commit 29655d149c
4 changed files with 13 additions and 22 deletions

View File

@ -1891,14 +1891,10 @@ void AP_InertialSensor::HarmonicNotch::update_params(uint8_t instance, bool conv
} }
#endif #endif
// notify IMUs of the new primaries // notify IMUs of the new primary
void AP_InertialSensor::set_primary_gyro(uint8_t instance) void AP_InertialSensor::set_primary(uint8_t instance)
{ {
_primary_gyro = instance; _primary = instance;
}
void AP_InertialSensor::set_primary_accel(uint8_t instance)
{
_primary_accel = instance;
} }
/* /*
@ -1974,7 +1970,7 @@ void AP_InertialSensor::update(void)
if (_gyro_healthy[i] && _use(i)) { if (_gyro_healthy[i] && _use(i)) {
_first_usable_gyro = i; _first_usable_gyro = i;
#if !AP_AHRS_ENABLED #if !AP_AHRS_ENABLED
_primary_gyro = _first_usable_gyro; _primary = _first_usable_gyro;
#endif #endif
break; break;
} }
@ -1982,9 +1978,6 @@ void AP_InertialSensor::update(void)
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) { for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
if (_accel_healthy[i] && _use(i)) { if (_accel_healthy[i] && _use(i)) {
_first_usable_accel = i; _first_usable_accel = i;
#if !AP_AHRS_ENABLED
_primary_accel = _first_usable_accel;
#endif
break; break;
} }
} }

View File

@ -283,9 +283,8 @@ public:
// Returns newly calculated trim values if calculated // Returns newly calculated trim values if calculated
bool get_new_trim(Vector3f &trim_rad); bool get_new_trim(Vector3f &trim_rad);
// notify IMUs of the new primaries // notify IMUs of the new primary
void set_primary_gyro(uint8_t instance); void set_primary(uint8_t instance);
void set_primary_accel(uint8_t instance);
#if HAL_INS_ACCELCAL_ENABLED #if HAL_INS_ACCELCAL_ENABLED
// initialise and register accel calibrator // initialise and register accel calibrator
@ -667,9 +666,8 @@ private:
uint8_t _first_usable_gyro; uint8_t _first_usable_gyro;
uint8_t _first_usable_accel; uint8_t _first_usable_accel;
// primary accel and gyro // primary instance
uint8_t _primary_gyro; uint8_t _primary;
uint8_t _primary_accel;
// mask of accels and gyros which we will be actively using // mask of accels and gyros which we will be actively using
// and this should wait for in wait_for_sample() // and this should wait for in wait_for_sample()

View File

@ -235,7 +235,7 @@ void AP_InertialSensor_Backend::apply_gyro_filters(const uint8_t instance, const
// currently active IMU we reset the inactive notch filters so // currently active IMU we reset the inactive notch filters so
// that if we switch IMUs we're not left with old data // that if we switch IMUs we're not left with old data
if (!notch.params.hasOption(HarmonicNotchFilterParams::Options::EnableOnAllIMUs) && if (!notch.params.hasOption(HarmonicNotchFilterParams::Options::EnableOnAllIMUs) &&
instance != _imu._primary_gyro) { instance != _imu._primary) {
inactive = true; inactive = true;
} }
if (inactive) { if (inactive) {
@ -471,7 +471,7 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa
} }
#if AP_AHRS_ENABLED #if AP_AHRS_ENABLED
const bool log_because_primary_gyro = _imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == AP::ahrs().get_primary_gyro_index()); const bool log_because_primary_gyro = _imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == _imu._primary);
#else #else
const bool log_because_primary_gyro = false; const bool log_because_primary_gyro = false;
#endif #endif
@ -811,9 +811,9 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance) /* front end */
void AP_InertialSensor_Backend::update_primary() void AP_InertialSensor_Backend::update_primary()
{ {
// timing changes need to be made in the bus thread in order to take effect which is // timing changes need to be made in the bus thread in order to take effect which is
// why they are actioned here. Currently the _primary_gyro and _primary_accel can never // why they are actioned here. Currently the primary gyro and primary accel can never
// be different for a particular IMU // be different for a particular IMU
const bool is_new_primary = (gyro_instance == _imu._primary_gyro); const bool is_new_primary = (gyro_instance == _imu._primary);
uint32_t now_us = AP_HAL::micros(); uint32_t now_us = AP_HAL::micros();
if (is_primary != is_new_primary if (is_primary != is_new_primary
|| AP_HAL::timeout_expired(last_primary_update_us, now_us, PRIMARY_UPDATE_TIMEOUT_US)) { || AP_HAL::timeout_expired(last_primary_update_us, now_us, PRIMARY_UPDATE_TIMEOUT_US)) {

View File

@ -196,7 +196,7 @@ void AP_InertialSensor::write_notch_log_messages() const
// ask the HarmonicNotchFilter object for primary gyro to // ask the HarmonicNotchFilter object for primary gyro to
// log the actual notch centers // log the actual notch centers
notch.filter[_primary_gyro].log_notch_centers(i, now_us); notch.filter[_primary].log_notch_centers(i, now_us);
} }
} }
#endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED #endif // AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED