Browse Source

AP_Arming: option to force arm, bypassing checks

mission-4.1.18
Peter Barker 8 years ago
parent
commit
d8128ba69a
  1. 4
      libraries/AP_Arming/AP_Arming.cpp
  2. 2
      libraries/AP_Arming/AP_Arming.h

4
libraries/AP_Arming/AP_Arming.cpp

@ -590,7 +590,7 @@ bool AP_Arming::arm_checks(uint8_t method) @@ -590,7 +590,7 @@ bool AP_Arming::arm_checks(uint8_t method)
}
//returns true if arming occurred successfully
bool AP_Arming::arm(uint8_t method)
bool AP_Arming::arm(uint8_t method, const bool do_arming_checks)
{
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// Copter should never use this function
@ -601,7 +601,7 @@ bool AP_Arming::arm(uint8_t method) @@ -601,7 +601,7 @@ bool AP_Arming::arm(uint8_t method)
}
//are arming checks disabled?
if (checks_to_perform == ARMING_CHECK_NONE) {
if (!do_arming_checks || checks_to_perform == ARMING_CHECK_NONE) {
armed = true;
arming_method = NONE;
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");

2
libraries/AP_Arming/AP_Arming.h

@ -40,7 +40,7 @@ public: @@ -40,7 +40,7 @@ public:
// these functions should not be used by Copter which holds the armed state in the motors library
ArmingRequired arming_required();
virtual bool arm(uint8_t method);
virtual bool arm(uint8_t method, bool do_arming_checks=true);
bool disarm();
bool is_armed();

Loading…
Cancel
Save