Plane: use all_healthy() for SYS_STATUS health

This commit is contained in:
Andrew Tridgell 2015-01-07 12:45:19 +11:00
parent 1c2a6deaaf
commit ca431a47a6

View File

@ -229,7 +229,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
if (barometer.healthy()) {
if (barometer.all_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {