AP_Logger: stop logs safely in the block logger and asynchronously where possible

This commit is contained in:
Andy Piper 2020-09-10 20:57:40 +01:00 committed by Peter Barker
parent 46d4d9a97e
commit d036b57de3
4 changed files with 29 additions and 7 deletions

View File

@ -57,7 +57,7 @@ void AP_Logger_Backend::periodic_1Hz()
if (_rotate_pending && !logging_enabled()) {
_rotate_pending = false;
// handle log rotation once we stop logging
stop_logging();
stop_logging_async();
}
df_stats_log();
}

View File

@ -60,6 +60,8 @@ public:
* packet from a client.
*/
virtual void stop_logging(void) = 0;
// asynchronously stop logging, status can be determined through logging_started()
virtual void stop_logging_async(void) { stop_logging(); }
void Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
void Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt);

View File

@ -526,20 +526,23 @@ uint16_t AP_Logger_Block::get_num_logs(void)
return (last - first + 1);
}
// stop logging and flush any remaining data
// stop logging immediately
void AP_Logger_Block::stop_logging(void)
{
WITH_SEMAPHORE(sem);
log_write_started = false;
// complete writing any previous log
while (writebuf.available()) {
write_log_page();
}
// nuke writing any previous log
writebuf.clear();
}
// stop logging and flush any remaining data
void AP_Logger_Block::stop_logging_async(void)
{
stop_log_pending = true;
}
// This function starts a new log file in the AP_Logger
// no actual data should be written to the storage here
// that should all be handled by the IO thread
@ -887,12 +890,26 @@ void AP_Logger_Block::io_timer(void)
return;
}
// we have been asked to stop logging, flush everything
if (stop_log_pending) {
WITH_SEMAPHORE(sem);
log_write_started = false;
// complete writing any previous log
while (writebuf.available()) {
write_log_page();
}
writebuf.clear();
stop_log_pending = false;
// write at most one page
if (writebuf.available() >= df_PageSize - sizeof(struct PageHeader)) {
} else if (writebuf.available() >= df_PageSize - sizeof(struct PageHeader)) {
WITH_SEMAPHORE(sem);
write_log_page();
}
}
// write out a page of log data

View File

@ -28,6 +28,7 @@ public:
void start_new_log(void) override;
uint32_t bufferspace_available() override;
void stop_logging(void) override;
void stop_logging_async(void) override;
bool logging_failed() const override;
bool logging_started(void) const override { return log_write_started; }
@ -112,6 +113,8 @@ private:
volatile bool erase_started;
// were we logging before the erase started?
volatile bool new_log_pending;
// have we been asked to stop logging safely?
volatile bool stop_log_pending;
// latch to make sure we only write out the full message once
volatile bool chip_full;
// io thread health