ArduPlane: 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:
Peter Barker 2021-01-06 11:15:48 +11:00 committed by Randy Mackay
parent 65adf5b4a9
commit b698546b70
2 changed files with 5 additions and 4 deletions

View File

@ -230,9 +230,10 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
/*
disarm motors
*/
bool AP_Arming_Plane::disarm(const AP_Arming::Method method)
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
if (method == AP_Arming::Method::RUDDER) {
if (do_disarm_checks &&
method == AP_Arming::Method::RUDDER) {
// don't allow rudder-disarming in flight:
if (plane.is_flying()) {
// obviously this could happen in-flight so we can't warn about it
@ -245,7 +246,7 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method)
}
}
if (!AP_Arming::disarm(method)) {
if (!AP_Arming::disarm(method, do_disarm_checks)) {
return false;
}
if (plane.control_mode != &plane.mode_auto) {

View File

@ -24,7 +24,7 @@ public:
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
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;
void update_soft_armed();