AP_HAL_ChibiOS: RAM initialization and linker files changes for external flash targets

This commit is contained in:
Martin Luessi 2023-06-16 15:46:30 -07:00 committed by Peter Barker
parent 18e4593bcd
commit 703d581f93
3 changed files with 34 additions and 28 deletions

View File

@ -20,16 +20,16 @@
*/
/* RAM region to be used for fast code. */
REGION_ALIAS("FASTCODE_RAM", ram1)
REGION_ALIAS("FASTCODE_RAM", flashram)
/* stack areas are configured to be in AXI RAM (ram1) to ensure the SSBL will load the image */
/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts*/
REGION_ALIAS("MAIN_STACK_RAM", ram1);
REGION_ALIAS("MAIN_STACK_RAM", flashram);
/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram1);
REGION_ALIAS("PROCESS_STACK_RAM", flashram);
/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
@ -45,19 +45,19 @@ __ram0_size__ = LENGTH(ram0);
__ram0_end__ = __ram0_start__ + __ram0_size__;
/* AXI */
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_start__ = ORIGIN(flashram);
__ram1_size__ = LENGTH(flashram);
__ram1_end__ = __ram1_start__ + __ram1_size__;
/* DTCM */
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_start__ = ORIGIN(dataram);
__ram2_size__ = LENGTH(dataram);
__ram2_end__ = __ram2_start__ + __ram2_size__;
/* ITCM */
__instram_start__ = ORIGIN(instram);
__instram_size__ = LENGTH(instram);
__instram_end__ = __instram_start__ + __instram_size__;
__ram3_start__ = ORIGIN(instram);
__ram3_size__ = LENGTH(instram);
__ram3_end__ = __ram3_start__ + __ram3_size__;
ENTRY(Reset_Handler)
@ -95,8 +95,8 @@ SECTIONS
.fastramfunc : ALIGN(4) SUBALIGN(4)
{
. = ALIGN(4);
__instram_init_text__ = LOADADDR(.fastramfunc);
__instram_init__ = .;
__ram3_init_text__ = LOADADDR(.fastramfunc);
__ram3_init__ = .;
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
/* performance critical sections of ChibiOS */
@ -123,9 +123,19 @@ SECTIONS
*libstdc++_nano.a:(.text* .rodata*)*/
*(.fastramfunc)
. = ALIGN(4);
__instram_end__ = .;
} > instram AT > default_flash
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
. = ALIGN(4);
__ram3_noinit__ = .;
. = ALIGN(4);
__ram3_free__ = .;
. = ALIGN(4);
} > instram
/* FLASH_RAM area is primarily used for RAM-based code and data, 256k allocation on H7 */
.ramfunc : ALIGN(4) SUBALIGN(4)
{
@ -166,7 +176,7 @@ SECTIONS
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
*(.ramfunc*)
. = ALIGN(4);
} > ram1 AT > default_flash
} > flashram AT > default_flash
.ram1 (NOLOAD) : ALIGN(4)
{
@ -177,7 +187,7 @@ SECTIONS
*(.ram1*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
} > flashram
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
.ramdata : ALIGN(4)
@ -205,7 +215,7 @@ SECTIONS
*libm.a:*(.rodata*)
*(.ramdata*)
. = ALIGN(4);
} > ram2 AT > default_flash
} > dataram AT > default_flash
.ram2 (NOLOAD) : ALIGN(4)
{
@ -216,7 +226,7 @@ SECTIONS
*(.ram2*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
} > dataram
.text : ALIGN(4) SUBALIGN(4)
{

View File

@ -63,10 +63,9 @@ __ram2_size__ = LENGTH(dataram);
__ram2_end__ = __ram2_start__ + __ram2_size__;
/* ITCM for RAM functions */
__instram_start__ = ORIGIN(instram);
__instram_size__ = LENGTH(instram);
__instram_end__ = __instram_start__ + __instram_size__;
__ram3_start__ = ORIGIN(instram);
__ram3_size__ = LENGTH(instram);
__ram3_end__ = __ram3_start__ + __ram3_size__;
ENTRY(Reset_Handler)
@ -104,8 +103,8 @@ SECTIONS
.fastramfunc : ALIGN(4) SUBALIGN(4)
{
. = ALIGN(4);
__instram_init_text__ = LOADADDR(.fastramfunc);
__instram_init__ = .;
__ram3_init_text__ = LOADADDR(.fastramfunc);
__ram3_init__ = .;
/* performance critical sections of ChibiOS */
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o) *libch.a:ch*.*(.text*)
@ -133,7 +132,6 @@ SECTIONS
*libstdc++_nano.a:(.text* .rodata*)*/
*(.fastramfunc)
. = ALIGN(4);
__instram_end__ = .;
} > instram AT > default_flash
.ram3 (NOLOAD) : ALIGN(4)

View File

@ -966,14 +966,12 @@ def write_mcu_config(f):
env_vars['EXT_FLASH_SIZE_MB'] = get_config('EXT_FLASH_SIZE_MB', default=0, type=int)
if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader:
f.write('#define CRT1_AREAS_NUMBER 3\n')
f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM
f.write('#define CRT0_AREAS_NUMBER 4\n')
f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n')
f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n')
f.write('#define PORT_IRQ_ATTRIBUTES __FASTRAMFUNC__\n')
else:
f.write('#define CRT1_AREAS_NUMBER 1\n')
f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n')
f.write('#define CRT0_AREAS_NUMBER 1\n')
storage_flash_page = get_storage_flash_page()
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)