From e400a0e351f946248bb2d3bb8704289377cca590 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Jun 2018 12:05:56 +1000 Subject: [PATCH] AP_Arming: use ArmingMethod enumeration --- libraries/AP_Arming/AP_Arming.cpp | 6 +++--- libraries/AP_Arming/AP_Arming.h | 9 +++++---- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 339f6bf6e5..110cbad667 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -541,7 +541,7 @@ bool AP_Arming::board_voltage_checks(bool report) bool AP_Arming::pre_arm_checks(bool report) { #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter) - if (armed || require == NONE) { + if (armed || require == NO) { // if we are already armed or don't need any arming checks // then skip the checks return true; @@ -560,7 +560,7 @@ bool AP_Arming::pre_arm_checks(bool report) & board_voltage_checks(report); } -bool AP_Arming::arm_checks(uint8_t method) +bool AP_Arming::arm_checks(ArmingMethod method) { // ensure the GPS drivers are ready on any final changes if ((checks_to_perform & ARMING_CHECK_ALL) || @@ -585,7 +585,7 @@ bool AP_Arming::arm_checks(uint8_t method) } //returns true if arming occurred successfully -bool AP_Arming::arm(uint8_t method, const bool do_arming_checks) +bool AP_Arming::arm(AP_Arming::ArmingMethod method, const bool do_arming_checks) { #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) // Copter should never use this function diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index c60f0e75dc..07c30ad681 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -34,9 +34,10 @@ public: }; enum ArmingMethod { - NONE = 0, RUDDER, - MAVLINK + MAVLINK, + AUXSWITCH, + MOTORTEST, }; enum ArmingRequired { @@ -47,7 +48,7 @@ public: // these functions should not be used by Copter which holds the armed state in the motors library ArmingRequired arming_required(); - virtual bool arm(uint8_t method, bool do_arming_checks=true); + virtual bool arm(ArmingMethod method, bool do_arming_checks=true); bool disarm(); bool is_armed(); @@ -61,7 +62,7 @@ public: // some arming checks have side-effects, or require some form of state // change to have occurred, and thus should not be done as pre-arm // checks. Those go here: - bool arm_checks(uint8_t method); + bool arm_checks(ArmingMethod method); // get expected magnetic field strength uint16_t compass_magfield_expected() const;