diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 01ac407a57..8350ccf2de 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -199,7 +199,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) if (ap.rc_receiver_present && !failsafe.radio) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER; } - if (!ins.get_gyro_health_all()) { + if (!ins.get_gyro_health_all() || !ins.gyro_calibrated_ok_all()) { control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO; } if (!ins.get_accel_health_all()) {