diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 2eec3c84598af7..6a394740eb36f1 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -342,7 +342,7 @@ 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); @@ -351,7 +351,7 @@ void AP_AHRS::update_state(void) if (primary_accel != state.primary_accel) { AP::ins().set_primary_accel(primary_accel); } - +#endif state.primary_IMU = _get_primary_IMU_index(); state.primary_gyro = primary_gyro; state.primary_accel = primary_accel;