mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
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.
This commit is contained in:
parent
c9b906de17
commit
b229c552e6
@ -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;
|
||||
|
@ -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…
Reference in New Issue
Block a user