|
|
|
@ -41,22 +41,49 @@
@@ -41,22 +41,49 @@
|
|
|
|
|
|
|
|
|
|
#if defined(CCM_RAM_SIZE_KB) |
|
|
|
|
static memory_heap_t ccm_heap; |
|
|
|
|
static bool ccm_heap_initialised = false; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if defined(DTCM_RAM_SIZE_KB) |
|
|
|
|
static memory_heap_t dtcm_heap; |
|
|
|
|
static bool dtcm_heap_initialised = false; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// size of memory reserved for dma-capable alloc
|
|
|
|
|
#ifndef DMA_RESERVE_SIZE |
|
|
|
|
#define DMA_RESERVE_SIZE 4096 |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
static memory_heap_t dma_reserve_heap; |
|
|
|
|
|
|
|
|
|
static void *malloc_dtcm(size_t size); |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
initialise memory handling |
|
|
|
|
*/ |
|
|
|
|
void malloc_init(void) |
|
|
|
|
{ |
|
|
|
|
#if defined(CCM_RAM_SIZE_KB) |
|
|
|
|
chHeapObjectInit(&ccm_heap, (void *)CCM_BASE_ADDRESS, CCM_RAM_SIZE_KB*1024); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if defined(DTCM_RAM_SIZE_KB) |
|
|
|
|
chHeapObjectInit(&dtcm_heap, (void *)DTCM_BASE_ADDRESS, DTCM_RAM_SIZE_KB*1024); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
create a DMA reserve heap, to ensure we keep some memory for DMA |
|
|
|
|
safe memory allocations |
|
|
|
|
*/ |
|
|
|
|
void *dma_reserve = malloc_dtcm(DMA_RESERVE_SIZE); |
|
|
|
|
if (!dma_reserve) { |
|
|
|
|
dma_reserve = chHeapAllocAligned(NULL, DMA_RESERVE_SIZE, MIN_ALIGNMENT); |
|
|
|
|
} |
|
|
|
|
chHeapObjectInit(&dma_reserve_heap, dma_reserve, DMA_RESERVE_SIZE); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void *malloc_ccm(size_t size) |
|
|
|
|
{ |
|
|
|
|
void *p = NULL; |
|
|
|
|
#if defined(CCM_RAM_SIZE_KB) |
|
|
|
|
if (!ccm_heap_initialised) { |
|
|
|
|
ccm_heap_initialised = true; |
|
|
|
|
chHeapObjectInit(&ccm_heap, (void *)CCM_BASE_ADDRESS, CCM_RAM_SIZE_KB*1024); |
|
|
|
|
} |
|
|
|
|
p = chHeapAllocAligned(&ccm_heap, size, CH_HEAP_ALIGNMENT); |
|
|
|
|
if (p != NULL) { |
|
|
|
|
memset(p, 0, size); |
|
|
|
@ -67,21 +94,17 @@ void *malloc_ccm(size_t size)
@@ -67,21 +94,17 @@ void *malloc_ccm(size_t size)
|
|
|
|
|
return p; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void *malloc_dtcm(size_t size) |
|
|
|
|
static void *malloc_dtcm(size_t size) |
|
|
|
|
{ |
|
|
|
|
void *p = NULL; |
|
|
|
|
#if defined(DTCM_RAM_SIZE_KB) |
|
|
|
|
if (!dtcm_heap_initialised) { |
|
|
|
|
dtcm_heap_initialised = true; |
|
|
|
|
chHeapObjectInit(&dtcm_heap, (void *)DTCM_BASE_ADDRESS, DTCM_RAM_SIZE_KB*1024); |
|
|
|
|
} |
|
|
|
|
p = chHeapAllocAligned(&dtcm_heap, size, CH_HEAP_ALIGNMENT); |
|
|
|
|
if (p != NULL) { |
|
|
|
|
memset(p, 0, size); |
|
|
|
|
} |
|
|
|
|
#else |
|
|
|
|
(void)size; |
|
|
|
|
#endif |
|
|
|
|
if (p != NULL) { |
|
|
|
|
memset(p, 0, size); |
|
|
|
|
} |
|
|
|
|
return p; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -109,24 +132,36 @@ void *malloc(size_t size)
@@ -109,24 +132,36 @@ void *malloc(size_t size)
|
|
|
|
|
return p; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// fall back to DMA reserve
|
|
|
|
|
p = chHeapAllocAligned(&dma_reserve_heap, size, MIN_ALIGNMENT); |
|
|
|
|
if (p) { |
|
|
|
|
memset(p, 0, size); |
|
|
|
|
return p; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return NULL; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
allocte DMA-safe memory |
|
|
|
|
allocate DMA-safe memory |
|
|
|
|
*/ |
|
|
|
|
void *malloc_dma(size_t size) |
|
|
|
|
{ |
|
|
|
|
void *p; |
|
|
|
|
#if defined(DTCM_RAM_SIZE_KB) |
|
|
|
|
return malloc_dtcm(size); |
|
|
|
|
p = malloc_dtcm(size); |
|
|
|
|
#else |
|
|
|
|
// if we don't have DTCM memory then assume that main heap is DMA-safe
|
|
|
|
|
void *p = chHeapAllocAligned(NULL, size, MIN_ALIGNMENT); |
|
|
|
|
p = chHeapAllocAligned(NULL, size, MIN_ALIGNMENT); |
|
|
|
|
#endif |
|
|
|
|
if (p == NULL) { |
|
|
|
|
p = chHeapAllocAligned(&dma_reserve_heap, size, MIN_ALIGNMENT); |
|
|
|
|
} |
|
|
|
|
if (p) { |
|
|
|
|
memset(p, 0, size); |
|
|
|
|
} |
|
|
|
|
return p; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void *calloc(size_t nmemb, size_t size) |
|
|
|
@ -164,7 +199,11 @@ size_t mem_available(void)
@@ -164,7 +199,11 @@ size_t mem_available(void)
|
|
|
|
|
chHeapStatus(&dtcm_heap, &dtcm_available, NULL); |
|
|
|
|
totalp += dtcm_available; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
size_t reserve_available = 0; |
|
|
|
|
chHeapStatus(&dma_reserve_heap, &reserve_available, NULL); |
|
|
|
|
totalp += reserve_available; |
|
|
|
|
|
|
|
|
|
return totalp; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|