Browse Source

Plane: report gyro unhealthy if failed calibration

master
Randy Mackay 10 years ago
parent
commit
6d8e760582
  1. 2
      ArduPlane/GCS_Mavlink.pde

2
ArduPlane/GCS_Mavlink.pde

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

Loading…
Cancel
Save