mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
ArduCopter: use AP::compass().available in place of enabled()
This commit is contained in:
parent
0189ee2a04
commit
f7b877f4da
@ -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());
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user