From 7686660c736e1f1c289006d0e9f7e508518522a9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 13 Aug 2014 22:54:41 +0900 Subject: [PATCH] Copter: use baro healthy() --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduCopter/motors.pde | 2 +- ArduCopter/system.pde | 4 ++-- ArduCopter/test.pde | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index c38db2e4dc..798f8ef148 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -187,7 +187,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.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 9d87247887..fbdbbf3cfd 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -240,7 +240,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.healthy()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Baro not healthy")); } diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 915e770f12..ee00e4a0d3 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -248,8 +248,8 @@ static void init_ardupilot() #endif // CLI_ENABLED #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/ArduCopter/test.pde b/ArduCopter/test.pde index b309792241..d59c10248a 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -60,7 +60,7 @@ test_baro(uint8_t argc, const Menu::arg *argv) delay(100); alt = read_barometer(); - 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"),