Browse Source

ArduSub: 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.
zr-v5.1
Peter Barker 4 years ago committed by Randy Mackay
parent
commit
f6f19eeeb2
  1. 4
      ArduSub/AP_Arming_Sub.cpp
  2. 2
      ArduSub/AP_Arming_Sub.h

4
ArduSub/AP_Arming_Sub.cpp

@ -152,14 +152,14 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks) @@ -152,14 +152,14 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
return true;
}
bool AP_Arming_Sub::disarm(const AP_Arming::Method method)
bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
// return immediately if we are already disarmed
if (!sub.motors.armed()) {
return false;
}
if (!AP_Arming::disarm(method)) {
if (!AP_Arming::disarm(method, do_disarm_checks)) {
return false;
}

2
ArduSub/AP_Arming_Sub.h

@ -15,7 +15,7 @@ public: @@ -15,7 +15,7 @@ public:
bool pre_arm_checks(bool display_failure) override;
bool has_disarm_function() const;
bool disarm(AP_Arming::Method method) override;
bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
protected:

Loading…
Cancel
Save