mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 02:44:00 -04:00
HAL_ChibiOS: added support for ALT_RAM_MAP on H7
for compatibility with the px4 H7 bootloader
This commit is contained in:
parent
262dd267ae
commit
091ca3f22e
@ -34,6 +34,16 @@ mcu = {
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
# alternative RAM_MAP needed for px4 bootloader compatibility
|
||||
'ALT_RAM_MAP' : [
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x30000000, 256, 0), # 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.
|
||||
(0x38000000, 64, 1), # SRAM4.
|
||||
],
|
||||
|
||||
# avoid a problem in the bootloader by making DTCM first. The DCache init
|
||||
# when using SRAM1 as primary memory gets a hard fault in bootloader
|
||||
# we can't use DTCM first for main firmware as some builds overflow the first segment
|
||||
|
@ -709,6 +709,9 @@ def get_ram_map():
|
||||
ram_map = get_mcu_config('RAM_MAP_EXTERNAL_FLASH', False)
|
||||
if ram_map is not None:
|
||||
return ram_map
|
||||
elif int(env_vars.get('USE_ALT_RAM_MAP',0)) == '1':
|
||||
print("Using ALT_RAM_MAP")
|
||||
return get_mcu_config('ALT_RAM_MAP', True)
|
||||
return get_mcu_config('RAM_MAP', True)
|
||||
|
||||
def get_flash_pages_sizes():
|
||||
|
Loading…
Reference in New Issue
Block a user