AP_Arming: option to force arm, bypassing checks

This commit is contained in:
Peter Barker 2016-09-27 18:08:41 +10:00
parent fd9ce90b8e
commit d8128ba69a
2 changed files with 3 additions and 3 deletions

View File

@ -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)
}
//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");

View File

@ -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();