HAL_ChibiOS: use 4k bouncebuffer for sdcard

match AP_Logger IO size
This commit is contained in:
Andrew Tridgell 2020-01-17 15:58:30 +11:00
parent c5b1c88948
commit 23005e6f46

View File

@ -56,7 +56,9 @@ bool sdcard_init()
#if HAL_USE_SDC
if (SDCD1.bouncebuffer == nullptr) {
bouncebuffer_init(&SDCD1.bouncebuffer, 512, true);
// allocate 4k bouncebuffer for microSD to match size in
// AP_Logger
bouncebuffer_init(&SDCD1.bouncebuffer, 4096, true);
}
if (sdcard_running) {