mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: use AP_Enum for log_disarmed
This commit is contained in:
parent
4899ec9457
commit
3b4f5d77af
|
@ -187,7 +187,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
|
|||
|
||||
if (hal.util->was_watchdog_armed()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Forcing logging for watchdog reset");
|
||||
_params.log_disarmed.set(1);
|
||||
_params.log_disarmed.set(LogDisarmed::LOG_WHILE_DISARMED);
|
||||
}
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
validate_structures(structures, num_types);
|
||||
|
@ -1468,7 +1468,8 @@ bool AP_Logger::log_while_disarmed(void) const
|
|||
if (_force_log_disarmed) {
|
||||
return true;
|
||||
}
|
||||
if (_params.log_disarmed == 1 || (_params.log_disarmed == 2 && !hal.gpio->usb_connected())) {
|
||||
if (_params.log_disarmed == LogDisarmed::LOG_WHILE_DISARMED ||
|
||||
(_params.log_disarmed == LogDisarmed::LOG_WHILE_DISARMED_NOT_USB && !hal.gpio->usb_connected())) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -315,13 +315,19 @@ public:
|
|||
|
||||
vehicle_startup_message_Writer _vehicle_messages;
|
||||
|
||||
enum class LogDisarmed : uint8_t {
|
||||
NONE = 0,
|
||||
LOG_WHILE_DISARMED = 1,
|
||||
LOG_WHILE_DISARMED_NOT_USB = 2,
|
||||
};
|
||||
|
||||
// parameter support
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
struct {
|
||||
AP_Int8 backend_types;
|
||||
AP_Int16 file_bufsize; // in kilobytes
|
||||
AP_Int8 file_disarm_rot;
|
||||
AP_Int8 log_disarmed;
|
||||
AP_Enum<LogDisarmed> log_disarmed;
|
||||
AP_Int8 log_replay;
|
||||
AP_Int8 mav_bufsize; // in kilobytes
|
||||
AP_Int16 file_timeout; // in seconds
|
||||
|
|
Loading…
Reference in New Issue