Browse Source

AP_Arming: add do_disarm_checks boolean to disarm call

this creates symmetry between arming and disarming, at least as far as
the top-level arm() and disarm() calls are concerned.
c415-sdk
Peter Barker 4 years ago committed by Randy Mackay
parent
commit
b229c552e6
  1. 2
      libraries/AP_Arming/AP_Arming.cpp
  2. 2
      libraries/AP_Arming/AP_Arming.h

2
libraries/AP_Arming/AP_Arming.cpp

@ -1204,7 +1204,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) @@ -1204,7 +1204,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
}
//returns true if disarming occurred successfully
bool AP_Arming::disarm(const AP_Arming::Method method)
bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
if (!armed) { // already disarmed
return false;

2
libraries/AP_Arming/AP_Arming.h

@ -86,7 +86,7 @@ public: @@ -86,7 +86,7 @@ public:
// these functions should not be used by Copter which holds the armed state in the motors library
Required arming_required();
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
virtual bool disarm(AP_Arming::Method method);
virtual bool disarm(AP_Arming::Method method, bool do_disarm_checks=true);
bool is_armed();
// get bitmask of enabled checks

Loading…
Cancel
Save