Skip to content

Commit

Permalink
AP_AHRS: remove changes to primary accel since it is always the same …
Browse files Browse the repository at this point in the history
…as the gyro
  • Loading branch information
andyp1per authored and tridge committed Jan 29, 2025
1 parent a5d04eb commit 9da3653
Showing 1 changed file with 2 additions and 7 deletions.
9 changes: 2 additions & 7 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,20 +347,15 @@ void AP_AHRS::reset_gyro_drift(void)
void AP_AHRS::update_state(void)
{
const uint8_t primary_gyro = _get_primary_gyro_index();
const uint8_t primary_accel = _get_primary_accel_index();
#if AP_INERTIALSENSOR_ENABLED
// tell the IMUS about primary changes
if (primary_gyro != state.primary_gyro) {
AP::ins().set_primary_gyro(primary_gyro);
}

if (primary_accel != state.primary_accel) {
AP::ins().set_primary_accel(primary_accel);
AP::ins().set_primary(primary_gyro);
}
#endif
state.primary_IMU = _get_primary_IMU_index();
state.primary_gyro = primary_gyro;
state.primary_accel = primary_accel;
state.primary_accel = _get_primary_accel_index();
state.primary_core = _get_primary_core_index();
state.wind_estimate_ok = _wind_estimate(state.wind_estimate);
state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS();
Expand Down

0 comments on commit 9da3653

Please sign in to comment.