mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Arming: use ArmingMethod enumeration
This commit is contained in:
parent
6979f0d3a0
commit
e400a0e351
@ -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
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user