AP_HAL_ChibiOS: clean up linker map on H730 and H750
use regular ChibiOS RAM areas for RAM functions exclude board.o from RAM functions and add some comments use separate linker script for H750 use correct RAM area for process stack on H750/H743 update EXCLUDE items to put __early_init in flash on H730 and H750 optimize H730 ramfunc usage
This commit is contained in:
parent
8b8f5eadd6
commit
798fc05ba8
@ -160,7 +160,7 @@ define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 2
|
||||
|
||||
IMU Invensense SPI:icm42688 ROTATION_YAW_90
|
||||
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_90
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# one BARO
|
||||
|
@ -228,6 +228,9 @@ static void stm32_gpio_init(void) {
|
||||
* @brief Early initialization code.
|
||||
* @details This initialization must be performed just after stack setup
|
||||
* and before any other initialization.
|
||||
*
|
||||
* You must not rely on: 1) BSS variables being cleared 2) DATA Variables being initialized 3) RAM functions to be in RAM
|
||||
* You can rely on: 1) const variables or tables 2) flash code 3) automatic variables
|
||||
*/
|
||||
void __early_init(void) {
|
||||
#if !defined(STM32F1)
|
||||
|
@ -20,16 +20,17 @@
|
||||
*/
|
||||
|
||||
/* 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 */
|
||||
/* stack areas are configured to be in AXI RAM (ram0) to ensure the SSBL will load the image.
|
||||
better performance can be achieved by using DTCM for stack but this will break SSBL. */
|
||||
/* 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);
|
||||
@ -40,24 +41,31 @@ REGION_ALIAS("BSS_RAM", ram0);
|
||||
/* RAM region to be used for the default heap.*/
|
||||
REGION_ALIAS("HEAP_RAM", ram0);
|
||||
|
||||
/* The ChibiOS crt code looks at all of the __ramx_xxxx__ sections
|
||||
it will copy from __ramx_init_text__ to __ramx_init__ until __ramx_clear__ is hit
|
||||
it will then clear from __ramx_clear__ to __ramx_no_init__
|
||||
the number of areas actually used is determined by CRT0_AREAS_NUMBER
|
||||
*/
|
||||
|
||||
/* AXI */
|
||||
__ram0_start__ = ORIGIN(ram0);
|
||||
__ram0_size__ = LENGTH(ram0);
|
||||
__ram0_end__ = __ram0_start__ + __ram0_size__;
|
||||
|
||||
/* AXI */
|
||||
__ram1_start__ = ORIGIN(ram1);
|
||||
__ram1_size__ = LENGTH(ram1);
|
||||
/* AXI for RAM functions */
|
||||
__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__;
|
||||
/* ITCM for RAM functions */
|
||||
__ram3_start__ = ORIGIN(instram);
|
||||
__ram3_size__ = LENGTH(instram);
|
||||
__ram3_end__ = __ram3_start__ + __ram3_size__;
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
@ -91,10 +99,10 @@ 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)
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *board.o)
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.text*)
|
||||
*libch.a:nvic.*(.text*)
|
||||
@ -119,9 +127,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)
|
||||
{
|
||||
@ -129,7 +147,7 @@ SECTIONS
|
||||
__ram1_init_text__ = LOADADDR(.ramfunc);
|
||||
__ram1_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *board.o)
|
||||
/*libch.a:*(.text* .rodata* .glue_7t .glue_7 .gcc*)*/
|
||||
/* a selection of larger performance critical functions */
|
||||
lib/lib*.a:*Filter.*(.text* .rodata*)
|
||||
@ -162,7 +180,7 @@ SECTIONS
|
||||
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
|
||||
*(.ramfunc*)
|
||||
. = ALIGN(4);
|
||||
} > ram1 AT > default_flash
|
||||
} > flashram AT > default_flash
|
||||
|
||||
.ram1 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
@ -170,10 +188,10 @@ SECTIONS
|
||||
__ram1_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram1_noinit__ = .;
|
||||
*(.ram1*)
|
||||
. = ALIGN(4);
|
||||
__ram1_free__ = .;
|
||||
} > ram1
|
||||
. = ALIGN(4);
|
||||
} > flashram
|
||||
|
||||
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
|
||||
.ramdata : ALIGN(4)
|
||||
@ -182,7 +200,7 @@ SECTIONS
|
||||
__ram2_init_text__ = LOADADDR(.ramdata);
|
||||
__ram2_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o *board.o)
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.rodata*)
|
||||
*libch.a:nvic.*(.rodata*)
|
||||
@ -201,7 +219,7 @@ SECTIONS
|
||||
*libm.a:*(.rodata*)
|
||||
*(.ramdata*)
|
||||
. = ALIGN(4);
|
||||
} > ram2 AT > default_flash
|
||||
} > dataram AT > default_flash
|
||||
|
||||
.ram2 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
@ -209,10 +227,10 @@ SECTIONS
|
||||
__ram2_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram2_noinit__ = .;
|
||||
*(.ram2*)
|
||||
. = ALIGN(4);
|
||||
__ram2_free__ = .;
|
||||
} > ram2
|
||||
. = ALIGN(4);
|
||||
} > dataram
|
||||
|
||||
.text : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
@ -220,6 +238,8 @@ SECTIONS
|
||||
positive isn't found by the bootloader (eg. ROMFS) */
|
||||
KEEP(*libch.a:vectors.o);
|
||||
KEEP(*libch.a:crt0_v7m.o);
|
||||
KEEP(*libch.a:crt1.o);
|
||||
KEEP(*libch.a:board.o);
|
||||
KEEP(*(.apsec_data));
|
||||
KEEP(*(.app_descriptor));
|
||||
*(.text)
|
||||
|
@ -20,9 +20,10 @@
|
||||
*/
|
||||
|
||||
/* 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 (ram0) to ensure the SSBL will load the image */
|
||||
/* stack areas are configured to be in AXI RAM (ram0) to ensure the SSBL will load the image.
|
||||
better performance can be achieved by using DTCM for stack but this will break SSBL. */
|
||||
/* RAM region to be used for Main stack. This stack accommodates the processing
|
||||
of all exceptions and interrupts*/
|
||||
REGION_ALIAS("MAIN_STACK_RAM", ram0);
|
||||
@ -40,25 +41,31 @@ REGION_ALIAS("BSS_RAM", ram0);
|
||||
/* RAM region to be used for the default heap.*/
|
||||
REGION_ALIAS("HEAP_RAM", ram0);
|
||||
|
||||
/* The ChibiOS crt code looks at all of the __ramx_xxxx__ sections
|
||||
it will copy from __ramx_init_text__ to __ramx_init__ until __ramx_clear__ is hit
|
||||
it will then clear from __ramx_clear__ to __ramx_no_init__
|
||||
the number of areas actually used is determined by CRT0_AREAS_NUMBER
|
||||
*/
|
||||
|
||||
/* AXI */
|
||||
__ram0_start__ = ORIGIN(ram0);
|
||||
__ram0_size__ = LENGTH(ram0);
|
||||
__ram0_end__ = __ram0_start__ + __ram0_size__;
|
||||
|
||||
/* AXI */
|
||||
__ram1_start__ = ORIGIN(ram1);
|
||||
__ram1_size__ = LENGTH(ram1);
|
||||
/* AXI for RAM functions */
|
||||
__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__;
|
||||
/* ITCM for RAM functions */
|
||||
__ram3_start__ = ORIGIN(instram);
|
||||
__ram3_size__ = LENGTH(instram);
|
||||
__ram3_end__ = __ram3_start__ + __ram3_size__;
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
@ -88,16 +95,15 @@ SECTIONS
|
||||
__fini_array_end__ = .;
|
||||
} > default_flash
|
||||
|
||||
/* INSTRUCTION_RAM area is fast-access ITCM used for RAM-based code, 64k on H7 */
|
||||
/* INSTRUCTION_RAM area is fast-access ITCM used for RAM-based code, 63k on H730 */
|
||||
.fastramfunc : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__instram_init_text__ = LOADADDR(.fastramfunc);
|
||||
__instram_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
__ram3_init_text__ = LOADADDR(.fastramfunc);
|
||||
__ram3_init__ = .;
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.text*)
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o) *libch.a:ch*.*(.text*)
|
||||
*libch.a:nvic.*(.text*)
|
||||
*libch.a:bouncebuffer.*(.text*)
|
||||
*libch.a:stm32_util.*(.text*)
|
||||
@ -105,12 +111,15 @@ SECTIONS
|
||||
*libch.a:memstreams.*(.text*)
|
||||
*libch.a:malloc.*(.text*)
|
||||
*libch.a:hrt.*(.text*)
|
||||
*libch.a:hal*.*(.text*)
|
||||
EXCLUDE_FILE (*hal_lld.o) *libch.a:hal*.*(.text*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.text*)
|
||||
lib/lib*.a:AP_Math.*(.text*)
|
||||
lib/lib*.a:vector3.*(.text*)
|
||||
lib/lib*.a:matrix3.*(.text*)
|
||||
/* the attitude controller runs at loop rate and needs to be optimized */
|
||||
lib/lib*.a:AC_AttitudeControl*.*(.text*)
|
||||
lib/lib*.a:AC_PID*.*(.text*)
|
||||
/* only used on debug builds */
|
||||
/**libg_nano.a:*memset*(.text*)
|
||||
*libg_nano.a:*memcpy*(.text*)*/
|
||||
@ -120,54 +129,47 @@ 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)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram1_init_text__ = LOADADDR(.ramfunc);
|
||||
__ram1_init__ = .;
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
/*libch.a:*(.text* .rodata* .glue_7t .glue_7 .gcc*)*/
|
||||
/* a selection of larger performance critical functions */
|
||||
lib/lib*.a:*Filter.*(.text* .rodata*)
|
||||
lib/lib*.a:*Filter2p.*(.text* .rodata*)
|
||||
/*
|
||||
lib/lib*.a:SPIDevice.*(.text* .rodata*)
|
||||
lib/lib*.a:I2CDevice.*(.text* .rodata*)
|
||||
*/
|
||||
/*lib/lib*.a:Util.*(.text* .rodata*)
|
||||
lib/lib*.a:LowPassFilter2p.*(.text* .rodata*)
|
||||
lib/lib*.a:LowPassFilter.*(.text* .rodata*)
|
||||
lib/lib*.a:NotchFilter.*(.text* .rodata*)
|
||||
lib/lib*.a:HarmonicNotchFilter.*(.text* .rodata*)
|
||||
lib/lib*.a:Util.*(.text* .rodata*)
|
||||
lib/lib*.a:Device.*(.text* .rodata*)
|
||||
lib/lib*.a:Scheduler.*(.text* .rodata*)
|
||||
lib/lib*.a:RingBuffer.*(.text* .rodata*)
|
||||
lib/lib*.a:shared_dma.*(.text* .rodata*)
|
||||
lib/lib*.a:crc.*(.text* .rodata*)*/
|
||||
lib/lib*.a:crc.*(.text* .rodata*)
|
||||
lib/lib*.a:matrixN.*(.text* .rodata*)
|
||||
lib/lib*.a:matrix_alg.*(.text* .rodata*)
|
||||
/*
|
||||
lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*)
|
||||
lib/lib*.a:EKF*.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_Compass_Backend.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol_Backend.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol_CRSF.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCTelemetry.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_CRSF_Telem.*(.text* .rodata*)
|
||||
*/
|
||||
lib/lib*.a:vector2.*(.text* .rodata*)
|
||||
lib/lib*.a:quaternion.*(.text* .rodata*)
|
||||
lib/lib*.a:polygon.*(.text* .rodata*)
|
||||
lib/lib*.a:flash.*(.text* .rodata*) /* flash ops in RAM so that both banks can be erased */
|
||||
/* uncomment these to test CPUInfo in FLASH_RAM */
|
||||
/*Tools/CPUInfo/CPUInfo.*(.text* .rodata*)
|
||||
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
|
||||
*(.ramfunc*)
|
||||
. = ALIGN(4);
|
||||
} > ram1 AT > default_flash
|
||||
} > flashram AT > default_flash
|
||||
|
||||
.ram1 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
@ -175,19 +177,20 @@ SECTIONS
|
||||
__ram1_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram1_noinit__ = .;
|
||||
*(.ram1*)
|
||||
. = ALIGN(4);
|
||||
__ram1_free__ = .;
|
||||
} > ram1
|
||||
. = ALIGN(4);
|
||||
} > flashram
|
||||
|
||||
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
|
||||
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables. 64k on H730 */
|
||||
.ramdata : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram2_init_text__ = LOADADDR(.ramdata);
|
||||
__ram2_init__ = .;
|
||||
/* performance critical sections of ChibiOS */
|
||||
/* ChibiOS won't boot unless these are excluded */
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
|
||||
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o) *libch.a:ch*.*(.rodata*)
|
||||
/* performance critical sections of ChibiOS */
|
||||
*libch.a:ch*.*(.rodata*)
|
||||
*libch.a:nvic.*(.rodata*)
|
||||
@ -197,16 +200,28 @@ SECTIONS
|
||||
*libch.a:memstreams.*(.rodata*)
|
||||
*libch.a:malloc.*(.rodata*)
|
||||
*libch.a:hrt.*(.rodata*)
|
||||
*libch.a:hal*.*(.rodata*)
|
||||
EXCLUDE_FILE (*hal_lld.o) *libch.a:hal*.*(.rodata*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.rodata*)
|
||||
lib/lib*.a:AP_Math.*(.rodata*)
|
||||
lib/lib*.a:vector3.*(.rodata*)
|
||||
lib/lib*.a:matrix3.*(.rodata*)
|
||||
*libm.a:*(.rodata*)
|
||||
lib/lib*.a:AC_AttitudeControl*.*(.rodata*)
|
||||
lib/lib*.a:AC_PID*.*(.rodata*)
|
||||
/* fill up remaining DTCM with other hot functions, esp EKF */
|
||||
lib/lib*.a:ModeFilter.*(.text* .rodata*)
|
||||
lib/lib*.a:DerivativeFilter.*(.text* .rodata*)
|
||||
lib/lib*.a:SlewLimiter.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF3_core.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF3_Outputs.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF3_Measurements.*(.text* .rodata*)
|
||||
lib/lib*.a:EKF*.*(.text* .rodata*)
|
||||
/* flash ops in RAM so that both banks can be erased */
|
||||
lib/lib*.a:flash.*(.text* .rodata*)
|
||||
*(.ramdata*)
|
||||
. = ALIGN(4);
|
||||
} > ram2 AT > default_flash
|
||||
} > dataram AT > default_flash
|
||||
|
||||
.ram2 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
@ -214,10 +229,10 @@ SECTIONS
|
||||
__ram2_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram2_noinit__ = .;
|
||||
*(.ram2*)
|
||||
. = ALIGN(4);
|
||||
__ram2_free__ = .;
|
||||
} > ram2
|
||||
. = ALIGN(4);
|
||||
} > dataram
|
||||
|
||||
.text : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
@ -225,6 +240,8 @@ SECTIONS
|
||||
positive isn't found by the bootloader (eg. ROMFS) */
|
||||
KEEP(*libch.a:vectors.o);
|
||||
KEEP(*libch.a:crt0_v7m.o);
|
||||
KEEP(*libch.a:crt1.o);
|
||||
KEEP(*libch.a:board.o);
|
||||
KEEP(*(.app_descriptor));
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
|
368
libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld
Normal file
368
libraries/AP_HAL_ChibiOS/hwdef/common/common_extf_h750.ld
Normal file
@ -0,0 +1,368 @@
|
||||
/*
|
||||
ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
||||
*/
|
||||
|
||||
/*
|
||||
this file is included by the board specific ldscript.ld which is
|
||||
generated from hwdef.dat
|
||||
*/
|
||||
|
||||
/* RAM region to be used for fast code. */
|
||||
REGION_ALIAS("FASTCODE_RAM", flashram)
|
||||
|
||||
/* stack areas are configured to be in AXI RAM (ram0) to ensure the SSBL will load the image.
|
||||
better performance can be achieved by using DTCM for stack but this will break SSBL. */
|
||||
/* RAM region to be used for Main stack. This stack accommodates the processing
|
||||
of all exceptions and interrupts*/
|
||||
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", flashram);
|
||||
|
||||
/* RAM region to be used for data segment.*/
|
||||
REGION_ALIAS("DATA_RAM", ram0);
|
||||
|
||||
/* RAM region to be used for BSS segment.*/
|
||||
REGION_ALIAS("BSS_RAM", ram0);
|
||||
|
||||
/* RAM region to be used for the default heap.*/
|
||||
REGION_ALIAS("HEAP_RAM", ram0);
|
||||
|
||||
/* The ChibiOS crt code looks at all of the __ramx_xxxx__ sections
|
||||
it will copy from __ramx_init_text__ to __ramx_init__ until __ramx_clear__ is hit
|
||||
it will then clear from __ramx_clear__ to __ramx_no_init__
|
||||
the number of areas actually used is determined by CRT0_AREAS_NUMBER
|
||||
*/
|
||||
|
||||
/* AXI */
|
||||
__ram0_start__ = ORIGIN(ram0);
|
||||
__ram0_size__ = LENGTH(ram0);
|
||||
__ram0_end__ = __ram0_start__ + __ram0_size__;
|
||||
|
||||
/* AXI for RAM functions */
|
||||
__ram1_start__ = ORIGIN(flashram);
|
||||
__ram1_size__ = LENGTH(flashram);
|
||||
__ram1_end__ = __ram1_start__ + __ram1_size__;
|
||||
|
||||
/* DTCM */
|
||||
__ram2_start__ = ORIGIN(dataram);
|
||||
__ram2_size__ = LENGTH(dataram);
|
||||
__ram2_end__ = __ram2_start__ + __ram2_size__;
|
||||
|
||||
/* ITCM for RAM functions */
|
||||
__ram3_start__ = ORIGIN(instram);
|
||||
__ram3_size__ = LENGTH(instram);
|
||||
__ram3_end__ = __ram3_start__ + __ram3_size__;
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
. = 0;
|
||||
_text = .;
|
||||
|
||||
startup : ALIGN(16) SUBALIGN(16)
|
||||
{
|
||||
KEEP(*(.vectors))
|
||||
} > default_flash
|
||||
|
||||
constructors : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
__init_array_base__ = .;
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
__init_array_end__ = .;
|
||||
} > default_flash
|
||||
|
||||
destructors : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
__fini_array_base__ = .;
|
||||
KEEP(*(.fini_array))
|
||||
KEEP(*(SORT(.fini_array.*)))
|
||||
__fini_array_end__ = .;
|
||||
} > default_flash
|
||||
|
||||
/* INSTRUCTION_RAM area is fast-access ITCM used for RAM-based code, 64k on H7 */
|
||||
.fastramfunc : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__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*)
|
||||
*libch.a:nvic.*(.text*)
|
||||
*libch.a:bouncebuffer.*(.text*)
|
||||
*libch.a:stm32_util.*(.text*)
|
||||
*libch.a:stm32_dma.*(.text*)
|
||||
*libch.a:memstreams.*(.text*)
|
||||
*libch.a:malloc.*(.text*)
|
||||
*libch.a:hrt.*(.text*)
|
||||
EXCLUDE_FILE (*hal_lld.o) *libch.a:hal*.*(.text*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.text*)
|
||||
lib/lib*.a:AP_Math.*(.text*)
|
||||
lib/lib*.a:vector3.*(.text*)
|
||||
lib/lib*.a:matrix3.*(.text*)
|
||||
/* only used on debug builds */
|
||||
/**libg_nano.a:*memset*(.text*)
|
||||
*libg_nano.a:*memcpy*(.text*)*/
|
||||
*libm.a:*(.text*)
|
||||
/* For some reason boards won't boot if libc is in RAM, but will with debug on */
|
||||
/**libc_nano.a:*(.text* .rodata*)
|
||||
*libstdc++_nano.a:(.text* .rodata*)*/
|
||||
*(.fastramfunc)
|
||||
. = ALIGN(4);
|
||||
} > 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)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram1_init_text__ = LOADADDR(.ramfunc);
|
||||
__ram1_init__ = .;
|
||||
/* a selection of larger performance critical functions */
|
||||
lib/lib*.a:*Filter.*(.text* .rodata*)
|
||||
lib/lib*.a:*Filter2p.*(.text* .rodata*)
|
||||
lib/lib*.a:SPIDevice.*(.text* .rodata*)
|
||||
lib/lib*.a:I2CDevice.*(.text* .rodata*)
|
||||
lib/lib*.a:Util.*(.text* .rodata*)
|
||||
lib/lib*.a:Device.*(.text* .rodata*)
|
||||
lib/lib*.a:Scheduler.*(.text* .rodata*)
|
||||
lib/lib*.a:shared_dma.*(.text* .rodata*)
|
||||
lib/lib*.a:RingBuffer.*(.text* .rodata*)
|
||||
lib/lib*.a:crc.*(.text* .rodata*)
|
||||
lib/lib*.a:matrixN.*(.text* .rodata*)
|
||||
lib/lib*.a:matrix_alg.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*)
|
||||
lib/lib*.a:EKF*.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_Compass_Backend.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol_Backend.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCProtocol_CRSF.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_RCTelemetry.*(.text* .rodata*)
|
||||
lib/lib*.a:AP_CRSF_Telem.*(.text* .rodata*)
|
||||
lib/lib*.a:vector2.*(.text* .rodata*)
|
||||
lib/lib*.a:quaternion.*(.text* .rodata*)
|
||||
lib/lib*.a:polygon.*(.text* .rodata*)
|
||||
lib/lib*.a:flash.*(.text* .rodata*) /* flash ops in RAM so that both banks can be erased */
|
||||
/* uncomment these to test CPUInfo in FLASH_RAM */
|
||||
/*Tools/CPUInfo/CPUInfo.*(.text* .rodata*)
|
||||
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
|
||||
*(.ramfunc*)
|
||||
. = ALIGN(4);
|
||||
} > flashram AT > default_flash
|
||||
|
||||
.ram1 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram1_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram1_noinit__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram1_free__ = .;
|
||||
. = ALIGN(4);
|
||||
} > flashram
|
||||
|
||||
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
|
||||
.ramdata : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram2_init_text__ = LOADADDR(.ramdata);
|
||||
__ram2_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*.*(.rodata*)
|
||||
*libch.a:nvic.*(.rodata*)
|
||||
*libch.a:bouncebuffer.*(.rodata*)
|
||||
*libch.a:stm32_util.*(.rodata*)
|
||||
*libch.a:stm32_dma.*(.rodata*)
|
||||
*libch.a:memstreams.*(.rodata*)
|
||||
*libch.a:malloc.*(.rodata*)
|
||||
*libch.a:hrt.*(.rodata*)
|
||||
EXCLUDE_FILE (*hal_lld.o) *libch.a:hal*.*(.rodata*)
|
||||
/* a selection of performance critical functions driven CPUInfo results */
|
||||
lib/lib*.a:Semaphores.*(.rodata*)
|
||||
lib/lib*.a:AP_Math.*(.rodata*)
|
||||
lib/lib*.a:vector3.*(.rodata*)
|
||||
lib/lib*.a:matrix3.*(.rodata*)
|
||||
*libm.a:*(.rodata*)
|
||||
*(.ramdata*)
|
||||
. = ALIGN(4);
|
||||
} > dataram AT > default_flash
|
||||
|
||||
.ram2 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram2_clear__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram2_noinit__ = .;
|
||||
. = ALIGN(4);
|
||||
__ram2_free__ = .;
|
||||
. = ALIGN(4);
|
||||
} > dataram
|
||||
|
||||
.text : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
/* we want app_descriptor near the start of flash so a false
|
||||
positive isn't found by the bootloader (eg. ROMFS) */
|
||||
KEEP(*libch.a:vectors.o);
|
||||
KEEP(*libch.a:crt0_v7m.o);
|
||||
KEEP(*libch.a:crt1.o);
|
||||
KEEP(*libch.a:board.o);
|
||||
KEEP(*(.apsec_data));
|
||||
KEEP(*(.app_descriptor));
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.rodata)
|
||||
*(.rodata.*)
|
||||
*(.glue_7t)
|
||||
*(.glue_7)
|
||||
*(.gcc*)
|
||||
} > default_flash
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > default_flash
|
||||
|
||||
.ARM.exidx : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
__exidx_end = .;
|
||||
} > default_flash
|
||||
|
||||
.eh_frame_hdr :
|
||||
{
|
||||
*(.eh_frame_hdr)
|
||||
} > default_flash
|
||||
|
||||
.eh_frame : ONLY_IF_RO
|
||||
{
|
||||
*(.eh_frame)
|
||||
} > default_flash
|
||||
|
||||
.textalign : ONLY_IF_RO
|
||||
{
|
||||
. = ALIGN(8);
|
||||
} > default_flash
|
||||
|
||||
/* Legacy symbol, not used anywhere.*/
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_etext = .);
|
||||
|
||||
/* Special section for exceptions stack.*/
|
||||
.mstack :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
__main_stack_base__ = .;
|
||||
. += __main_stack_size__;
|
||||
. = ALIGN(8);
|
||||
__main_stack_end__ = .;
|
||||
} > MAIN_STACK_RAM
|
||||
|
||||
/* Special section for process stack.*/
|
||||
.pstack :
|
||||
{
|
||||
__process_stack_base__ = .;
|
||||
__main_thread_stack_base__ = .;
|
||||
. += __process_stack_size__;
|
||||
. = ALIGN(8);
|
||||
__process_stack_end__ = .;
|
||||
__main_thread_stack_end__ = .;
|
||||
} > PROCESS_STACK_RAM
|
||||
|
||||
.data : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_textdata = LOADADDR(.data));
|
||||
PROVIDE(_data = .);
|
||||
__textdata_base__ = LOADADDR(.data);
|
||||
__data_base__ = .;
|
||||
*(.data)
|
||||
*(.data.*)
|
||||
*(.ramtext)
|
||||
. = ALIGN(4);
|
||||
PROVIDE(_edata = .);
|
||||
__data_end__ = .;
|
||||
} > DATA_RAM AT > default_flash
|
||||
|
||||
.bss (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__bss_base__ = .;
|
||||
*(.bss)
|
||||
*(.bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
__bss_end__ = .;
|
||||
PROVIDE(end = .);
|
||||
} > BSS_RAM
|
||||
|
||||
.ram0_init : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram0_init_text__ = LOADADDR(.ram0_init);
|
||||
__ram0_init__ = .;
|
||||
*(.ram0_init)
|
||||
*(.ram0_init.*)
|
||||
. = ALIGN(4);
|
||||
} > ram0 AT > default_flash
|
||||
|
||||
.ram0 (NOLOAD) : ALIGN(4)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__ram0_clear__ = .;
|
||||
*(.ram0_clear)
|
||||
*(.ram0_clear.*)
|
||||
. = ALIGN(4);
|
||||
__ram0_noinit__ = .;
|
||||
*(.ram0)
|
||||
*(.ram0.*)
|
||||
. = ALIGN(4);
|
||||
__ram0_free__ = .;
|
||||
} > ram0
|
||||
|
||||
/* The default heap uses the (statically) unused part of a RAM section.*/
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
__heap_base__ = .;
|
||||
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
|
||||
__heap_end__ = .;
|
||||
} > HEAP_RAM
|
||||
|
||||
/* The crash log uses the unused part of a flash section.*/
|
||||
.crash_log (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(32);
|
||||
__crash_log_base__ = .;
|
||||
. = ORIGIN(default_flash) + LENGTH(default_flash);
|
||||
__crash_log_end__ = .;
|
||||
} > default_flash
|
||||
}
|
@ -430,7 +430,7 @@
|
||||
* buffers.
|
||||
*/
|
||||
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
|
||||
#if defined(STM32H7)
|
||||
#if defined(STM32H7) && HAL_MEMORY_TOTAL_KB>=512
|
||||
#define SERIAL_BUFFERS_SIZE 512
|
||||
#else
|
||||
#define SERIAL_BUFFERS_SIZE 256
|
||||
@ -469,7 +469,7 @@
|
||||
* buffers.
|
||||
*/
|
||||
#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__)
|
||||
#if defined(STM32H7)
|
||||
#if defined(STM32H7) && HAL_MEMORY_TOTAL_KB>=512
|
||||
#define SERIAL_USB_BUFFERS_SIZE 768
|
||||
#else
|
||||
#define SERIAL_USB_BUFFERS_SIZE 256
|
||||
@ -482,7 +482,7 @@
|
||||
*/
|
||||
#if !defined(SERIAL_USB_BUFFERS_NUMBER) || defined(__DOXYGEN__)
|
||||
// more USB buffers works well on H7 and higher end F7
|
||||
#if defined(STM32H7) || (defined(STM32F7) && HAL_MEMORY_TOTAL_KB>=512)
|
||||
#if (defined(STM32H7) || defined(STM32F7)) && HAL_MEMORY_TOTAL_KB>=512
|
||||
#define SERIAL_USB_BUFFERS_NUMBER 4
|
||||
#else
|
||||
#define SERIAL_USB_BUFFERS_NUMBER 2
|
||||
|
@ -81,7 +81,7 @@
|
||||
// enable memory protection on part of AXI used for SDMMC
|
||||
#if defined(STM32H730xx)
|
||||
#define STM32_NOCACHE_MPU_REGION_2 MPU_REGION_4
|
||||
#define STM32_NOCACHE_MPU_REGION_2_BASE 0x2403C000
|
||||
#define STM32_NOCACHE_MPU_REGION_2_BASE 0x24044000
|
||||
#define STM32_NOCACHE_MPU_REGION_2_SIZE MPU_RASR_SIZE_16K
|
||||
#endif
|
||||
/*
|
||||
|
@ -44,7 +44,7 @@ mcu = {
|
||||
(0x24044000, 16, 4), # non-cacheable AXI SRAM. Use this for SDMMC IDMA ops.
|
||||
(0x30000000, 32, 0), # SRAM1, SRAM2
|
||||
(0x20000000, 64, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x38000000, 16, 1), # SRAM4. Use this for DMA and BDMA ops.
|
||||
(0x38000000, 16, 1), # non-cacheable SRAM4. Use this for DMA and BDMA ops.
|
||||
],
|
||||
'INSTRUCTION_RAM' : (0x00000400, 63), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
'FLASH_RAM' : (0x24048000, 32), # AXI SRAM used for process stack and ram functions
|
||||
@ -56,14 +56,22 @@ mcu = {
|
||||
'RAM_MAP_BOOTLOADER' : [
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 32, 0), # SRAM1, SRAM2
|
||||
(0x24000000, 240, 0), # AXI SRAM.
|
||||
(0x2403C000, 16, 4), # non-cacheable AXI SRAM. Use this for SDMMC IDMA ops.
|
||||
(0x24000000, 272, 0), # AXI SRAM.
|
||||
(0x24044000, 16, 4), # non-cacheable AXI SRAM. Use this for SDMMC IDMA ops.
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x38000000, 16, 1), # SRAM4.
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
||||
'EXPECTED_CLOCKS' : [
|
||||
('STM32_SYS_CK', 520000000),
|
||||
('STM32_OSPICLK', 200000000),
|
||||
('STM32_SDMMC1CLK', 86666666),
|
||||
('STM32_SPI45CLK', 100000000),
|
||||
('STM32_FDCANCLK', 86666666),
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
'CORTEX' : 'cortex-m7',
|
||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||
|
@ -79,7 +79,7 @@ mcu = {
|
||||
'STM32H7' : '1',
|
||||
},
|
||||
|
||||
'LINKER_CONFIG' : 'common_extf.ld'
|
||||
'LINKER_CONFIG' : 'common_extf_h750.ld'
|
||||
}
|
||||
|
||||
pincount = {
|
||||
|
@ -1005,10 +1005,9 @@ def write_mcu_config(f):
|
||||
env_vars['EXT_FLASH_SIZE_MB'] = get_config('EXT_FLASH_SIZE_MB', default=0, type=int)
|
||||
env_vars['INT_FLASH_PRIMARY'] = get_config('INT_FLASH_PRIMARY', default=False, type=bool)
|
||||
if env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader and not env_vars['INT_FLASH_PRIMARY']:
|
||||
f.write('#define CRT0_AREAS_NUMBER 3\n')
|
||||
f.write('#define CRT0_AREAS_NUMBER 4\n')
|
||||
f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM
|
||||
f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n')
|
||||
if not mcu_type.startswith('STM32H730'):
|
||||
f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n')
|
||||
f.write('#define PORT_IRQ_ATTRIBUTES __FASTRAMFUNC__\n')
|
||||
else:
|
||||
@ -1372,8 +1371,8 @@ MEMORY
|
||||
default_flash (rx) : org = 0x%08x, len = %uK
|
||||
instram : org = 0x%08x, len = %uK
|
||||
ram0 : org = 0x%08x, len = %u
|
||||
ram1 : org = 0x%08x, len = %u
|
||||
ram2 : org = 0x%08x, len = %u
|
||||
flashram : org = 0x%08x, len = %u
|
||||
dataram : org = 0x%08x, len = %u
|
||||
}
|
||||
|
||||
INCLUDE common.ld
|
||||
|
Loading…
Reference in New Issue
Block a user