DataFlash: allow use of a smaller writebuf for PX4v1

this fixes logging on PX4v1
This commit is contained in:
Andrew Tridgell 2014-09-09 17:32:35 +10:00
parent 8fcc96bb79
commit 9d846d5f2a
2 changed files with 14 additions and 3 deletions

View File

@ -105,9 +105,20 @@ void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_type
if (_writebuf != NULL) {
free(_writebuf);
}
_writebuf = (uint8_t *)malloc(_writebuf_size);
/*
if we can't allocate the full writebuf then try reducing it
until we can allocate it
*/
while (_writebuf == NULL && _writebuf_size >= _writebuf_chunk) {
_writebuf = (uint8_t *)malloc(_writebuf_size);
if (_writebuf == NULL) {
_writebuf_size /= 2;
}
}
if (_writebuf == NULL) {
return;
hal.console->printf("Out of memory for logging\n");
return;
}
_writebuf_head = _writebuf_tail = 0;
_initialised = true;

View File

@ -67,7 +67,7 @@ private:
// write buffer
uint8_t *_writebuf;
const uint16_t _writebuf_size;
uint16_t _writebuf_size;
const uint16_t _writebuf_chunk;
volatile uint16_t _writebuf_head;
volatile uint16_t _writebuf_tail;