From 6e68292c62917c89d2bc930e9bf8b8d6dfb83885 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 28 Jul 2021 11:54:59 +1000 Subject: [PATCH] Blimp: use AP::compass().available in place of enabled() --- Blimp/Blimp.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index e8406b28ac..34d0f6df35 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -133,7 +133,7 @@ void Blimp::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_voltage(battery.voltage()); compass.read();