mirror of https://github.com/ArduPilot/ardupilot
Blimp: use AP::compass().available in place of enabled()
This commit is contained in:
parent
d40587062e
commit
6e68292c62
|
@ -133,7 +133,7 @@ void Blimp::update_batt_compass(void)
|
||||||
// read battery before compass because it may be used for motor interference compensation
|
// read battery before compass because it may be used for motor interference compensation
|
||||||
battery.read();
|
battery.read();
|
||||||
|
|
||||||
if (AP::compass().enabled()) {
|
if (AP::compass().available()) {
|
||||||
// update compass with throttle value - used for compassmot
|
// update compass with throttle value - used for compassmot
|
||||||
compass.set_voltage(battery.voltage());
|
compass.set_voltage(battery.voltage());
|
||||||
compass.read();
|
compass.read();
|
||||||
|
|
Loading…
Reference in New Issue