Browse Source

ArduCopter: use AP::compass().available in place of enabled()

gps-1.3.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
f7b877f4da
  1. 2
      ArduCopter/Copter.cpp
  2. 2
      ArduCopter/compassmot.cpp

2
ArduCopter/Copter.cpp

@ -380,7 +380,7 @@ void Copter::update_batt_compass(void) @@ -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());

2
ArduCopter/compassmot.cpp

@ -34,7 +34,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -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…
Cancel
Save