DataFlash: only fsync every 10 seconds
prevents too much work in SITL
This commit is contained in:
parent
757dd228d2
commit
4519aa8867
@ -531,8 +531,11 @@ void DataFlash_File::_io_timer(void)
|
|||||||
_write_fd = -1;
|
_write_fd = -1;
|
||||||
_initialised = false;
|
_initialised = false;
|
||||||
} else {
|
} else {
|
||||||
::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();
|
||||||
|
::fsync(_write_fd);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -49,6 +49,7 @@ private:
|
|||||||
uint32_t _read_offset;
|
uint32_t _read_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
|
||||||
|
Loading…
Reference in New Issue
Block a user