diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 276397a85f..bb6f8c81a1 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -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; } diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index f96a9d4916..b4fc3e93d3 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -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 log_disarmed; AP_Int8 log_replay; AP_Int8 mav_bufsize; // in kilobytes AP_Int16 file_timeout; // in seconds