Skip to content

Commit

Permalink
AP_Logger: make block logger conform to mavlink expectations of numbe…
Browse files Browse the repository at this point in the history
…ring

add support for log time to block logger
refactor rotation into backed. Don't start logs when erasing
correct log start logic
separate read and write points so that requesting log information does not corrupt the current log
when starting a new log stop logging first
clear the write buffer when starting a new log
insert utc time when requesting info for the current log
stop logging and request formats again when starting a new log
cope with erase happening while we are logging
keep pushing out startup messages even when format messages are done
don't log to the gcs in the io thread
don't start new logs in the io thread
don't validate logs while erasing
flush logs when stopping logging
account for page header when calculating logs sizes
don't return data when asked for more data than in the log
optimize locking and use separate semaphore to mediate ring buffer access
stop logging when the chip is full and send a notification
calculate logs sizes correctly even when they wrap
read log data correctly even when it wraps
add stats support to block logger
reset dropped when starting a new log
fail logging when the chip is full
refactor critical bufferspace checks
increase messagewriter budget to 250us and to 300us for FMT
  • Loading branch information
andyp1per authored and peterbarker committed Sep 5, 2020
1 parent 11417ac commit ccb583d
Show file tree
Hide file tree
Showing 14 changed files with 675 additions and 416 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_Logger/AP_Logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
AP_GROUPINFO("_BACKEND_TYPE", 0, AP_Logger, _params.backend_types, uint8_t(HAL_LOGGING_BACKENDS_DEFAULT)),

// @Param: _FILE_BUFSIZE
// @DisplayName: Maximum AP_Logger File Backend buffer size (in kilobytes)
// @Description: The AP_Logger_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
// @DisplayName: Maximum AP_Logger File and Block Backend buffer size (in kilobytes)
// @Description: The File and Block backends use a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
// @User: Standard
AP_GROUPINFO("_FILE_BUFSIZE", 1, AP_Logger, _params.file_bufsize, HAL_LOGGING_FILE_BUFSIZE),

Expand All @@ -75,7 +75,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {

// @Param: _FILE_DSRMROT
// @DisplayName: Stop logging to current file on disarm
// @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened.
// @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened. Applies to the File and Block logging backends.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_FILE_DSRMROT", 4, AP_Logger, _params.file_disarm_rot, 0),
Expand Down
120 changes: 120 additions & 0 deletions libraries/AP_Logger/AP_Logger_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,20 @@ AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_mes
void AP_Logger_Backend::periodic_10Hz(const uint32_t now)
{
}

void AP_Logger_Backend::periodic_1Hz()
{
if (_rotate_pending && !logging_enabled()) {
_rotate_pending = false;
// handle log rotation once we stop logging
stop_logging();
}
df_stats_log();
}

void AP_Logger_Backend::periodic_fullrate()
{
push_log_blocks();
}

void AP_Logger_Backend::periodic_tasks()
Expand All @@ -74,8 +83,10 @@ void AP_Logger_Backend::periodic_tasks()

void AP_Logger_Backend::start_new_log_reset_variables()
{
_dropped = 0;
_startup_messagewriter->reset();
_front.backend_starting_new_log(this);
_log_file_size_bytes = 0;
}

// this method can be overridden to do extra things with your buffer.
Expand Down Expand Up @@ -410,6 +421,18 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
return true;
}

void AP_Logger_Backend::PrepForArming()
{
if (_rotate_pending) {
_rotate_pending = false;
stop_logging();
}
if (logging_started()) {
return;
}
start_new_log();
}

bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
{
char msg[65] {}; // sizeof(log_Message.msg) + null-termination
Expand Down Expand Up @@ -445,3 +468,100 @@ bool AP_Logger_Backend::Write_Rally()
// kick off asynchronous write:
return _startup_messagewriter->writeallrallypoints();
}

/*
convert a list entry number back into a log number (which can then
be converted into a filename). A "list entry number" is a sequence
where the oldest log has a number of 1, the second-from-oldest 2,
and so on. Thus the highest list entry number is equal to the
number of logs.
*/
uint16_t AP_Logger_Backend::log_num_from_list_entry(const uint16_t list_entry)
{
uint16_t oldest_log = find_oldest_log();
if (oldest_log == 0) {
return 0;
}

uint32_t log_num = oldest_log + list_entry - 1;
if (log_num > MAX_LOG_FILES) {
log_num -= MAX_LOG_FILES;
}
return (uint16_t)log_num;
}

// find_oldest_log - find oldest log
// returns 0 if no log was found
uint16_t AP_Logger_Backend::find_oldest_log()
{
if (_cached_oldest_log != 0) {
return _cached_oldest_log;
}

uint16_t last_log_num = find_last_log();
if (last_log_num == 0) {
return 0;
}

_cached_oldest_log = last_log_num - get_num_logs() + 1;

return _cached_oldest_log;
}

void AP_Logger_Backend::vehicle_was_disarmed()
{
if (_front._params.file_disarm_rot) {
// rotate our log. Closing the current one and letting the
// logging restart naturally based on log_disarmed should do
// the trick:
_rotate_pending = true;
}
}

// this sensor is enabled if we should be logging at the moment
bool AP_Logger_Backend::logging_enabled() const
{
if (hal.util->get_soft_armed() ||
_front.log_while_disarmed()) {
return true;
}
return false;
}

void AP_Logger_Backend::Write_AP_Logger_Stats_File(const struct df_stats &_stats)
{
struct log_DSF pkt = {
LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS),
time_us : AP_HAL::micros64(),
dropped : _dropped,
blocks : _stats.blocks,
bytes : _stats.bytes,
buf_space_min : _stats.buf_space_min,
buf_space_max : _stats.buf_space_max,
buf_space_avg : (_stats.blocks) ? (_stats.buf_space_sigma / _stats.blocks) : 0,
};
WriteBlock(&pkt, sizeof(pkt));
}

void AP_Logger_Backend::df_stats_gather(const uint16_t bytes_written, uint32_t space_remaining) {
if (space_remaining < stats.buf_space_min) {
stats.buf_space_min = space_remaining;
}
if (space_remaining > stats.buf_space_max) {
stats.buf_space_max = space_remaining;
}
stats.buf_space_sigma += space_remaining;
stats.bytes += bytes_written;
_log_file_size_bytes += bytes_written;
stats.blocks++;
}

void AP_Logger_Backend::df_stats_clear() {
memset(&stats, '\0', sizeof(stats));
stats.buf_space_min = -1;
}

void AP_Logger_Backend::df_stats_log() {
Write_AP_Logger_Stats_File(stats);
df_stats_clear();
}
65 changes: 54 additions & 11 deletions libraries/AP_Logger/AP_Logger_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

class LoggerMessageWriter_DFLogStart;

#define MAX_LOG_FILES 500

class AP_Logger_Backend
{

Expand All @@ -20,7 +22,6 @@ class AP_Logger_Backend
// erase handling
virtual void EraseAll() = 0;

virtual bool NeedPrep() = 0;
virtual void Prep() = 0;

/* Write a block of data at current offset */
Expand All @@ -34,22 +35,23 @@ class AP_Logger_Backend

bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);

// high level interface
// high level interface, indexed by the position in the list of logs
virtual uint16_t find_last_log() = 0;
virtual void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) = 0;
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
virtual void get_log_boundaries(uint16_t list_entry, uint32_t & start_page, uint32_t & end_page) = 0;
virtual void get_log_info(uint16_t list_entry, uint32_t &size, uint32_t &time_utc) = 0;
virtual int16_t get_log_data(uint16_t list_entry, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
virtual uint16_t get_num_logs() = 0;
virtual uint16_t find_oldest_log();

virtual bool logging_started(void) const = 0;

virtual void Init() { }
virtual void Init() = 0;

virtual uint32_t bufferspace_available() = 0;

virtual void PrepForArming() { }
virtual void PrepForArming();

virtual void start_new_log() { };
virtual void start_new_log() { }

/* stop logging - close output files etc etc.
*
Expand Down Expand Up @@ -115,16 +117,15 @@ class AP_Logger_Backend
bool Write(uint8_t msg_type, va_list arg_list, bool is_critical=false);

// these methods are used when reporting system status over mavlink
virtual bool logging_enabled() const = 0;
virtual bool logging_enabled() const;
virtual bool logging_failed() const = 0;

virtual void vehicle_was_disarmed() { };
virtual void vehicle_was_disarmed();

bool Write_Unit(const struct UnitStructure *s);
bool Write_Multiplier(const struct MultiplierStructure *s);
bool Write_Format_Units(const struct LogStructure *structure);


protected:

AP_Logger &_front;
Expand All @@ -147,20 +148,62 @@ class AP_Logger_Backend
LoggerMessageWriter_DFLogStart *_startup_messagewriter;
bool _writing_startup_messages;

uint16_t _cached_oldest_log;

uint32_t _dropped;
uint32_t _log_file_size_bytes;
// should we rotate when we next stop logging
bool _rotate_pending;

// must be called when a new log is being started:
virtual void start_new_log_reset_variables();
// convert between log numbering in storage and normalized numbering
uint16_t log_num_from_list_entry(const uint16_t list_entry);

uint32_t critical_message_reserved_space(uint32_t bufsize) const {
// possibly make this a proportional to buffer size?
uint32_t ret = 1024;
if (ret > bufsize) {
// in this case you will only get critical messages
ret = bufsize;
}
return ret;
};
uint32_t non_messagewriter_message_reserved_space(uint32_t bufsize) const {
// possibly make this a proportional to buffer size?
uint32_t ret = 1024;
if (ret >= bufsize) {
// need to allow messages out from the messagewriters. In
// this case while you have a messagewriter you won't get
// any other messages. This should be a corner case!
ret = 0;
}
return ret;
};

virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;

bool _initialised;

void df_stats_gather(uint16_t bytes_written, uint32_t space_remaining);
void df_stats_log();
void df_stats_clear();

private:
// statistics support
struct df_stats {
uint16_t blocks;
uint32_t bytes;
uint32_t buf_space_min;
uint32_t buf_space_max;
uint32_t buf_space_sigma;
};
struct df_stats stats;

uint32_t _last_periodic_1Hz;
uint32_t _last_periodic_10Hz;
bool have_logged_armed;

void Write_AP_Logger_Stats_File(const struct df_stats &_stats);
void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size);
};
Loading

0 comments on commit ccb583d

Please sign in to comment.