mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: report gyro unhealthy if failed calibration
This commit is contained in:
parent
a8733ae8a8
commit
6d8e760582
@ -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()) {
|
||||
|
Loading…
Reference in New Issue
Block a user