AP_HAL_ChibiOS: Allow custom linker script, change extflash linker script

This commit is contained in:
Martin Luessi 2023-06-15 14:36:51 -07:00 committed by Randy Mackay
parent ee10f447e0
commit 0eb4afaeec
1 changed files with 16 additions and 22 deletions

View File

@ -1292,34 +1292,22 @@ MEMORY
INCLUDE common.ld INCLUDE common.ld
''' % (flash_base, flash_length, ram0_start, ram0_len)) ''' % (flash_base, flash_length, ram0_start, ram0_len))
elif int_flash_primary: else:
if ext_flash_size > 32: if ext_flash_size > 32:
error("We only support 24bit addressing over external flash") error("We only support 24bit addressing over external flash")
env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1 env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1
f.write('''/* generated ldscript.ld */ build_flags.append('COPY_VECTORS_TO_RAM=yes')
MEMORY
{
flash : org = 0x%08x, len = %uK
ext_flash : org = 0x%08x, len = %uK
ram0 : org = 0x%08x, len = %u
}
INCLUDE common_mixf.ld
''' % (flash_base, flash_length, ext_flash_base, ext_flash_length, ram0_start, ram0_len))
else:
self.env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 1
self.build_flags.append('COPY_VECTORS_TO_RAM=yes')
f.write('''/* generated ldscript.ld */ f.write('''/* generated ldscript.ld */
MEMORY MEMORY
{ {
default_flash (rx) : org = 0x%08x, len = %uK default_flash (rx) : org = 0x%08x, len = %uK
instram : org = 0x%08x, len = %uK instram : org = 0x%08x, len = %uK
ram0 : org = 0x%08x, len = %u ram0 : org = 0x%08x, len = %u
ram1 : org = 0x%08x, len = %u flashram : org = 0x%08x, len = %u
ram2 : org = 0x%08x, len = %u dataram : org = 0x%08x, len = %u
} }
INCLUDE common_extf.ld INCLUDE common.ld
''' % (ext_flash_base, ext_flash_length, ''' % (ext_flash_base, ext_flash_length,
instruction_ram_base, instruction_ram_length, instruction_ram_base, instruction_ram_length,
ram0_start, ram0_len, ram0_start, ram0_len,
@ -1328,12 +1316,18 @@ INCLUDE common_extf.ld
def copy_common_linkerscript(outdir): def copy_common_linkerscript(outdir):
dirpath = os.path.dirname(os.path.realpath(__file__)) dirpath = os.path.dirname(os.path.realpath(__file__))
if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int) or args.bootloader:
shutil.copy(os.path.join(dirpath, "../common/common.ld"), if args.bootloader:
os.path.join(outdir, "common.ld")) linker = 'common.ld'
else: else:
shutil.copy(os.path.join(dirpath, "../common/common_extf.ld"), linker = get_mcu_config('LINKER_CONFIG')
os.path.join(outdir, "common_extf.ld")) if linker is None:
if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int):
linker = 'common.ld'
else:
linker = 'common_extf.ld'
shutil.copy(os.path.join(dirpath, "../common", linker),
os.path.join(outdir, "common.ld"))
def get_USB_IDs(): def get_USB_IDs():
'''return tuple of USB VID/PID''' '''return tuple of USB VID/PID'''