mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: set force disarmed logging for all the nasty disarm reasons
This commit is contained in:
parent
38cdc00137
commit
1e5b9e487b
|
@ -1339,6 +1339,8 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
|||
|
||||
Log_Write_Disarm(method); // should be able to pass through force here?
|
||||
|
||||
check_forced_logging(method);
|
||||
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
|
||||
if ((board_cfg != nullptr) &&
|
||||
|
@ -1478,6 +1480,54 @@ void AP_Arming::Log_Write_Disarm(const AP_Arming::Method method)
|
|||
AP::logger().Write_Event(LogEvent::DISARMED);
|
||||
}
|
||||
|
||||
// check if we should keep logging after disarming
|
||||
void AP_Arming::check_forced_logging(const AP_Arming::Method method)
|
||||
{
|
||||
// keep logging if disarmed for a bad reason
|
||||
switch(method) {
|
||||
case Method::TERMINATION:
|
||||
case Method::CPUFAILSAFE:
|
||||
case Method::BATTERYFAILSAFE:
|
||||
case Method::AFS:
|
||||
case Method::ADSBCOLLISIONACTION:
|
||||
case Method::PARACHUTE_RELEASE:
|
||||
case Method::CRASH:
|
||||
case Method::FENCEBREACH:
|
||||
case Method::RADIOFAILSAFE:
|
||||
case Method::GCSFAILSAFE:
|
||||
case Method::TERRRAINFAILSAFE:
|
||||
case Method::FAILSAFE_ACTION_TERMINATE:
|
||||
case Method::TERRAINFAILSAFE:
|
||||
case Method::BADFLOWOFCONTROL:
|
||||
case Method::EKFFAILSAFE:
|
||||
case Method::GCS_FAILSAFE_SURFACEFAILED:
|
||||
case Method::GCS_FAILSAFE_HOLDFAILED:
|
||||
case Method::PILOT_INPUT_FAILSAFE:
|
||||
// keep logging for longger if disarmed for a bad reason
|
||||
AP::logger().set_long_log_persist(true);
|
||||
return;
|
||||
|
||||
case Method::RUDDER:
|
||||
case Method::MAVLINK:
|
||||
case Method::AUXSWITCH:
|
||||
case Method::MOTORTEST:
|
||||
case Method::SCRIPTING:
|
||||
case Method::SOLOPAUSEWHENLANDED:
|
||||
case Method::LANDED:
|
||||
case Method::MISSIONEXIT:
|
||||
case Method::DISARMDELAY:
|
||||
case Method::MOTORDETECTDONE:
|
||||
case Method::TAKEOFFTIMEOUT:
|
||||
case Method::AUTOLANDED:
|
||||
case Method::TOYMODELANDTHROTTLE:
|
||||
case Method::TOYMODELANDFORCE:
|
||||
case Method::LANDING:
|
||||
case Method::UNKNOWN:
|
||||
AP::logger().set_long_log_persist(false);
|
||||
return;
|
||||
};
|
||||
}
|
||||
|
||||
AP_Arming *AP_Arming::_singleton = nullptr;
|
||||
|
||||
/*
|
||||
|
|
|
@ -211,6 +211,9 @@ private:
|
|||
bool ins_accels_consistent(const AP_InertialSensor &ins);
|
||||
bool ins_gyros_consistent(const AP_InertialSensor &ins);
|
||||
|
||||
// check if we should keep logging after disarming
|
||||
void check_forced_logging(const AP_Arming::Method method);
|
||||
|
||||
enum MIS_ITEM_CHECK {
|
||||
MIS_ITEM_CHECK_LAND = (1 << 0),
|
||||
MIS_ITEM_CHECK_VTOL_LAND = (1 << 1),
|
||||
|
|
Loading…
Reference in New Issue