AP_Logger: make log file erase async

this prevents clagging up the main loop on a big erase. With an erase
of large enough files we could trigger a disarmed watchdog.
This commit is contained in:
Andrew Tridgell 2021-03-29 12:05:57 +11:00
parent 721850d00a
commit c886fd7025
2 changed files with 62 additions and 21 deletions

View File

@ -124,6 +124,15 @@ void AP_Logger_File::periodic_1Hz()
{
AP_Logger_Backend::periodic_1Hz();
if (_initialised &&
_write_fd == -1 && _read_fd == -1 &&
erase.log_num == 0 &&
erase.was_logging) {
// restart logging after an erase if needed
erase.was_logging = false;
start_new_log();
}
if (_initialised &&
_write_fd == -1 && _read_fd == -1 &&
logging_enabled() &&
@ -403,29 +412,10 @@ void AP_Logger_File::EraseAll()
return;
}
const bool was_logging = (_write_fd != -1);
erase.was_logging = (_write_fd != -1);
stop_logging();
for (uint16_t log_num=1; log_num<=MAX_LOG_FILES; log_num++) {
char *fname = _log_file_name(log_num);
if (fname == nullptr) {
break;
}
EXPECT_DELAY_MS(3000);
AP::FS().unlink(fname);
free(fname);
}
char *fname = _lastlog_file_name();
if (fname != nullptr) {
AP::FS().unlink(fname);
free(fname);
}
_cached_oldest_log = 0;
if (was_logging) {
start_new_log();
}
erase.log_num = 1;
}
bool AP_Logger_File::WritesOK() const
@ -724,6 +714,13 @@ void AP_Logger_File::start_new_log(void)
return;
}
if (erase.log_num != 0) {
// don't start a new log while erasing, but record that we
// want to start logging when erase finished
erase.was_logging = true;
return;
}
const bool open_error_ms_was_zero = (_open_error_ms == 0);
// set _open_error here to avoid infinite recursion. Simply
@ -858,6 +855,13 @@ void AP_Logger_File::io_timer(void)
{
uint32_t tnow = AP_HAL::millis();
_io_timer_heartbeat = tnow;
if (erase.log_num != 0) {
// continue erase
erase_next();
return;
}
if (_write_fd == -1 || !_initialised || recent_open_error()) {
return;
}
@ -999,5 +1003,35 @@ bool AP_Logger_File::logging_failed() const
return false;
}
/*
erase another file in async erase operation
*/
void AP_Logger_File::erase_next(void)
{
char *fname = _log_file_name(erase.log_num);
if (fname == nullptr) {
erase.log_num = 0;
return;
}
AP::FS().unlink(fname);
free(fname);
erase.log_num++;
if (erase.log_num <= MAX_LOG_FILES) {
return;
}
fname = _lastlog_file_name();
if (fname != nullptr) {
AP::FS().unlink(fname);
free(fname);
}
_cached_oldest_log = 0;
erase.log_num = 0;
}
#endif // HAL_LOGGING_FILESYSTEM_ENABLED

View File

@ -126,6 +126,13 @@ private:
// bad fd
HAL_Semaphore write_fd_semaphore;
// async erase state
struct {
bool was_logging;
uint16_t log_num;
} erase;
void erase_next(void);
const char *last_io_operation = "";
};