mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
ArduSub: use AP::compass().available in place of enabled()
This commit is contained in:
parent
c348f602d9
commit
3e13790039
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user