Copter: use barometer.all_healthy() for health check in SYS_STATUS and arming

This commit is contained in:
Andrew Tridgell 2015-01-07 12:45:50 +11:00
parent ca431a47a6
commit 557f4df77e
2 changed files with 2 additions and 2 deletions

View File

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

View File

@ -232,7 +232,7 @@ static void pre_arm_checks(bool display_failure)
// check Baro // check Baro
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) { if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
// barometer health check // barometer health check
if(!barometer.healthy()) { if(!barometer.all_healthy()) {
if (display_failure) { if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Barometer not healthy")); gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Barometer not healthy"));
} }