HAL_ChibiOS: separate out DMA allocation for sdcard IO
this fixes an issue with DMA to SPI6 on STM32H7. On the H7 SRAM4 can be used for DMA and BDMA to all devices except for SDMMC which uses IDMA. by separating out DMA of sdcard data from other data we can arrange for DMA to all devices to work
This commit is contained in:
parent
a7c91d1cb4
commit
26d1371d25
@ -32,8 +32,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, 10);
|
||||
bouncebuffer_init(&bounce_buffer_rx, 10);
|
||||
bouncebuffer_init(&bounce_buffer_tx, 10, false);
|
||||
bouncebuffer_init(&bounce_buffer_rx, 10, false);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -36,12 +36,13 @@
|
||||
/*
|
||||
initialise a bouncebuffer
|
||||
*/
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes)
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes, bool sdcard)
|
||||
{
|
||||
(*bouncebuffer) = calloc(1, sizeof(struct bouncebuffer_t));
|
||||
osalDbgAssert(((*bouncebuffer) != NULL), "bouncebuffer init");
|
||||
(*bouncebuffer)->is_sdcard = sdcard;
|
||||
if (prealloc_bytes) {
|
||||
(*bouncebuffer)->dma_buf = malloc_dma(prealloc_bytes);
|
||||
(*bouncebuffer)->dma_buf = sdcard?malloc_sdcard_dma(prealloc_bytes):malloc_dma(prealloc_bytes);
|
||||
osalDbgAssert(((*bouncebuffer)->dma_buf != NULL), "bouncebuffer preallocate");
|
||||
(*bouncebuffer)->size = prealloc_bytes;
|
||||
}
|
||||
@ -64,7 +65,7 @@ void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf,
|
||||
if (bouncebuffer->size > 0) {
|
||||
free(bouncebuffer->dma_buf);
|
||||
}
|
||||
bouncebuffer->dma_buf = malloc_dma(size);
|
||||
bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
|
||||
osalDbgAssert((bouncebuffer->dma_buf != NULL), "bouncebuffer read allocate");
|
||||
bouncebuffer->size = size;
|
||||
}
|
||||
@ -105,7 +106,7 @@ void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t
|
||||
if (bouncebuffer->size > 0) {
|
||||
free(bouncebuffer->dma_buf);
|
||||
}
|
||||
bouncebuffer->dma_buf = malloc_dma(size);
|
||||
bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
|
||||
osalDbgAssert((bouncebuffer->dma_buf != NULL), "bouncebuffer write allocate");
|
||||
bouncebuffer->size = size;
|
||||
}
|
||||
|
@ -16,12 +16,13 @@ struct bouncebuffer_t {
|
||||
uint8_t *orig_buf;
|
||||
uint32_t size;
|
||||
bool busy;
|
||||
bool is_sdcard;
|
||||
};
|
||||
|
||||
/*
|
||||
initialise a bouncebuffer
|
||||
*/
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes);
|
||||
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes, bool sdcard);
|
||||
|
||||
/*
|
||||
setup for reading from a device into memory, allocating a bouncebuffer if needed
|
||||
|
@ -33,6 +33,7 @@
|
||||
|
||||
#define MEM_REGION_FLAG_DMA_OK 1
|
||||
#define MEM_REGION_FLAG_FAST 2
|
||||
#define MEM_REGION_FLAG_SDCARD 4
|
||||
|
||||
static const struct memory_region {
|
||||
void *address;
|
||||
@ -91,11 +92,12 @@ static void *malloc_flags(size_t size, uint32_t flags)
|
||||
if (size == 0) {
|
||||
return NULL;
|
||||
}
|
||||
const uint8_t alignment = (flags&MEM_REGION_FLAG_DMA_OK?DMA_ALIGNMENT:MIN_ALIGNMENT);
|
||||
const uint8_t dma_flags = (MEM_REGION_FLAG_DMA_OK | MEM_REGION_FLAG_SDCARD);
|
||||
const uint8_t alignment = (flags&dma_flags?DMA_ALIGNMENT:MIN_ALIGNMENT);
|
||||
void *p = NULL;
|
||||
uint8_t i;
|
||||
|
||||
if (flags & MEM_REGION_FLAG_DMA_OK) {
|
||||
if (flags & dma_flags) {
|
||||
// allocate multiple of DMA alignment
|
||||
size = (size + (DMA_ALIGNMENT-1)) & ~(DMA_ALIGNMENT-1);
|
||||
}
|
||||
@ -116,6 +118,10 @@ static void *malloc_flags(size_t size, uint32_t flags)
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_DMA_OK)) {
|
||||
continue;
|
||||
}
|
||||
if ((flags & MEM_REGION_FLAG_SDCARD) &&
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_SDCARD)) {
|
||||
continue;
|
||||
}
|
||||
if ((flags & MEM_REGION_FLAG_FAST) &&
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_FAST)) {
|
||||
continue;
|
||||
@ -127,7 +133,7 @@ static void *malloc_flags(size_t size, uint32_t flags)
|
||||
}
|
||||
|
||||
// if this is a not a DMA request then we can fall back to any heap
|
||||
if (!(flags & MEM_REGION_FLAG_DMA_OK)) {
|
||||
if (!(flags & dma_flags)) {
|
||||
for (i=1; i<NUM_MEMORY_REGIONS; i++) {
|
||||
p = chHeapAllocAligned(&heaps[i], size, alignment);
|
||||
if (p) {
|
||||
@ -173,6 +179,19 @@ void *malloc_dma(size_t size)
|
||||
return malloc_flags(size, MEM_REGION_FLAG_DMA_OK);
|
||||
}
|
||||
|
||||
/*
|
||||
allocate DMA-safe memory for microSD transfers. This is only
|
||||
different on H7 where SDMMC IDMA can't use SRAM4
|
||||
*/
|
||||
void *malloc_sdcard_dma(size_t size)
|
||||
{
|
||||
#if defined(STM32H7)
|
||||
return malloc_flags(size, MEM_REGION_FLAG_SDCARD);
|
||||
#else
|
||||
return malloc_flags(size, MEM_REGION_FLAG_DMA_OK);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
allocate fast memory
|
||||
*/
|
||||
|
@ -31,6 +31,7 @@ void show_stack_usage(void);
|
||||
// allocation functions in malloc.c
|
||||
size_t mem_available(void);
|
||||
void *malloc_dma(size_t size);
|
||||
void *malloc_sdcard_dma(size_t size);
|
||||
void *malloc_fastmem(size_t size);
|
||||
thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg);
|
||||
|
||||
|
@ -15,14 +15,15 @@ mcu = {
|
||||
'UDID_START' : 0x1FF1E800,
|
||||
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 1 means DMA-capable (DMA and BDMA)
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
# flags of 4 means memory can be used for SDMMC DMA
|
||||
'RAM_MAP' : [
|
||||
(0x24000000, 512, 1), # AXI SRAM
|
||||
(0x30000000, 288, 1), # SRAM1, SRAM2, SRAM3
|
||||
(0x38000000, 64, 1), # SRAM4
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 288, 0), # SRAM1, SRAM2, SRAM3
|
||||
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA
|
||||
]
|
||||
}
|
||||
|
||||
|
@ -56,7 +56,7 @@ bool sdcard_init()
|
||||
#if HAL_USE_SDC
|
||||
|
||||
if (SDCD1.bouncebuffer == nullptr) {
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer, 512);
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer, 512, true);
|
||||
}
|
||||
|
||||
if (sdcard_running) {
|
||||
|
Loading…
Reference in New Issue
Block a user