From 557f4df77e018b341cead55d1a5ad0855c8fb25b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Jan 2015 12:45:50 +1100 Subject: [PATCH] Copter: use barometer.all_healthy() for health check in SYS_STATUS and arming --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduCopter/motors.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index e0efe0fa56..b2cde83b7a 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -194,7 +194,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) MAV_SYS_STATUS_SENSOR_3D_MAG | MAV_SYS_STATUS_SENSOR_GPS | MAV_SYS_STATUS_SENSOR_RC_RECEIVER); - 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()) { diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index a2438a9e7f..0d2499843d 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -232,7 +232,7 @@ static void pre_arm_checks(bool display_failure) // check Baro if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) { // barometer health check - if(!barometer.healthy()) { + if(!barometer.all_healthy()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Barometer not healthy")); }