diff --git a/APMrover2/AP_Arming.cpp b/APMrover2/AP_Arming.cpp index a0ee05fe46..2048dc5622 100644 --- a/APMrover2/AP_Arming.cpp +++ b/APMrover2/AP_Arming.cpp @@ -81,6 +81,10 @@ bool AP_Arming_Rover::gps_checks(bool display_failure) bool AP_Arming_Rover::pre_arm_checks(bool report) { + //are arming checks disabled? + if (checks_to_perform == ARMING_CHECK_NONE) { + return true; + } if (SRV_Channels::get_emergency_stop()) { check_failed(ARMING_CHECK_NONE, report, "Motors Emergency Stopped"); return false; @@ -92,6 +96,15 @@ bool AP_Arming_Rover::pre_arm_checks(bool report) & proximity_check(report)); } +bool AP_Arming_Rover::arm_checks(AP_Arming::Method method) +{ + //are arming checks disabled? + if (checks_to_perform == ARMING_CHECK_NONE) { + return true; + } + return AP_Arming::arm_checks(method); +} + // check nothing is too close to vehicle bool AP_Arming_Rover::proximity_check(bool report) { diff --git a/APMrover2/AP_Arming.h b/APMrover2/AP_Arming.h index b7c48d817d..e52349cb9b 100644 --- a/APMrover2/AP_Arming.h +++ b/APMrover2/AP_Arming.h @@ -17,6 +17,7 @@ public: AP_Arming_Rover &operator=(const AP_Arming_Rover&) = delete; bool pre_arm_checks(bool report) override; + bool arm_checks(AP_Arming::Method method) override; bool pre_arm_rc_checks(const bool display_failure); bool gps_checks(bool display_failure) override;