diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e367cb88de..9c25fc6a8d 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -216,7 +216,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) // AHRS subsystem is unhealthy control_sensors_health &= ~MAV_SYS_STATUS_AHRS; } - if (barometer.healthy) { + if (barometer.healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; } if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) { diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 6af94c30c4..57a9bc1e9e 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -456,8 +456,8 @@ static void check_short_failsafe() static void startup_INS_ground(bool do_accel_init) { #if HIL_MODE != HIL_MODE_DISABLED - while (!barometer.healthy) { - // the barometer becomes healthy when we get the first + while (barometer.get_last_update() == 0) { + // the barometer begins updating when we get the first // HIL_STATE message gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message")); delay(1000); diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index 7dc7c22f69..7cec78b3c0 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -578,7 +578,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv) while(1) { delay(100); - if (!barometer.healthy) { + if (!barometer.healthy()) { cliSerial->println_P(PSTR("not healthy")); } else { cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),