Browse Source

Copter: move checking of fence up

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
cc8912255e
  1. 17
      ArduCopter/AP_Arming.cpp
  2. 1
      ArduCopter/AP_Arming.h

17
ArduCopter/AP_Arming.cpp

@ -100,23 +100,6 @@ bool AP_Arming_Copter::compass_checks(bool display_failure) @@ -100,23 +100,6 @@ bool AP_Arming_Copter::compass_checks(bool display_failure)
return ret;
}
bool AP_Arming_Copter::fence_checks(bool display_failure)
{
#if AC_FENCE == ENABLED
// check fence is initialised
const char *fail_msg = nullptr;
if (!copter.fence.pre_arm_check(fail_msg)) {
if (fail_msg == nullptr) {
check_failed(ARMING_CHECK_NONE, display_failure, "Check fence");
} else {
check_failed(ARMING_CHECK_NONE, display_failure, "%s", fail_msg);
}
return false;
}
#endif
return true;
}
bool AP_Arming_Copter::ins_checks(bool display_failure)
{
bool ret = AP_Arming::ins_checks(display_failure);

1
ArduCopter/AP_Arming.h

@ -40,7 +40,6 @@ protected: @@ -40,7 +40,6 @@ protected:
bool board_voltage_checks(bool display_failure) override;
// NOTE! the following check functions *DO NOT* call into AP_Arming!
bool fence_checks(bool display_failure);
bool parameter_checks(bool display_failure);
bool motor_checks(bool display_failure);
bool pilot_throttle_checks(bool display_failure);

Loading…
Cancel
Save