AP_Arming: use ArmingMethod enumeration

This commit is contained in:
Peter Barker 2018-06-25 12:05:56 +10:00 committed by Peter Barker
parent 6979f0d3a0
commit e400a0e351
2 changed files with 8 additions and 7 deletions

View File

@ -541,7 +541,7 @@ bool AP_Arming::board_voltage_checks(bool report)
bool AP_Arming::pre_arm_checks(bool report) bool AP_Arming::pre_arm_checks(bool report)
{ {
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter) #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 // if we are already armed or don't need any arming checks
// then skip the checks // then skip the checks
return true; return true;
@ -560,7 +560,7 @@ bool AP_Arming::pre_arm_checks(bool report)
& board_voltage_checks(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 // ensure the GPS drivers are ready on any final changes
if ((checks_to_perform & ARMING_CHECK_ALL) || 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 //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) #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// Copter should never use this function // Copter should never use this function

View File

@ -34,9 +34,10 @@ public:
}; };
enum ArmingMethod { enum ArmingMethod {
NONE = 0,
RUDDER, RUDDER,
MAVLINK MAVLINK,
AUXSWITCH,
MOTORTEST,
}; };
enum ArmingRequired { enum ArmingRequired {
@ -47,7 +48,7 @@ public:
// these functions should not be used by Copter which holds the armed state in the motors library // these functions should not be used by Copter which holds the armed state in the motors library
ArmingRequired arming_required(); 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 disarm();
bool is_armed(); bool is_armed();
@ -61,7 +62,7 @@ public:
// some arming checks have side-effects, or require some form of state // 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 // change to have occurred, and thus should not be done as pre-arm
// checks. Those go here: // checks. Those go here:
bool arm_checks(uint8_t method); bool arm_checks(ArmingMethod method);
// get expected magnetic field strength // get expected magnetic field strength
uint16_t compass_magfield_expected() const; uint16_t compass_magfield_expected() const;