mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: fixed log listing with gap, and EKF error on log list
this fixes two issues: The first issue that if we are missing a log file in the middle of the list then it was not possible to download recent logs, as we get the incorrect value for total number of logs. This happened for me with 107 logs, with log62 missing from the microSD. It would only show 45 available logs, so the most recent logs could not be downloaded. The second issue is that get_num_logs() was very slow if there were a lot of log files in a directory. This would cause EKF errors and ESC resets. Using a opendir/readdir loop is much faster (approx 10x faster in my testing with 107 logs on a MatekH743).
This commit is contained in:
parent
fa3c1fef18
commit
43f1a11a5b
|
@ -201,6 +201,29 @@ int64_t AP_Logger_File::disk_space()
|
||||||
return AP::FS().disk_space(_log_directory);
|
return AP::FS().disk_space(_log_directory);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
convert a dirent to a log number
|
||||||
|
*/
|
||||||
|
bool AP_Logger_File::dirent_to_log_num(const dirent *de, uint16_t &log_num) const
|
||||||
|
{
|
||||||
|
uint8_t length = strlen(de->d_name);
|
||||||
|
if (length < 5) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (strncmp(&de->d_name[length-4], ".BIN", 4) != 0) {
|
||||||
|
// doesn't end in .BIN
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t thisnum = strtoul(de->d_name, nullptr, 10);
|
||||||
|
if (thisnum > MAX_LOG_FILES) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
log_num = thisnum;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// find_oldest_log - find oldest log in _log_directory
|
// find_oldest_log - find oldest log in _log_directory
|
||||||
// returns 0 if no log was found
|
// returns 0 if no log was found
|
||||||
uint16_t AP_Logger_File::find_oldest_log()
|
uint16_t AP_Logger_File::find_oldest_log()
|
||||||
|
@ -230,19 +253,9 @@ uint16_t AP_Logger_File::find_oldest_log()
|
||||||
EXPECT_DELAY_MS(3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) {
|
for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) {
|
||||||
EXPECT_DELAY_MS(3000);
|
EXPECT_DELAY_MS(3000);
|
||||||
uint8_t length = strlen(de->d_name);
|
uint16_t thisnum;
|
||||||
if (length < 5) {
|
if (!dirent_to_log_num(de, thisnum)) {
|
||||||
// not long enough for \d+[.]BIN
|
// not a log filename
|
||||||
continue;
|
|
||||||
}
|
|
||||||
if (strncmp(&de->d_name[length-4], ".BIN", 4) != 0) {
|
|
||||||
// doesn't end in .BIN
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t thisnum = strtoul(de->d_name, nullptr, 10);
|
|
||||||
if (thisnum > MAX_LOG_FILES) {
|
|
||||||
// ignore files above our official maximum...
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (current_oldest_log == 0) {
|
if (current_oldest_log == 0) {
|
||||||
|
@ -661,29 +674,39 @@ void AP_Logger_File::get_log_info(const uint16_t list_entry, uint32_t &size, uin
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get the number of logs - note that the log numbers must be consecutive
|
get the number of logs - note that the log numbers must be consecutive
|
||||||
*/
|
*/
|
||||||
uint16_t AP_Logger_File::get_num_logs()
|
uint16_t AP_Logger_File::get_num_logs()
|
||||||
{
|
{
|
||||||
uint16_t ret = 0;
|
auto *d = AP::FS().opendir(_log_directory);
|
||||||
|
if (d == nullptr) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
uint16_t high = find_last_log();
|
uint16_t high = find_last_log();
|
||||||
uint16_t i;
|
uint16_t ret = high;
|
||||||
for (i=high; i>0; i--) {
|
uint16_t smallest = high;
|
||||||
if (! log_exists(i)) {
|
uint16_t smallest_above_last = 0;
|
||||||
break;
|
|
||||||
|
EXPECT_DELAY_MS(2000);
|
||||||
|
for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) {
|
||||||
|
EXPECT_DELAY_MS(100);
|
||||||
|
uint16_t thisnum;
|
||||||
|
if (!dirent_to_log_num(de, thisnum)) {
|
||||||
|
// not a log filename
|
||||||
|
continue;
|
||||||
}
|
}
|
||||||
ret++;
|
smallest = MIN(smallest, thisnum);
|
||||||
}
|
if (thisnum > high && (smallest_above_last != 0 || thisnum < smallest_above_last)) {
|
||||||
if (i == 0) {
|
smallest_above_last = thisnum;
|
||||||
for (i=MAX_LOG_FILES; i>high; i--) {
|
|
||||||
if (! log_exists(i)) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
ret++;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
AP::FS().closedir(d);
|
||||||
|
if (smallest_above_last != 0) {
|
||||||
|
// we have wrapped, add in the logs with high numbers
|
||||||
|
ret += (MAX_LOG_FILES - smallest_above_last) + 1;
|
||||||
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -100,6 +100,8 @@ private:
|
||||||
bool file_exists(const char *filename) const;
|
bool file_exists(const char *filename) const;
|
||||||
bool log_exists(const uint16_t lognum) const;
|
bool log_exists(const uint16_t lognum) const;
|
||||||
|
|
||||||
|
bool dirent_to_log_num(const dirent *de, uint16_t &log_num) const;
|
||||||
|
|
||||||
// write buffer
|
// write buffer
|
||||||
ByteBuffer _writebuf{0};
|
ByteBuffer _writebuf{0};
|
||||||
const uint16_t _writebuf_chunk = HAL_LOGGER_WRITE_CHUNK_SIZE;
|
const uint16_t _writebuf_chunk = HAL_LOGGER_WRITE_CHUNK_SIZE;
|
||||||
|
|
Loading…
Reference in New Issue