diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 2178cc582e..eec537ec7a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -2045,6 +2045,29 @@ AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_t return (Gyro_Calibration_Timing)_gyro_cal_timing.get(); } +/* + update IMU kill mask, used for testing IMU failover + */ +void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it) +{ + if (kill_it) { + uint8_t new_kill_mask = imu_kill_mask | (1U<