Browse Source

Copter: remove redundant compass arming checks

These are already part of prearm checks in the parent class, which must also pass for us to arm
master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
6bac6cd725
  1. 13
      ArduCopter/AP_Arming.cpp

13
ArduCopter/AP_Arming.cpp

@ -453,8 +453,8 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method @@ -453,8 +453,8 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
return false;
}
const Compass &_compass = AP::compass();
#ifndef ALLOW_ARM_NO_COMPASS
const Compass &_compass = AP::compass();
// check compass health
if (!_compass.healthy()) {
check_failed(ARMING_CHECK_NONE, display_failure, "Compass not healthy");
@ -462,17 +462,6 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method @@ -462,17 +462,6 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method
}
#endif
if (_compass.is_calibrating()) {
check_failed(ARMING_CHECK_NONE, display_failure, "Compass calibration running");
return false;
}
//check if compass has calibrated and requires reboot
if (_compass.compass_cal_requires_reboot()) {
check_failed(ARMING_CHECK_NONE, display_failure, "Compass calibrated requires reboot");
return false;
}
control_mode_t control_mode = copter.control_mode;
// always check if the current mode allows arming

Loading…
Cancel
Save