mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_ChibiOS: dynamically allocate memory for MAC Peripheral
This commit is contained in:
parent
1aff011e52
commit
e6b51df7cd
@ -39,6 +39,7 @@
|
||||
#define MEM_REGION_FLAG_DMA_OK 1
|
||||
#define MEM_REGION_FLAG_FAST 2
|
||||
#define MEM_REGION_FLAG_AXI_BUS 4
|
||||
#define MEM_REGION_FLAG_ETH_SAFE 8
|
||||
|
||||
#ifdef HAL_CHIBIOS_ENABLE_MALLOC_GUARD
|
||||
static mutex_t mem_mutex;
|
||||
@ -125,7 +126,7 @@ static void *malloc_flags(size_t size, uint32_t flags)
|
||||
if (size == 0) {
|
||||
return NULL;
|
||||
}
|
||||
const uint8_t dma_flags = (MEM_REGION_FLAG_DMA_OK | MEM_REGION_FLAG_AXI_BUS);
|
||||
const uint8_t dma_flags = (MEM_REGION_FLAG_DMA_OK | MEM_REGION_FLAG_AXI_BUS | MEM_REGION_FLAG_ETH_SAFE);
|
||||
const uint8_t alignment = (flags&dma_flags?DMA_ALIGNMENT:MIN_ALIGNMENT);
|
||||
void *p = NULL;
|
||||
uint8_t i;
|
||||
@ -159,6 +160,10 @@ static void *malloc_flags(size_t size, uint32_t flags)
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_FAST)) {
|
||||
continue;
|
||||
}
|
||||
if ((flags & MEM_REGION_FLAG_ETH_SAFE) &&
|
||||
!(memory_regions[i].flags & MEM_REGION_FLAG_ETH_SAFE)) {
|
||||
continue;
|
||||
}
|
||||
p = chHeapAllocAligned(&heaps[i], size, alignment);
|
||||
if (p) {
|
||||
goto found;
|
||||
@ -371,6 +376,18 @@ void *malloc_axi_sram(size_t size)
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
allocate memory for ethernet DMA
|
||||
*/
|
||||
void *malloc_eth_safe(size_t size)
|
||||
{
|
||||
#if defined(STM32H7)
|
||||
return malloc_flags(size, MEM_REGION_FLAG_ETH_SAFE);
|
||||
#else
|
||||
return NULL;
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
allocate fast memory
|
||||
*/
|
||||
|
@ -41,6 +41,7 @@ size_t mem_available(void);
|
||||
void *malloc_dma(size_t size);
|
||||
void *malloc_axi_sram(size_t size);
|
||||
void *malloc_fastmem(size_t size);
|
||||
void *malloc_eth_safe(size_t size);
|
||||
thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg);
|
||||
|
||||
struct memory_region {
|
||||
|
@ -65,10 +65,10 @@
|
||||
/*
|
||||
* Memory attributes settings.
|
||||
*/
|
||||
#define STM32_NOCACHE_ENABLE TRUE
|
||||
#define STM32_NOCACHE_MPU_REGION MPU_REGION_6
|
||||
#define STM32_NOCACHE_RBAR 0x30040000U
|
||||
#define STM32_NOCACHE_RASR MPU_RASR_SIZE_32K
|
||||
// #define STM32_NOCACHE_ENABLE TRUE
|
||||
#define STM32_NOCACHE_MPU_REGION_ETH MPU_REGION_6
|
||||
// #define STM32_NOCACHE_RBAR 0x30040000U
|
||||
// #define STM32_NOCACHE_RASR MPU_RASR_SIZE_32K
|
||||
|
||||
// enable memory protection on SRAM4, used for bdshot
|
||||
#define STM32_NOCACHE_MPU_REGION_1 MPU_REGION_5
|
||||
|
@ -26,21 +26,21 @@ mcu = {
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
# flags of 4 means memory can be used for SDMMC DMA
|
||||
'RAM_MAP' : [
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x30000000, 256, 8), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 512, 4), # AXI SRAM.
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
# alternative RAM_MAP needed for px4 bootloader compatibility
|
||||
'ALT_RAM_MAP' : [
|
||||
(0x24000000, 512, 4), # AXI SRAM.
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x30000000, 256, 8), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
@ -49,14 +49,13 @@ mcu = {
|
||||
# we can't use DTCM first for main firmware as some builds overflow the first segment
|
||||
'RAM_MAP_BOOTLOADER' : [
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x30000000, 256, 8), # SRAM1, SRAM2
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
#(0x30040000, 32, 0), # SRAM3.
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'ETHERNET_RAM' : (0x30040000, 32, 0), # SRAM3
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
'EXPECTED_CLOCKS' : [
|
||||
|
@ -29,10 +29,11 @@ mcu = {
|
||||
# flags of 2 means faster memory for CPU intensive work
|
||||
# flags of 4 means memory can be used for SDMMC DMA
|
||||
'RAM_MAP' : [
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x30000000, 256, 8), # SRAM1, SRAM2
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
@ -41,6 +42,7 @@ mcu = {
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 64, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x24000000, 128, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
@ -52,13 +54,13 @@ mcu = {
|
||||
# we can't use DTCM first for main firmware as some builds overflow the first segment
|
||||
'RAM_MAP_BOOTLOADER' : [
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x30000000, 256, 8), # SRAM1, SRAM2
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 8), # SRAM3.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'ETHERNET_RAM' : (0x30040000, 32, 0), # SRAM3
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
|
@ -936,7 +936,7 @@ class ChibiOSHWDef(object):
|
||||
f.write('#define CH_CFG_USE_MAILBOXES TRUE\n')
|
||||
f.write('#define HAL_USE_MAC TRUE\n')
|
||||
f.write('#define MAC_USE_EVENTS TRUE\n')
|
||||
f.write('#define STM32_NOCACHE_SRAM3 TRUE\n')
|
||||
f.write('#define STM32_ETH_BUFFERS_EXTERN\n')
|
||||
f.write('#define AP_NETWORKING_ENABLED TRUE\n')
|
||||
self.build_flags.append('USE_LWIP=yes')
|
||||
self.env_vars['WITH_NETWORKING'] = True
|
||||
@ -1328,13 +1328,6 @@ class ChibiOSHWDef(object):
|
||||
ext_flash_size = self.get_config('EXT_FLASH_SIZE_MB', default=0, type=int)
|
||||
int_flash_primary = self.get_config('INT_FLASH_PRIMARY', default=False, type=int)
|
||||
|
||||
ethernet_ram = self.get_mcu_config('ETHERNET_RAM', False)
|
||||
if ethernet_ram is None and self.env_vars['WITH_NETWORKING']:
|
||||
self.error("No ethernet ram defined in mcu config")
|
||||
elif self.env_vars['WITH_NETWORKING']:
|
||||
ethernet_ram_base = ethernet_ram[0]
|
||||
ethernet_ram_length = ethernet_ram[1]
|
||||
|
||||
if not args.bootloader:
|
||||
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
|
||||
ext_flash_length = ext_flash_size * 1024 - (ext_flash_reserve_start + ext_flash_reserve_end)
|
||||
@ -1399,15 +1392,6 @@ INCLUDE common.ld
|
||||
ram0_start, ram0_len,
|
||||
ram1_start, ram1_len,
|
||||
ram2_start, ram2_len))
|
||||
if self.env_vars['WITH_NETWORKING']:
|
||||
f.write('''
|
||||
/* Ethernet RAM */
|
||||
MEMORY
|
||||
{
|
||||
eth_ram : org = 0x%08x, len = %uK
|
||||
}
|
||||
INCLUDE common_eth.ld
|
||||
''' % (ethernet_ram_base, ethernet_ram_length))
|
||||
f.close()
|
||||
|
||||
def copy_common_linkerscript(self, outdir):
|
||||
|
Loading…
Reference in New Issue
Block a user