mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: added preallocation of DMA bouncebuffers
we need 512 bytes for microSD
This commit is contained in:
parent
e193a161f2
commit
f083b80700
|
@ -31,8 +31,8 @@ static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
|||
DeviceBus::DeviceBus(uint8_t _thread_priority) :
|
||||
thread_priority(_thread_priority)
|
||||
{
|
||||
bouncebuffer_init(&bounce_buffer_tx);
|
||||
bouncebuffer_init(&bounce_buffer_rx);
|
||||
bouncebuffer_init(&bounce_buffer_tx, 10);
|
||||
bouncebuffer_init(&bounce_buffer_rx, 10);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -32,10 +32,15 @@
|
|||
/*
|
||||
initialise a bouncebuffer
|
||||
*/
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer)
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes)
|
||||
{
|
||||
(*bouncebuffer) = calloc(1, sizeof(struct bouncebuffer_t));
|
||||
osalDbgAssert(((*bouncebuffer) != NULL), "bouncebuffer init");
|
||||
if (prealloc_bytes) {
|
||||
(*bouncebuffer)->dma_buf = malloc_dma(prealloc_bytes);
|
||||
osalDbgAssert(((*bouncebuffer)->dma_buf != NULL), "bouncebuffer preallocate");
|
||||
(*bouncebuffer)->size = prealloc_bytes;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -21,7 +21,7 @@ struct bouncebuffer_t {
|
|||
/*
|
||||
initialise a bouncebuffer
|
||||
*/
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer);
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes);
|
||||
|
||||
/*
|
||||
setup for reading from a device into memory, allocating a bouncebuffer if needed
|
||||
|
|
|
@ -46,7 +46,7 @@ void sdcard_init()
|
|||
sdcard_init_done = true;
|
||||
#if HAL_USE_SDC
|
||||
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer);
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer, 512);
|
||||
|
||||
sdcStart(&SDCD1, NULL);
|
||||
|
||||
|
|
Loading…
Reference in New Issue