mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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.
This commit is contained in:
parent
b698546b70
commit
f6f19eeeb2
@ -152,14 +152,14 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
|
|||||||
return true;
|
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
|
// return immediately if we are already disarmed
|
||||||
if (!sub.motors.armed()) {
|
if (!sub.motors.armed()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!AP_Arming::disarm(method)) {
|
if (!AP_Arming::disarm(method, do_disarm_checks)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -15,7 +15,7 @@ public:
|
|||||||
bool pre_arm_checks(bool display_failure) override;
|
bool pre_arm_checks(bool display_failure) override;
|
||||||
bool has_disarm_function() const;
|
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;
|
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
Loading…
Reference in New Issue
Block a user