diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index b1896d29b4..7ab35833ff 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) if (barometer.all_healthy()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; } - if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) { + if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) { control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG; } if (gps.status() > AP_GPS::NO_GPS) { diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index dfcd187b49..e8976f0ef7 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -258,7 +258,7 @@ static bool pre_arm_checks(bool display_failure) // check Compass if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_COMPASS)) { // check the primary compass is healthy - if(!compass.healthy(0)) { + if(!compass.healthy()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy")); }