Browse Source

Copter: report gyro unhealthy if failed calibration

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
9a0a83f404
  1. 2
      ArduCopter/GCS_Mavlink.pde

2
ArduCopter/GCS_Mavlink.pde

@ -206,7 +206,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -206,7 +206,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()) {

Loading…
Cancel
Save