mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
DataFlash: LOG_FILE_BUFSIZE sets buffer size for DataFlash_File
This commit is contained in:
parent
c118130dda
commit
7900359fac
@ -9,6 +9,13 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
|
||||
// @Values: 0:None,1:File,2:MAVLink,3:BothFileAndMAVLink
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_BACKEND_TYPE", 0, DataFlash_Class, _params.backend_types, DATAFLASH_BACKEND_FILE),
|
||||
|
||||
// @Param: _FILE_BUFSIZE
|
||||
// @DisplayName: Maximum DataFlash File Backend buffer size (in kilobytes)
|
||||
// @Description: The DataFlash_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_FILE_BUFSIZE", 1, DataFlash_Class, _params.file_bufsize, 16),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -162,6 +162,7 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
struct {
|
||||
AP_Int8 backend_types;
|
||||
AP_Int8 file_bufsize; // in kilobytes
|
||||
} _params;
|
||||
|
||||
const struct LogStructure *structure(uint16_t num) const;
|
||||
|
@ -60,7 +60,6 @@ DataFlash_File::DataFlash_File(DataFlash_Class &front,
|
||||
_log_directory(log_directory),
|
||||
_cached_oldest_log(0),
|
||||
_writebuf(NULL),
|
||||
_writebuf_size(16*1024),
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
// V1 gets IO errors with larger than 512 byte writes
|
||||
_writebuf_chunk(512),
|
||||
@ -130,11 +129,21 @@ void DataFlash_File::Init()
|
||||
_writebuf = NULL;
|
||||
}
|
||||
|
||||
// determine and limit file backend buffersize
|
||||
uint8_t bufsize = _front._params.file_bufsize;
|
||||
if (bufsize > 64) {
|
||||
// we currently use uint16_t for the ringbuffer. Also,
|
||||
// PixHawk has DMA limitaitons.
|
||||
bufsize = 64;
|
||||
}
|
||||
_writebuf_size = bufsize * 1024;
|
||||
|
||||
/*
|
||||
if we can't allocate the full writebuf then try reducing it
|
||||
until we can allocate it
|
||||
*/
|
||||
while (_writebuf == NULL && _writebuf_size >= _writebuf_chunk) {
|
||||
hal.console->printf("DataFlash_File: buffer size=%d\n", _writebuf_size);
|
||||
_writebuf = (uint8_t *)malloc(_writebuf_size);
|
||||
if (_writebuf == NULL) {
|
||||
_writebuf_size /= 2;
|
||||
@ -463,20 +472,20 @@ bool DataFlash_File::WritePrioritisedBlock(const void *pBuffer, uint16_t size, b
|
||||
|
||||
if (_writebuf_tail < _head) {
|
||||
// perform as single memcpy
|
||||
assert(_writebuf_tail+size <= _writebuf_size);
|
||||
assert(((uint32_t)_writebuf_tail)+size <= _writebuf_size);
|
||||
memcpy(&_writebuf[_writebuf_tail], pBuffer, size);
|
||||
BUF_ADVANCETAIL(_writebuf, size);
|
||||
} else {
|
||||
// perform as two memcpy calls
|
||||
uint16_t n = _writebuf_size - _writebuf_tail;
|
||||
uint32_t n = _writebuf_size - _writebuf_tail;
|
||||
if (n > size) n = size;
|
||||
assert(_writebuf_tail+n <= _writebuf_size);
|
||||
assert(((uint32_t)_writebuf_tail)+n <= _writebuf_size);
|
||||
memcpy(&_writebuf[_writebuf_tail], pBuffer, n);
|
||||
BUF_ADVANCETAIL(_writebuf, n);
|
||||
pBuffer = (const void *)(((const uint8_t *)pBuffer) + n);
|
||||
n = size - n;
|
||||
if (n > 0) {
|
||||
assert(_writebuf_tail+n <= _writebuf_size);
|
||||
assert(((uint32_t)_writebuf_tail)+n <= _writebuf_size);
|
||||
memcpy(&_writebuf[_writebuf_tail], pBuffer, n);
|
||||
BUF_ADVANCETAIL(_writebuf, n);
|
||||
}
|
||||
@ -978,7 +987,7 @@ void DataFlash_File::_io_timer(void)
|
||||
}
|
||||
}
|
||||
|
||||
assert(_writebuf_head+nbytes <= _writebuf_size);
|
||||
assert(((uint32_t)_writebuf_head)+nbytes <= _writebuf_size);
|
||||
ssize_t nwritten = ::write(_write_fd, &_writebuf[_writebuf_head], nbytes);
|
||||
if (nwritten <= 0) {
|
||||
hal.util->perf_count(_perf_errors);
|
||||
|
@ -94,7 +94,7 @@ private:
|
||||
#endif
|
||||
// write buffer
|
||||
uint8_t *_writebuf;
|
||||
uint16_t _writebuf_size;
|
||||
uint32_t _writebuf_size; // in bytes; may be == 65536, thus 32-bits
|
||||
const uint16_t _writebuf_chunk;
|
||||
volatile uint16_t _writebuf_head;
|
||||
volatile uint16_t _writebuf_tail;
|
||||
@ -112,11 +112,23 @@ private:
|
||||
|
||||
uint16_t critical_message_reserved_space() const {
|
||||
// possibly make this a proportional to buffer size?
|
||||
return 1024;
|
||||
uint16_t ret = 1024;
|
||||
if (ret > _writebuf_size) {
|
||||
// in this case you will only get critical messages
|
||||
ret = _writebuf_size;
|
||||
}
|
||||
return ret;
|
||||
};
|
||||
uint16_t non_messagewriter_message_reserved_space() const {
|
||||
// possibly make this a proportional to buffer size?
|
||||
return 1024;
|
||||
uint16_t ret = 1024;
|
||||
if (ret >= _writebuf_size) {
|
||||
// need to allow messages out from the messagewriters. In
|
||||
// this case while you have a messagewriter you won't get
|
||||
// any other messages. This should be a corner case!
|
||||
ret = 0;
|
||||
}
|
||||
return ret;
|
||||
};
|
||||
|
||||
// performance counters
|
||||
|
Loading…
Reference in New Issue
Block a user