mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Copy vector table to RAM if external flash is primary
This commit is contained in:
parent
84ccd046c6
commit
0c93800ec1
|
@ -264,6 +264,10 @@ endif
|
|||
# Define ASM defines here
|
||||
UADEFS =
|
||||
|
||||
ifeq ($(COPY_VECTORS_TO_RAM),yes)
|
||||
UADEFS += -DCRT0_INIT_VECTORS=1
|
||||
endif
|
||||
|
||||
# List all user directories here
|
||||
UINCDIR =
|
||||
|
||||
|
|
|
@ -1363,6 +1363,7 @@ 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 */
|
||||
MEMORY
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue