diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index ee738d1bc2..77ce49a874 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -182,7 +182,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack // default to all healthy except compass, gps and receiver which we set individually control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS & ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER); - 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 && !gps_glitch.glitching()) { diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index f2ceeeedc4..4c94f17c8d 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -248,7 +248,7 @@ static void pre_arm_checks(bool display_failure) // check Compass if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) { // check the compass is healthy - if(!compass.healthy) { + if(!compass.healthy()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy")); } diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 2d2baa7e1d..5a3cb9d363 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -183,7 +183,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv) compass.read(); // exit immediately if the compass is not healthy - if( !compass.healthy ) { + if( !compass.healthy() ) { cliSerial->print_P(PSTR("check compass\n")); return 0; } @@ -208,7 +208,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv) last_run_time = millis(); // main run while there is no user input and the compass is healthy - while(!cliSerial->available() && compass.healthy) { + while(!cliSerial->available() && compass.healthy()) { // 50hz loop if( millis() - last_run_time > 20 ) { diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index 2465df9129..476337a1fa 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -141,7 +141,7 @@ test_compass(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"),