From 49f49648ec1e71465c5e82d5efa5972df494ddb1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 Dec 2013 17:47:38 +1100 Subject: [PATCH] Plane: changes for compass healthy API --- ArduPlane/GCS_Mavlink.pde | 2 +- ArduPlane/test.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 55ef068a0c..92154922eb 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -206,7 +206,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_3D_MAG | MAV_SYS_STATUS_SENSOR_GPS | MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE); - if (g.compass_enabled && compass.healthy && ahrs.use_compass()) { + if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) { diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index 10b8184940..0c3a364111 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -522,7 +522,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) counter++; if (counter>20) { - if (compass.healthy) { + if (compass.healthy()) { const Vector3f &mag_ofs = compass.get_offsets(); const Vector3f &mag = compass.get_field(); cliSerial->printf_P(PSTR("Heading: %ld, XYZ: %.0f, %.0f, %.0f,\tXYZoff: %6.2f, %6.2f, %6.2f\n"),