DataFlash: only fsync every 10 seconds

prevents too much work in SITL
This commit is contained in:
Andrew Tridgell 2014-01-02 22:04:22 +11:00
parent 757dd228d2
commit 4519aa8867
2 changed files with 5 additions and 1 deletions

View File

@ -531,8 +531,11 @@ void DataFlash_File::_io_timer(void)
_write_fd = -1;
_initialised = false;
} else {
::fsync(_write_fd);
BUF_ADVANCEHEAD(_writebuf, nwritten);
if (hal.scheduler->millis() - last_fsync_ms > 10000) {
last_fsync_ms = hal.scheduler->millis();
::fsync(_write_fd);
}
}
}

View File

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