mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: report compass unhealthy if primary compass unhealthy
This commit is contained in:
parent
bf4566095a
commit
d124fdb182
@ -206,7 +206,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_3D_MAG |
|
||||
MAV_SYS_STATUS_SENSOR_GPS |
|
||||
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE);
|
||||
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
|
||||
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (g_gps != NULL && g_gps->status() >= GPS::GPS_OK_FIX_3D) {
|
||||
|
Loading…
Reference in New Issue
Block a user