Skip to content

Commit

Permalink
HAL_ChibiOS: avoid an issue with DCache init on H743
Browse files Browse the repository at this point in the history
this fixes an issue found by Andy Piper where the H743 bootloader gets
a hard fault in the DCache enable code when SRAM1 is primary memory.

This is the simplest fix I could think of, and avoids the problem by
making DTCM the first segment in the bootloader.

Note that we can't use DTCM as first segment for main firmware since
we went to double precision EKF as the static variables don't fit
  • Loading branch information
tridge committed Sep 6, 2021
1 parent 948a001 commit b77580f
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 2 deletions.
12 changes: 12 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,18 @@
(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
'RAM_MAP_BOOTLOADER' : [
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
(0x30000000, 256, 0), # 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.
(0x38000000, 64, 1), # SRAM4.
],

'EXPECTED_CLOCK' : 400000000,

# this MCU has M7 instructions and hardware double precision
Expand Down
13 changes: 11 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Original file line number Diff line number Diff line change
Expand Up @@ -671,6 +671,15 @@ def has_sdcard_spi():
return False


def get_ram_map():
'''get RAM_MAP. May be different for bootloader'''
if args.bootloader:
ram_map = get_mcu_config('RAM_MAP_BOOTLOADER', False)
if ram_map is not None:
return ram_map
return get_mcu_config('RAM_MAP', True)


def write_mcu_config(f):
'''write MCU config defines'''
f.write('// MCU type (ChibiOS define)\n')
Expand Down Expand Up @@ -788,7 +797,7 @@ def write_mcu_config(f):
f.write('#define APP_START_OFFSET_KB %u\n' % get_config('APP_START_OFFSET_KB', default=0, type=int))
f.write('\n')

ram_map = get_mcu_config('RAM_MAP', True)
ram_map = get_ram_map()
f.write('// memory regions\n')
regions = []
total_memory = 0
Expand Down Expand Up @@ -930,7 +939,7 @@ def write_ldscript(fname):
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)

# ram layout
ram_map = get_mcu_config('RAM_MAP', True)
ram_map = get_ram_map()
instruction_ram = get_mcu_config('INSTRUCTION_RAM', False)

flash_base = 0x08000000 + flash_reserve_start * 1024
Expand Down

0 comments on commit b77580f

Please sign in to comment.