Plane: report gyro unhealthy if failed calibration

This commit is contained in:
Randy Mackay 2014-10-08 20:19:37 +09:00
parent a8733ae8a8
commit 6d8e760582

View File

@ -228,7 +228,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (!ins.get_gyro_health_all()) {
if (!ins.get_gyro_health_all() || (!g.skip_gyro_cal && !ins.gyro_calibrated_ok_all())) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
}
if (!ins.get_accel_health_all()) {