DataFlash: improve reliability of microSD for logs

This commit is contained in:
Andrew Tridgell 2014-01-14 12:39:49 +11:00
parent b88bb0751c
commit b4b66210ff
2 changed files with 27 additions and 10 deletions

View File

@ -23,6 +23,7 @@
#include <AP_Math.h> #include <AP_Math.h>
#include <stdio.h> #include <stdio.h>
#include <time.h> #include <time.h>
#include <dirent.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -41,8 +42,7 @@ DataFlash_File::DataFlash_File(const char *log_directory) :
_log_directory(log_directory), _log_directory(log_directory),
_writebuf(NULL), _writebuf(NULL),
_writebuf_size(16*1024), _writebuf_size(16*1024),
_writebuf_chunk(512), // until multiblock write support works on _writebuf_chunk(4096),
// px4, we are best off keeping writes small
_writebuf_head(0), _writebuf_head(0),
_writebuf_tail(0), _writebuf_tail(0),
_last_write_time(0) _last_write_time(0)
@ -61,6 +61,22 @@ void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_type
// create the log directory if need be // create the log directory if need be
int ret; int ret;
struct stat st; struct stat st;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// try to cope with an existing lowercase log directory
// name. NuttX does not handle case insensitive VFAT well
DIR *d = opendir("/fs/microsd/APM");
if (d != NULL) {
for (struct dirent *de=readdir(d); de; de=readdir(d)) {
if (strcmp(de->d_name, "logs") == 0) {
rename("/fs/microsd/APM/logs", "/fs/microsd/APM/OLDLOGS");
break;
}
}
closedir(d);
}
#endif
ret = stat(_log_directory, &st); ret = stat(_log_directory, &st);
if (ret == -1) { if (ret == -1) {
ret = mkdir(_log_directory, 0777); ret = mkdir(_log_directory, 0777);
@ -370,7 +386,7 @@ uint16_t DataFlash_File::start_new_log(void)
// now update lastlog.txt with the new log number // now update lastlog.txt with the new log number
fname = _lastlog_file_name(); fname = _lastlog_file_name();
FILE *f = ::fopen(fname, "w"); FILE *f = ::fopen(fname, "w");
fprintf(f, "%u\n", (unsigned)log_num); fprintf(f, "%u\r\n", (unsigned)log_num);
fclose(f); fclose(f);
free(fname); free(fname);
@ -513,6 +529,7 @@ void DataFlash_File::_io_timer(void)
if (_write_fd == -1 || !_initialised) { if (_write_fd == -1 || !_initialised) {
return; return;
} }
uint16_t nbytes = BUF_AVAILABLE(_writebuf); uint16_t nbytes = BUF_AVAILABLE(_writebuf);
if (nbytes == 0) { if (nbytes == 0) {
return; return;
@ -555,13 +572,14 @@ void DataFlash_File::_io_timer(void)
_initialised = false; _initialised = false;
} else { } else {
_write_offset += nwritten; _write_offset += nwritten;
/*
the best strategy for minimising corruption on microSD cards
seems to be to write in 4k chunks and fsync the file on each
chunk, ensuring the directory entry is updated after each
write.
*/
::fsync(_write_fd);
BUF_ADVANCEHEAD(_writebuf, nwritten); BUF_ADVANCEHEAD(_writebuf, nwritten);
if (hal.scheduler->millis() - last_fsync_ms > 10000) {
last_fsync_ms = hal.scheduler->millis();
perf_begin(_perf_fsync);
::fsync(_write_fd);
perf_end(_perf_fsync);
}
} }
perf_end(_perf_write); perf_end(_perf_write);
} }

View File

@ -58,7 +58,6 @@ private:
uint32_t _write_offset; uint32_t _write_offset;
volatile bool _initialised; volatile bool _initialised;
const char *_log_directory; const char *_log_directory;
uint32_t last_fsync_ms;
/* /*
read a block read a block