AP_Logger: prevent log erase from triggering watchdog

# Conflicts:
#	libraries/DataFlash/DataFlash_File.cpp
This commit is contained in:
Andrew Tridgell 2019-04-20 14:02:14 +10:00
parent b6285547c3
commit 6252f97df4
1 changed files with 21 additions and 1 deletions

View File

@ -128,11 +128,13 @@ void DataFlash_File::Init()
_log_directory = custom_dir;
}
hal.scheduler->expect_delay_ms(3000);
ret = stat(_log_directory, &st);
if (ret == -1) {
ret = mkdir(_log_directory, 0777);
}
if (ret == -1) {
hal.scheduler->expect_delay_ms(0);
if (ret == -1 && errno != EEXIST) {
printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno));
}
@ -163,11 +165,14 @@ void DataFlash_File::Init()
bool DataFlash_File::file_exists(const char *filename) const
{
struct stat st;
hal.scheduler->expect_delay_ms(3000);
if (stat(filename, &st) == -1) {
// hopefully errno==ENOENT. If some error occurs it is
// probably better to assume this file exists.
hal.scheduler->expect_delay_ms(0);
return false;
}
hal.scheduler->expect_delay_ms(0);
return true;
}
@ -295,14 +300,18 @@ uint16_t DataFlash_File::find_oldest_log()
// We could count up to find_last_log(), but if people start
// relying on the min_avail_space_percent feature we could end up
// doing a *lot* of asprintf()s and stat()s
hal.scheduler->expect_delay_ms(3000);
DIR *d = opendir(_log_directory);
hal.scheduler->expect_delay_ms(0);
if (d == nullptr) {
internal_error();
return 0;
}
// we only remove files which look like xxx.BIN
hal.scheduler->expect_delay_ms(3000);
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
hal.scheduler->expect_delay_ms(3000);
uint8_t length = strlen(de->d_name);
if (length < 5) {
// not long enough for \d+[.]BIN
@ -337,6 +346,7 @@ uint16_t DataFlash_File::find_oldest_log()
}
}
closedir(d);
hal.scheduler->expect_delay_ms(0);
_cached_oldest_log = current_oldest_log;
return current_oldest_log;
@ -381,6 +391,7 @@ void DataFlash_File::Prep_MinSpace()
if (file_exists(filename_to_remove)) {
hal.console->printf("Removing (%s) for minimum-space requirements (%.2f%% < %.0f%%)\n",
filename_to_remove, (double)avail, (double)min_avail_space_percent);
hal.scheduler->expect_delay_ms(2000);
if (unlink(filename_to_remove) == -1) {
hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno));
free(filename_to_remove);
@ -395,6 +406,7 @@ void DataFlash_File::Prep_MinSpace()
} else {
free(filename_to_remove);
}
hal.scheduler->expect_delay_ms(0);
}
log_to_remove++;
if (log_to_remove > MAX_LOG_FILES) {
@ -508,7 +520,9 @@ void DataFlash_File::EraseAll()
if (fname == nullptr) {
break;
}
hal.scheduler->expect_delay_ms(3000);
unlink(fname);
hal.scheduler->expect_delay_ms(0);
free(fname);
}
char *fname = _lastlog_file_name();
@ -641,11 +655,14 @@ uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const
write_fd_semaphore->give();
}
struct stat st;
hal.scheduler->expect_delay_ms(3000);
if (::stat(fname, &st) != 0) {
printf("Unable to fetch Log File Size: %s\n", strerror(errno));
free(fname);
hal.scheduler->expect_delay_ms(0);
return 0;
}
hal.scheduler->expect_delay_ms(0);
free(fname);
return st.st_size;
}
@ -670,11 +687,14 @@ uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const
write_fd_semaphore->give();
}
struct stat st;
hal.scheduler->expect_delay_ms(3000);
if (::stat(fname, &st) != 0) {
free(fname);
hal.scheduler->expect_delay_ms(0);
return 0;
}
free(fname);
hal.scheduler->expect_delay_ms(0);
return st.st_mtime;
}