mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_Logger: try harder to use close to user buffer size
this stops us drastically reducing buffer size when low on memory
This commit is contained in:
parent
3105255080
commit
609a2d95f8
@ -83,10 +83,14 @@ void AP_Logger_File::Init()
|
|||||||
}
|
}
|
||||||
bufsize *= 1024;
|
bufsize *= 1024;
|
||||||
|
|
||||||
|
const uint32_t desired_bufsize = bufsize;
|
||||||
|
|
||||||
// If we can't allocate the full size, try to reduce it until we can allocate it
|
// If we can't allocate the full size, try to reduce it until we can allocate it
|
||||||
while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
|
while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
|
||||||
hal.console->printf("AP_Logger_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize);
|
bufsize *= 0.9;
|
||||||
bufsize >>= 1;
|
}
|
||||||
|
if (bufsize >= _writebuf_chunk && bufsize != desired_bufsize) {
|
||||||
|
hal.console->printf("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize, (unsigned)desired_bufsize);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!_writebuf.get_size()) {
|
if (!_writebuf.get_size()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user