|
|
|
@ -2045,6 +2045,7 @@ AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_t
@@ -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)
@@ -2067,6 +2068,7 @@ void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it)
|
|
|
|
|
imu_kill_mask &= ~(1U<<imu_idx); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif // HAL_MINIMIZE_FEATURES
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
namespace AP { |
|
|
|
|