DataFlash: added LOG_REPLAY and LOG_DISARMED parameters

This commit is contained in:
Andrew Tridgell 2016-05-09 12:00:55 +10:00
parent 5398283c9b
commit 8ca6ed54c5
2 changed files with 20 additions and 0 deletions

View File

@ -18,6 +18,20 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
// @User: Standard
AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, 16),
// @Param: _DISARMED
// @DisplayName: Enable logging while disarmed
// @Description: If LOG_DISARMED is set to 1 then logging will be enabled while disarmed. This can make for very large logfiles but can help a lot when tracking down startup issues
// @Values:0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_DISARMED", 2, DataFlash_Class, _params.log_disarmed, 0),
// @Param: _REPLAY
// @DisplayName: Enable logging of information needed for Replay
// @Description: If LOG_REPLAY is set to 1 then the EKF2 state estimator will log detailed information needed for diagnosing problems with the Kalman filter. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost
// @Values:0:Disabled,1:EnabledIMU1,3:EnabledIMU1andIMU2
// @User: Standard
AP_GROUPINFO("_REPLAY", 3, DataFlash_Class, _params.log_replay, 0),
AP_GROUPEND
};

View File

@ -174,6 +174,10 @@ public:
// number of blocks that have been dropped
uint32_t num_dropped(void) const;
// accesss to public parameters
bool log_while_disarmed(void) const { return _params.log_disarmed != 0; }
uint8_t log_replay(void) const { return _params.log_replay; }
vehicle_startup_message_Log_Writer _vehicle_messages;
@ -182,6 +186,8 @@ public:
struct {
AP_Int8 backend_types;
AP_Int8 file_bufsize; // in kilobytes
AP_Int8 log_disarmed;
AP_Int8 log_replay;
} _params;
const struct LogStructure *structure(uint16_t num) const;