From 3e137900399ba699e182313d1ac0e6bb9da398e7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 28 Jul 2021 10:27:39 +1000 Subject: [PATCH] ArduSub: use AP::compass().available in place of enabled() --- ArduSub/ArduSub.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index eeccffee8e..59bb1b2749 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -164,7 +164,7 @@ void Sub::update_batt_compass() // 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.read();