mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Arming: log disarm method
This commit is contained in:
parent
05a0fe615b
commit
7b9cdd6d06
@ -943,14 +943,14 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
|
|||||||
}
|
}
|
||||||
|
|
||||||
//returns true if disarming occurred successfully
|
//returns true if disarming occurred successfully
|
||||||
bool AP_Arming::disarm()
|
bool AP_Arming::disarm(const AP_Arming::Method method)
|
||||||
{
|
{
|
||||||
if (!armed) { // already disarmed
|
if (!armed) { // already disarmed
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
armed = false;
|
armed = false;
|
||||||
|
|
||||||
Log_Write_Disarm(); // should be able to pass through method and/or force here?
|
Log_Write_Disarm(method); // should be able to pass through force here?
|
||||||
|
|
||||||
#if HAL_HAVE_SAFETY_SWITCH
|
#if HAL_HAVE_SAFETY_SWITCH
|
||||||
AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
|
AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
|
||||||
@ -1035,7 +1035,7 @@ void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method)
|
|||||||
AP::logger().Write_Event(LogEvent::ARMED);
|
AP::logger().Write_Event(LogEvent::ARMED);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Arming::Log_Write_Disarm()
|
void AP_Arming::Log_Write_Disarm(const AP_Arming::Method method)
|
||||||
{
|
{
|
||||||
const struct log_Arm_Disarm pkt {
|
const struct log_Arm_Disarm pkt {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
|
||||||
@ -1043,7 +1043,7 @@ void AP_Arming::Log_Write_Disarm()
|
|||||||
arm_state : is_armed(),
|
arm_state : is_armed(),
|
||||||
arm_checks : 0,
|
arm_checks : 0,
|
||||||
forced : 0,
|
forced : 0,
|
||||||
method : 0
|
method : (uint8_t)method
|
||||||
};
|
};
|
||||||
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
|
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||||
AP::logger().Write_Event(LogEvent::DISARMED);
|
AP::logger().Write_Event(LogEvent::DISARMED);
|
||||||
|
@ -42,6 +42,30 @@ public:
|
|||||||
AUXSWITCH = 2,
|
AUXSWITCH = 2,
|
||||||
MOTORTEST = 3,
|
MOTORTEST = 3,
|
||||||
SCRIPTING = 4,
|
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 {
|
enum class Required {
|
||||||
@ -55,7 +79,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
|
||||||
Required arming_required();
|
Required arming_required();
|
||||||
virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
|
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();
|
bool is_armed();
|
||||||
|
|
||||||
// get bitmask of enabled checks
|
// get bitmask of enabled checks
|
||||||
@ -148,7 +172,7 @@ protected:
|
|||||||
void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4);
|
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_Arm(bool forced, AP_Arming::Method method);
|
||||||
void Log_Write_Disarm();
|
void Log_Write_Disarm(AP_Arming::Method method);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user