From 4519aa886774f693f9e2fc28242c98d9fa1a57e8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 Jan 2014 22:04:22 +1100 Subject: [PATCH] DataFlash: only fsync every 10 seconds prevents too much work in SITL --- libraries/DataFlash/DataFlash_File.cpp | 5 ++++- libraries/DataFlash/DataFlash_File.h | 1 + 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index b13e39b0f2..6d7f8bd61e 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -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); + } } } diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 03fbf55aad..ea5a001da6 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -49,6 +49,7 @@ private: uint32_t _read_offset; volatile bool _initialised; const char *_log_directory; + uint32_t last_fsync_ms; /* read a block