|
|
|
@ -42,6 +42,30 @@ public:
@@ -42,6 +42,30 @@ public:
|
|
|
|
|
AUXSWITCH = 2, |
|
|
|
|
MOTORTEST = 3, |
|
|
|
|
SCRIPTING = 4, |
|
|
|
|
TERMINATION = 5, // only disarm uses this...
|
|
|
|
|
CPUFAILSAFE = 6, // only disarm uses this...
|
|
|
|
|
BATTERYFAILSAFE = 7, // only disarm uses this...
|
|
|
|
|
SOLOPAUSEWHENLANDED = 8, // only disarm uses this...
|
|
|
|
|
AFS = 9, // only disarm uses this...
|
|
|
|
|
ADSBCOLLISIONACTION = 10, // only disarm uses this...
|
|
|
|
|
PARACHUTE_RELEASE = 11, // only disarm uses this...
|
|
|
|
|
CRASH = 12, // only disarm uses this...
|
|
|
|
|
LANDED = 13, // only disarm uses this...
|
|
|
|
|
MISSIONEXIT = 14, // only disarm uses this...
|
|
|
|
|
FENCEBREACH = 15, // only disarm uses this...
|
|
|
|
|
RADIOFAILSAFE = 16, // only disarm uses this...
|
|
|
|
|
DISARMDELAY = 17, // only disarm uses this...
|
|
|
|
|
GCSFAILSAFE = 18, // only disarm uses this...
|
|
|
|
|
TERRRAINFAILSAFE = 19, // only disarm uses this...
|
|
|
|
|
FAILSAFE_ACTION_TERMINATE = 20, // only disarm uses this...
|
|
|
|
|
TERRAINFAILSAFE = 21, // only disarm uses this...
|
|
|
|
|
MOTORDETECTDONE = 22, // only disarm uses this...
|
|
|
|
|
BADFLOWOFCONTROL = 23, // only disarm uses this...
|
|
|
|
|
EKFFAILSAFE = 24, // only disarm uses this...
|
|
|
|
|
GCS_FAILSAFE_SURFACEFAILED = 25, // only disarm uses this...
|
|
|
|
|
GCS_FAILSAFE_HOLDFAILED = 26, // only disarm uses this...
|
|
|
|
|
TAKEOFFTIMEOUT = 27, // only disarm uses this...
|
|
|
|
|
AUTOLANDED = 28, // only disarm uses this...
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
enum class Required { |
|
|
|
@ -55,7 +79,7 @@ public:
@@ -55,7 +79,7 @@ public:
|
|
|
|
|
// these functions should not be used by Copter which holds the armed state in the motors library
|
|
|
|
|
Required arming_required(); |
|
|
|
|
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true); |
|
|
|
|
virtual bool disarm(); |
|
|
|
|
virtual bool disarm(AP_Arming::Method method); |
|
|
|
|
bool is_armed(); |
|
|
|
|
|
|
|
|
|
// get bitmask of enabled checks
|
|
|
|
@ -148,7 +172,7 @@ protected:
@@ -148,7 +172,7 @@ protected:
|
|
|
|
|
void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4); |
|
|
|
|
|
|
|
|
|
void Log_Write_Arm(bool forced, AP_Arming::Method method); |
|
|
|
|
void Log_Write_Disarm(); |
|
|
|
|
void Log_Write_Disarm(AP_Arming::Method method); |
|
|
|
|
|
|
|
|
|
private: |
|
|
|
|
|
|
|
|
|