diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index ecfe82cea0..969efd62bf 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -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) { diff --git a/Rover/AP_Arming.h b/Rover/AP_Arming.h index 72d546d80c..e1279d767e 100644 --- a/Rover/AP_Arming.h +++ b/Rover/AP_Arming.h @@ -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();