HAL_ChibiOS: added support for more flexible memory regions
this allows for an arbitrary number of memory regions, with each one flagged as DMA safe, fast or normal
This commit is contained in:
parent
664e92ed7e
commit
cda1959629
@ -54,7 +54,7 @@ void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
||||
return malloc_dma(size);
|
||||
} else if (mem_type == AP_HAL::Util::MEM_FAST) {
|
||||
return try_alloc_from_ccm_ram(size);
|
||||
return malloc_fastmem(size);
|
||||
} else {
|
||||
return calloc(1, size);
|
||||
}
|
||||
@ -68,16 +68,6 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||
}
|
||||
|
||||
|
||||
void* Util::try_alloc_from_ccm_ram(size_t size)
|
||||
{
|
||||
void *ret = malloc_ccm(size);
|
||||
if (ret == nullptr) {
|
||||
//we failed to allocate from CCM so we are going to try common SRAM
|
||||
ret = calloc(1, size);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
#ifdef ENABLE_HEAP
|
||||
|
||||
void *Util::allocate_heap_memory(size_t size)
|
||||
|
@ -75,8 +75,6 @@ private:
|
||||
|
||||
static ToneAlarmPwmGroup _toneAlarm_pwm_group;
|
||||
#endif
|
||||
void* try_alloc_from_ccm_ram(size_t size);
|
||||
uint32_t available_memory_in_ccm_ram(void);
|
||||
|
||||
#if HAL_HAVE_IMU_HEATER
|
||||
struct {
|
||||
|
@ -31,6 +31,20 @@
|
||||
#include <stdarg.h>
|
||||
#include "stm32_util.h"
|
||||
|
||||
#define MEM_REGION_FLAG_DMA_OK 1
|
||||
#define MEM_REGION_FLAG_FAST 2
|
||||
|
||||
static struct memory_region {
|
||||
void *address;
|
||||
uint32_t size;
|
||||
uint32_t flags;
|
||||
memory_heap_t heap;
|
||||
} memory_regions[] = { HAL_MEMORY_REGIONS };
|
||||
|
||||
// the first memory region is already setup as the ChibiOS
|
||||
// default heap, so we will index from 1 in the allocators
|
||||
#define NUM_MEMORY_REGIONS (sizeof(memory_regions)/sizeof(memory_regions[0]))
|
||||
|
||||
#if CH_CFG_USE_HEAP == TRUE
|
||||
|
||||
#define MIN_ALIGNMENT 8
|
||||
@ -41,18 +55,6 @@
|
||||
#define DMA_ALIGNMENT 8
|
||||
#endif
|
||||
|
||||
#ifdef HAL_NO_CCM
|
||||
#undef CCM_RAM_SIZE_KB
|
||||
#endif
|
||||
|
||||
#if defined(CCM_RAM_SIZE_KB)
|
||||
static memory_heap_t ccm_heap;
|
||||
#endif
|
||||
|
||||
#if defined(DTCM_RAM_SIZE_KB)
|
||||
static memory_heap_t dtcm_heap;
|
||||
#endif
|
||||
|
||||
// size of memory reserved for dma-capable alloc
|
||||
#ifndef DMA_RESERVE_SIZE
|
||||
#define DMA_RESERVE_SIZE 4096
|
||||
@ -62,96 +64,102 @@ static memory_heap_t dtcm_heap;
|
||||
static memory_heap_t dma_reserve_heap;
|
||||
#endif
|
||||
|
||||
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
|
||||
for (uint8_t i=1; i<NUM_MEMORY_REGIONS; i++) {
|
||||
chHeapObjectInit(&memory_regions[i].heap, memory_regions[i].address, memory_regions[i].size);
|
||||
}
|
||||
|
||||
#if DMA_RESERVE_SIZE != 0
|
||||
/*
|
||||
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);
|
||||
}
|
||||
void *dma_reserve = malloc_dma(DMA_RESERVE_SIZE);
|
||||
osalDbgAssert(dma_reserve != NULL, "DMA reserve");
|
||||
chHeapObjectInit(&dma_reserve_heap, dma_reserve, DMA_RESERVE_SIZE);
|
||||
#endif //#if DMA_RESERVE_SIZE != 0
|
||||
}
|
||||
|
||||
void *malloc_ccm(size_t size)
|
||||
{
|
||||
void *p = NULL;
|
||||
#if defined(CCM_RAM_SIZE_KB)
|
||||
p = chHeapAllocAligned(&ccm_heap, size, CH_HEAP_ALIGNMENT);
|
||||
if (p != NULL) {
|
||||
memset(p, 0, size);
|
||||
}
|
||||
#else
|
||||
(void)size;
|
||||
#endif
|
||||
return p;
|
||||
}
|
||||
|
||||
static void *malloc_dtcm(size_t size)
|
||||
{
|
||||
void *p = NULL;
|
||||
#if defined(DTCM_RAM_SIZE_KB)
|
||||
p = chHeapAllocAligned(&dtcm_heap, size, DMA_ALIGNMENT);
|
||||
#else
|
||||
(void)size;
|
||||
#endif
|
||||
if (p != NULL) {
|
||||
memset(p, 0, size);
|
||||
}
|
||||
return p;
|
||||
}
|
||||
|
||||
void *malloc(size_t size)
|
||||
static void *malloc_flags(size_t size, uint32_t flags)
|
||||
{
|
||||
if (size == 0) {
|
||||
return NULL;
|
||||
}
|
||||
void *p = chHeapAllocAligned(NULL, size, MIN_ALIGNMENT);
|
||||
if (p) {
|
||||
memset(p, 0, size);
|
||||
return p;
|
||||
const uint8_t alignment = (flags&MEM_REGION_FLAG_DMA_OK?DMA_ALIGNMENT:MIN_ALIGNMENT);
|
||||
void *p = NULL;
|
||||
|
||||
if (flags & MEM_REGION_FLAG_DMA_OK) {
|
||||
// allocate multiple of DMA alignment
|
||||
size = (size + (DMA_ALIGNMENT-1)) & ~(DMA_ALIGNMENT-1);
|
||||
}
|
||||
if (!p) {
|
||||
// fall back to CCM memory
|
||||
p = malloc_ccm(size);
|
||||
|
||||
// if no flags are set or this is a DMA request and default heap
|
||||
// is DMA safe then start with default heap
|
||||
if (flags == 0 || (flags == MEM_REGION_FLAG_DMA_OK &&
|
||||
(memory_regions[0].flags & MEM_REGION_FLAG_DMA_OK))) {
|
||||
p = chHeapAllocAligned(NULL, size, alignment);
|
||||
if (p) {
|
||||
return p;
|
||||
goto found;
|
||||
}
|
||||
}
|
||||
if (!p) {
|
||||
// fall back to DTCM memory
|
||||
p = malloc_dtcm(size);
|
||||
|
||||
// try with matching flags
|
||||
for (uint8_t i=1; i<NUM_MEMORY_REGIONS; i++) {
|
||||
if ((flags & MEM_REGION_FLAG_DMA_OK) &&
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_DMA_OK)) {
|
||||
continue;
|
||||
}
|
||||
if ((flags & MEM_REGION_FLAG_FAST) &&
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_FAST)) {
|
||||
continue;
|
||||
}
|
||||
p = chHeapAllocAligned(&memory_regions[i].heap, size, alignment);
|
||||
if (p) {
|
||||
return p;
|
||||
goto found;
|
||||
}
|
||||
}
|
||||
|
||||
// if this is a not a DMA request then we can fall back to any heap
|
||||
if (!(flags & MEM_REGION_FLAG_DMA_OK)) {
|
||||
for (uint8_t i=1; i<NUM_MEMORY_REGIONS; i++) {
|
||||
p = chHeapAllocAligned(&memory_regions[i].heap, size, alignment);
|
||||
if (p) {
|
||||
goto found;
|
||||
}
|
||||
}
|
||||
// try default heap
|
||||
p = chHeapAllocAligned(NULL, size, alignment);
|
||||
if (p) {
|
||||
goto found;
|
||||
}
|
||||
}
|
||||
|
||||
#if DMA_RESERVE_SIZE != 0
|
||||
// fall back to DMA reserve
|
||||
p = chHeapAllocAligned(&dma_reserve_heap, size, MIN_ALIGNMENT);
|
||||
p = chHeapAllocAligned(&dma_reserve_heap, size, alignment);
|
||||
if (p) {
|
||||
memset(p, 0, size);
|
||||
return p;
|
||||
}
|
||||
#endif
|
||||
|
||||
// failed
|
||||
return NULL;
|
||||
|
||||
found:
|
||||
memset(p, 0, size);
|
||||
return p;
|
||||
}
|
||||
/*
|
||||
allocate normal memory
|
||||
*/
|
||||
void *malloc(size_t size)
|
||||
{
|
||||
return malloc_flags(size, 0);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -159,27 +167,15 @@ void *malloc(size_t size)
|
||||
*/
|
||||
void *malloc_dma(size_t size)
|
||||
{
|
||||
#if defined(STM32H7)
|
||||
size = (size + (DMA_ALIGNMENT-1)) & ~(DMA_ALIGNMENT-1);
|
||||
#endif
|
||||
void *p;
|
||||
#if defined(DTCM_RAM_SIZE_KB)
|
||||
p = malloc_dtcm(size);
|
||||
#else
|
||||
// if we don't have DTCM memory then assume that main heap is DMA-safe
|
||||
p = chHeapAllocAligned(NULL, size, DMA_ALIGNMENT);
|
||||
#endif
|
||||
#if DMA_RESERVE_SIZE != 0
|
||||
if (p == NULL) {
|
||||
p = chHeapAllocAligned(&dma_reserve_heap, size, DMA_ALIGNMENT);
|
||||
}
|
||||
#endif
|
||||
return malloc_flags(size, MEM_REGION_FLAG_DMA_OK);
|
||||
}
|
||||
|
||||
if (p) {
|
||||
memset(p, 0, size);
|
||||
}
|
||||
osalDbgAssert((((uint32_t)p) & (DMA_ALIGNMENT-1)) == 0, "DMA alignment");
|
||||
return p;
|
||||
/*
|
||||
allocate fast memory
|
||||
*/
|
||||
void *malloc_fastmem(size_t size)
|
||||
{
|
||||
return malloc_flags(size, MEM_REGION_FLAG_FAST);
|
||||
}
|
||||
|
||||
void *calloc(size_t nmemb, size_t size)
|
||||
@ -200,31 +196,39 @@ void free(void *ptr)
|
||||
size_t mem_available(void)
|
||||
{
|
||||
size_t totalp = 0;
|
||||
|
||||
// get memory available on main heap
|
||||
chHeapStatus(NULL, &totalp, NULL);
|
||||
|
||||
// we also need to add in memory that is not yet allocated to the heap
|
||||
totalp += chCoreGetStatusX();
|
||||
|
||||
#if defined(CCM_RAM_SIZE_KB)
|
||||
size_t ccm_available = 0;
|
||||
chHeapStatus(&ccm_heap, &ccm_available, NULL);
|
||||
totalp += ccm_available;
|
||||
#endif
|
||||
|
||||
#if defined(DTCM_RAM_SIZE_KB)
|
||||
size_t dtcm_available = 0;
|
||||
chHeapStatus(&dtcm_heap, &dtcm_available, NULL);
|
||||
totalp += dtcm_available;
|
||||
#endif
|
||||
// now our own heaps
|
||||
for (uint8_t i=1; i<NUM_MEMORY_REGIONS; i++) {
|
||||
size_t available = 0;
|
||||
chHeapStatus(&memory_regions[i].heap, &available, NULL);
|
||||
totalp += available;
|
||||
}
|
||||
|
||||
#if DMA_RESERVE_SIZE != 0
|
||||
size_t reserve_available = 0;
|
||||
chHeapStatus(&dma_reserve_heap, &reserve_available, NULL);
|
||||
totalp += reserve_available;
|
||||
// and reserve DMA heap
|
||||
size_t available = 0;
|
||||
chHeapStatus(&dma_reserve_heap, &available, NULL);
|
||||
totalp += available;
|
||||
#endif
|
||||
|
||||
return totalp;
|
||||
}
|
||||
|
||||
#endif // CH_CFG_USE_HEAP
|
||||
|
||||
|
||||
/*
|
||||
flush all memory. Used in chSysHalt()
|
||||
*/
|
||||
void memory_flush_all(void)
|
||||
{
|
||||
for (uint8_t i=0; i<NUM_MEMORY_REGIONS; i++) {
|
||||
cacheBufferFlush(memory_regions[i].address, memory_regions[i].size);
|
||||
}
|
||||
}
|
||||
|
@ -95,14 +95,6 @@ void show_stack_usage(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
flush all memory. Used in chSysHalt()
|
||||
*/
|
||||
void memory_flush_all(void)
|
||||
{
|
||||
cacheBufferFlush(HAL_RAM_BASE_ADDRESS, HAL_RAM_SIZE_KB * 1024U);
|
||||
}
|
||||
|
||||
/*
|
||||
set the utc time
|
||||
*/
|
||||
|
@ -30,8 +30,8 @@ void show_stack_usage(void);
|
||||
|
||||
// allocation functions in malloc.c
|
||||
size_t mem_available(void);
|
||||
void *malloc_ccm(size_t size);
|
||||
void *malloc_dma(size_t size);
|
||||
void *malloc_fastmem(size_t size);
|
||||
|
||||
// flush all dcache
|
||||
void memory_flush_all(void);
|
||||
|
@ -25,12 +25,12 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFFF7E8,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 8,
|
||||
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 8, 1), # main memory, DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
ADC1_map = {
|
||||
|
@ -15,15 +15,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFF7A10,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 128,
|
||||
|
||||
# CCM ram address and size
|
||||
'CCM_BASE_ADDRESS' : 0x10000000,
|
||||
'CCM_RAM_SIZE_KB' : 64,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 128, 1), # main memory, DMA safe
|
||||
(0x10000000, 64, 2), # CCM memory, faster, but not DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
AltFunction_map = {
|
||||
|
@ -15,15 +15,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFF7A10,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 128,
|
||||
|
||||
# CCM ram address and size
|
||||
'CCM_BASE_ADDRESS' : 0x10000000,
|
||||
'CCM_RAM_SIZE_KB' : 64,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 128, 1), # main memory, DMA safe
|
||||
(0x10000000, 64, 2), # CCM memory, faster, but not DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -15,11 +15,12 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFF7A10,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 256
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 256, 1), # main memory, DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -15,15 +15,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFF7A10,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 192,
|
||||
|
||||
# CCM ram address and size
|
||||
'CCM_BASE_ADDRESS' : 0x10000000,
|
||||
'CCM_RAM_SIZE_KB' : 64,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 192, 1), # main memory, DMA safe
|
||||
(0x10000000, 64, 2), # CCM memory, faster, but not DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -28,15 +28,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FFF7A10,
|
||||
|
||||
# base address of main memory
|
||||
'RAM_BASE_ADDRESS' : 0x20000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 320,
|
||||
|
||||
# CCM ram address and size
|
||||
'CCM_BASE_ADDRESS' : 0x10000000,
|
||||
'CCM_RAM_SIZE_KB' : 64,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 320, 1), # main memory, DMA safe
|
||||
(0x10000000, 64, 1), # CCM memory, faster, not DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -15,17 +15,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FF0F420,
|
||||
|
||||
# base address of main memory. We use SRAM1/SRAM2 as main memory
|
||||
# for maximum speed (using the dcache). DMA will be done from DTCM
|
||||
# memory
|
||||
'RAM_BASE_ADDRESS' : 0x20010000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 256,
|
||||
|
||||
# DTCM ram address and size
|
||||
'DTCM_BASE_ADDRESS' : 0x20000000,
|
||||
'DTCM_RAM_SIZE_KB' : 64,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20010000, 256, 0), # main memory, not DMA safe
|
||||
(0x20000000, 64, 1), # DTCM memory, DMA safe
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -30,17 +30,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FF0F420,
|
||||
|
||||
# base address of main memory. We use SRAM1/SRAM2 as main memory
|
||||
# for maximum speed (using the dcache). DMA will be done from DTCM
|
||||
# memory
|
||||
'RAM_BASE_ADDRESS' : 0x20020000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 384,
|
||||
|
||||
# DTCM ram address and size
|
||||
'DTCM_BASE_ADDRESS' : 0x20000000,
|
||||
'DTCM_RAM_SIZE_KB' : 128,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20020000, 384, 0), # SRAM1/SRAM2
|
||||
(0x20000000, 128, 1), # DTCM, DMA
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -29,17 +29,13 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FF0F420,
|
||||
|
||||
# base address of main memory. We use SRAM1/SRAM2 as main memory
|
||||
# for maximum speed (using the dcache). DMA will be done from DTCM
|
||||
# memory
|
||||
'RAM_BASE_ADDRESS' : 0x20020000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 384,
|
||||
|
||||
# DTCM ram address and size
|
||||
'DTCM_BASE_ADDRESS' : 0x20000000,
|
||||
'DTCM_RAM_SIZE_KB' : 128,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x20020000, 384, 0), # SRAM1/SRAM2
|
||||
(0x20000000, 128, 1), # DTCM, DMA
|
||||
]
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
@ -14,17 +14,16 @@ mcu = {
|
||||
# location of MCU serial number
|
||||
'UDID_START' : 0x1FF1E800,
|
||||
|
||||
# base address of main memory. We use AXI SRAM as main memory
|
||||
# for maximum speed (using the dcache). DMA will be done from DTCM
|
||||
# memory. Other SRAM areas will be added later
|
||||
'RAM_BASE_ADDRESS' : 0x24000000,
|
||||
|
||||
# size of main memory
|
||||
'RAM_SIZE_KB' : 512,
|
||||
|
||||
# DTCM ram address and size
|
||||
# 'DTCM_BASE_ADDRESS' : 0x20000000,
|
||||
# 'DTCM_RAM_SIZE_KB' : 128,
|
||||
# ram map, as list of (address, size-kb, flags)
|
||||
# flags of 1 means DMA-capable
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
'RAM_MAP' : [
|
||||
(0x24000000, 512, 1), # AXI SRAM
|
||||
(0x30000000, 288, 1), # SRAM1, SRAM2, SRAM3
|
||||
(0x38000000, 64, 1), # SRAM4
|
||||
(0x00004000, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA
|
||||
]
|
||||
}
|
||||
|
||||
pincount = {
|
||||
|
@ -549,31 +549,18 @@ def write_mcu_config(f):
|
||||
f.write('#define BOARD_FLASH_SIZE %u\n' % flash_size)
|
||||
f.write('#define CRT1_AREAS_NUMBER 1\n')
|
||||
|
||||
# get core-coupled-memory if available (not be DMA capable)
|
||||
ccm_size = get_mcu_config('CCM_RAM_SIZE_KB')
|
||||
if ccm_size is not None:
|
||||
f.write('\n// core-coupled memory\n')
|
||||
f.write('#define CCM_RAM_SIZE_KB %u\n' % ccm_size)
|
||||
f.write('#define CCM_BASE_ADDRESS 0x%08x\n' % get_mcu_config('CCM_BASE_ADDRESS', True))
|
||||
|
||||
# get DTCM memory if available (DMA-capable with no cache flush/invalidate)
|
||||
dtcm_size = get_mcu_config('DTCM_RAM_SIZE_KB')
|
||||
if dtcm_size is not None:
|
||||
f.write('\n// DTCM memory\n')
|
||||
f.write('#define DTCM_RAM_SIZE_KB %u\n' % dtcm_size)
|
||||
f.write('#define DTCM_BASE_ADDRESS 0x%08x\n' % get_mcu_config('DTCM_BASE_ADDRESS', True))
|
||||
|
||||
flash_reserve_start = get_config(
|
||||
'FLASH_RESERVE_START_KB', default=16, type=int)
|
||||
f.write('\n// location of loaded firmware\n')
|
||||
f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024))
|
||||
f.write('\n')
|
||||
|
||||
ram_size_kb = get_mcu_config('RAM_SIZE_KB', True)
|
||||
ram_base_address = get_mcu_config('RAM_BASE_ADDRESS', True)
|
||||
f.write('// main memory size and address\n')
|
||||
f.write('#define HAL_RAM_SIZE_KB %uU\n' % ram_size_kb)
|
||||
f.write('#define HAL_RAM_BASE_ADDRESS 0x%08x\n' % ram_base_address)
|
||||
ram_map = get_mcu_config('RAM_MAP', True)
|
||||
f.write('// memory regions\n')
|
||||
regions = []
|
||||
for (address, size, flags) in ram_map:
|
||||
regions.append('{(void*)0x%08x, 0x%08x, 0x%02x, {}}' % (address, size*1024, flags))
|
||||
f.write('#define HAL_MEMORY_REGIONS %s\n' % ', '.join(regions))
|
||||
|
||||
f.write('\n// CPU serial number (12 bytes)\n')
|
||||
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
|
||||
@ -646,9 +633,8 @@ def write_ldscript(fname):
|
||||
# space to reserve for storage at end of flash
|
||||
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)
|
||||
|
||||
# ram size
|
||||
ram_size = get_mcu_config('RAM_SIZE_KB', True)
|
||||
ram_base = get_mcu_config('RAM_BASE_ADDRESS', True)
|
||||
# ram layout
|
||||
ram_map = get_mcu_config('RAM_MAP', True)
|
||||
|
||||
flash_base = 0x08000000 + flash_reserve_start * 1024
|
||||
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
|
||||
@ -663,7 +649,7 @@ MEMORY
|
||||
}
|
||||
|
||||
INCLUDE common.ld
|
||||
''' % (flash_base, flash_length, ram_base, ram_size))
|
||||
''' % (flash_base, flash_length, ram_map[0][0], ram_map[0][1]))
|
||||
|
||||
def copy_common_linkerscript(outdir, hwdef):
|
||||
dirpath = os.path.dirname(hwdef)
|
||||
|
Loading…
Reference in New Issue
Block a user