From 8e5c0fa32bfb5efb0a36090cc76e6a3f820caae7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jul 2019 18:05:51 +1000 Subject: [PATCH] AP_InertialSensor: disable kill IMUs with HAL_MINIMIZE_FEATURES --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index eec537ec7a..1683f97ec8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -2045,6 +2045,7 @@ AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_t return (Gyro_Calibration_Timing)_gyro_cal_timing.get(); } +#if !HAL_MINIMIZE_FEATURES /* update IMU kill mask, used for testing IMU failover */ @@ -2067,6 +2068,7 @@ void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it) imu_kill_mask &= ~(1U<