Rover: 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 f6f19eeeb2
commit 5001978704
2 changed files with 3 additions and 3 deletions

View File

@ -134,9 +134,9 @@ bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)
/*
disarm motors
*/
bool AP_Arming_Rover::disarm(const AP_Arming::Method method)
bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
if (!AP_Arming::disarm(method)) {
if (!AP_Arming::disarm(method, do_disarm_checks)) {
return false;
}
if (rover.control_mode != &rover.mode_auto) {

View File

@ -21,7 +21,7 @@ public:
bool rc_calibration_checks(const bool display_failure) override;
bool gps_checks(bool display_failure) override;
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();