mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_Arming: use enum class for ArmingMethod and ArmingRequired
This commit is contained in:
parent
8d75e8c5bb
commit
0dacf78c12
@ -44,9 +44,9 @@
|
||||
#define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||
#define ARMING_RUDDER_DEFAULT ARMING_RUDDER_ARMONLY
|
||||
#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY
|
||||
#else
|
||||
#define ARMING_RUDDER_DEFAULT ARMING_RUDDER_ARMDISARM
|
||||
#define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -122,7 +122,7 @@ uint16_t AP_Arming::compass_magfield_expected() const
|
||||
|
||||
bool AP_Arming::is_armed()
|
||||
{
|
||||
return (ArmingRequired)require.get() == NO || armed;
|
||||
return (Required)require.get() == Required::NO || armed;
|
||||
}
|
||||
|
||||
uint16_t AP_Arming::get_enabled_checks()
|
||||
@ -723,7 +723,7 @@ bool AP_Arming::fence_checks(bool display_failure)
|
||||
bool AP_Arming::pre_arm_checks(bool report)
|
||||
{
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
if (armed || require == NO) {
|
||||
if (armed || require == (uint8_t)Required::NO) {
|
||||
// if we are already armed or don't need any arming checks
|
||||
// then skip the checks
|
||||
return true;
|
||||
@ -745,7 +745,7 @@ bool AP_Arming::pre_arm_checks(bool report)
|
||||
& can_checks(report);
|
||||
}
|
||||
|
||||
bool AP_Arming::arm_checks(ArmingMethod method)
|
||||
bool AP_Arming::arm_checks(AP_Arming::Method method)
|
||||
{
|
||||
// ensure the GPS drivers are ready on any final changes
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
@ -777,7 +777,7 @@ bool AP_Arming::arm_checks(ArmingMethod method)
|
||||
}
|
||||
|
||||
//returns true if arming occurred successfully
|
||||
bool AP_Arming::arm(AP_Arming::ArmingMethod method, const bool do_arming_checks)
|
||||
bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
|
||||
{
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
// Copter should never use this function
|
||||
@ -839,9 +839,9 @@ bool AP_Arming::disarm()
|
||||
#endif
|
||||
}
|
||||
|
||||
AP_Arming::ArmingRequired AP_Arming::arming_required()
|
||||
AP_Arming::Required AP_Arming::arming_required()
|
||||
{
|
||||
return (AP_Arming::ArmingRequired)require.get();
|
||||
return (AP_Arming::Required)require.get();
|
||||
}
|
||||
|
||||
// Copter and sub share the same RC input limits
|
||||
|
@ -33,22 +33,22 @@ public:
|
||||
ARMING_CHECK_MISSION = 0x4000,
|
||||
};
|
||||
|
||||
enum ArmingMethod {
|
||||
enum class Method {
|
||||
RUDDER,
|
||||
MAVLINK,
|
||||
AUXSWITCH,
|
||||
MOTORTEST,
|
||||
};
|
||||
|
||||
enum ArmingRequired {
|
||||
enum class Required {
|
||||
NO = 0,
|
||||
YES_MIN_PWM = 1,
|
||||
YES_ZERO_PWM = 2
|
||||
};
|
||||
|
||||
// these functions should not be used by Copter which holds the armed state in the motors library
|
||||
ArmingRequired arming_required();
|
||||
virtual bool arm(ArmingMethod method, bool do_arming_checks=true);
|
||||
Required arming_required();
|
||||
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
|
||||
bool disarm();
|
||||
bool is_armed();
|
||||
|
||||
@ -61,18 +61,19 @@ 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(ArmingMethod method);
|
||||
bool arm_checks(AP_Arming::Method method);
|
||||
|
||||
// get expected magnetic field strength
|
||||
uint16_t compass_magfield_expected() const;
|
||||
|
||||
// rudder arming support
|
||||
enum ArmingRudder {
|
||||
ARMING_RUDDER_DISABLED = 0,
|
||||
ARMING_RUDDER_ARMONLY = 1,
|
||||
ARMING_RUDDER_ARMDISARM = 2
|
||||
enum class RudderArming {
|
||||
IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h
|
||||
ARMONLY = 1,
|
||||
ARMDISARM = 2
|
||||
};
|
||||
ArmingRudder get_rudder_arming_type() const { return (ArmingRudder)_rudder_arming.get(); }
|
||||
|
||||
RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user