From f7b877f4dade81c16bb5749f6c22f02891e2d81e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 28 Jul 2021 10:27:39 +1000 Subject: [PATCH] ArduCopter: use AP::compass().available in place of enabled() --- ArduCopter/Copter.cpp | 2 +- ArduCopter/compassmot.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 1ee70b7452..29c05a7bca 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -380,7 +380,7 @@ void Copter::update_batt_compass(void) // read battery before compass because it may be used for motor interference compensation battery.read(); - if(AP::compass().enabled()) { + if(AP::compass().available()) { // update compass with throttle value - used for compassmot compass.set_throttle(motors->get_throttle()); compass.set_voltage(battery.voltage()); diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 63ae89e807..93a8fd171c 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -34,7 +34,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) } // check compass is enabled - if (!AP::compass().enabled()) { + if (!AP::compass().available()) { gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled"); ap.compass_mot = false; return MAV_RESULT_TEMPORARILY_REJECTED;