Browse Source

AP_InertialSensor: disable kill IMUs with HAL_MINIMIZE_FEATURES

master
Andrew Tridgell 6 years ago
parent
commit
8e5c0fa32b
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor.cpp

2
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(); return (Gyro_Calibration_Timing)_gyro_cal_timing.get();
} }
#if !HAL_MINIMIZE_FEATURES
/* /*
update IMU kill mask, used for testing IMU failover 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<<imu_idx); imu_kill_mask &= ~(1U<<imu_idx);
} }
} }
#endif // HAL_MINIMIZE_FEATURES
namespace AP { namespace AP {

Loading…
Cancel
Save