AP_Logger: fixed @SYS file logging

the key fix is the reset of the fd to -1. Without that fix we only
ever log @SYS/uarts.txt

The timing change is needed to get the files out in a reasonable
time. The function is actually getting called at 100Hz or less, not
1kHz (measured on MatekH743 copter at 400Hz). So we need to run it
faster to get the files logged in a reasonable time
This commit is contained in:
Andrew Tridgell 2022-04-05 19:48:00 +10:00
parent eef3ab9e94
commit a661f3e7a7
1 changed files with 8 additions and 6 deletions

View File

@ -1532,14 +1532,15 @@ void AP_Logger::file_content_update(FileContent &file_content)
return;
}
/* this function is called at max 1kHz. We don't want to saturate
the logging with file data, so we reduce the frequency of 64
byte file writes by a factor of 100. For the file
crash_dump.bin we dump 10x faster so we get it in a reasonable
time (full dump of 450k in about 1 minute)
/* this function is called at around 100Hz on average (tested on
400Hz copter). We don't want to saturate the logging with file
data, so we reduce the frequency of 64 byte file writes by a
factor of 10. For the file crash_dump.bin we dump 10x faster so
we get it in a reasonable time (full dump of 450k in about 1
minute)
*/
file_content.counter++;
const uint8_t frequency = file_content.fast?10:100;
const uint8_t frequency = file_content.fast?1:10;
if (file_content.counter % frequency != 0) {
return;
}
@ -1565,6 +1566,7 @@ void AP_Logger::file_content_update(FileContent &file_content)
const auto length = AP::FS().read(file_content.fd, pkt.data, sizeof(pkt.data));
if (length <= 0) {
AP::FS().close(file_content.fd);
file_content.fd = -1;
file_content.remove_and_free(file);
return;
}