1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Rearranged flash on targets >512 kB to keep first sector from overflowing.

This commit is contained in:
Michael Keller 2021-08-06 02:22:15 +12:00
parent 86a0e3cd2c
commit b83bc86713
17 changed files with 95 additions and 56 deletions

View file

@ -37,4 +37,8 @@ REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
REGION_ALIAS("VECTAB", RAM)
INCLUDE "stm32_flash_split.ld"
/* Put various bits and bobs of data into the main chunk of flash as we have enough of it */
REGION_ALIAS("MOVABLE_FLASH", FLASH1)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -34,4 +34,8 @@ MEMORY
REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
INCLUDE "stm32_flash_split.ld"
/* Put various bits and bobs of data into the main chunk of flash as we have enough of it */
REGION_ALIAS("MOVABLE_FLASH", FLASH1)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -36,4 +36,8 @@ REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
REGION_ALIAS("VECTAB", RAM)
INCLUDE "stm32_flash_split.ld"
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", FLASH)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -33,4 +33,8 @@ MEMORY
REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
INCLUDE "stm32_flash_split.ld"
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", FLASH)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -34,4 +34,8 @@ REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
REGION_ALIAS("VECTAB", RAM)
INCLUDE "stm32_flash_split.ld"
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", FLASH)
INCLUDE "stm32_flash_f4_split.ld"

View file

@ -1,7 +1,7 @@
/*
*****************************************************************************
**
** File : stm32_flash_split.ld
** File : stm32_flash_f4_split.ld
**
** Abstract : Common linker script for STM32 devices.
**
@ -80,35 +80,35 @@ SECTIONS
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
} >MOVABLE_FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
} >MOVABLE_FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
} >MOVABLE_FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(.fini_array*))
KEEP (*(SORT(.fini_array.*)))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
} >MOVABLE_FLASH
.pg_registry :
{
PROVIDE_HIDDEN (__pg_registry_start = .);
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH
} >MOVABLE_FLASH
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
@ -144,7 +144,7 @@ SECTIONS
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
} >RAM AT> MOVABLE_FLASH
/* Uninitialized data section */
. = ALIGN(4);

View file

@ -21,6 +21,7 @@ MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
/* Alternate access to the same flash storage as AXIM flash, but not writable by the boot loader. */
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
@ -39,14 +40,19 @@ MEMORY
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("WRITABLE_FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH_OVERFLOW", AXIM_FLASH1)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("WRITABLE_FLASH1", AXIM_FLASH1)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS_EXTENDED", AXIM_FLASH_CUSTOM_DEFAULTS_EXTENDED)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", AXIM_FLASH)
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -23,13 +23,14 @@ MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
/* Alternate access to the same flash storage as AXIM flash, but not writable by the boot loader. */
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
AXIM_FLASH_OVERFLOW (r) : ORIGIN = 0x08005000, LENGTH = 12K
AXIM_FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
/* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 928K : 960K
@ -42,14 +43,19 @@ MEMORY
}
REGION_ALIAS("FLASH", ITCM_FLASH)
REGION_ALIAS("FLASH_OVERFLOW", AXIM_FLASH_OVERFLOW)
REGION_ALIAS("WRITABLE_FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", ITCM_FLASH1)
REGION_ALIAS("WRITABLE_FLASH1", AXIM_FLASH1)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS_EXTENDED", AXIM_FLASH_CUSTOM_DEFAULTS_EXTENDED)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
/* Put various bits and bobs of data into the main chunk of flash as we have enough of it */
REGION_ALIAS("MOVABLE_FLASH", AXIM_FLASH1)
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -23,13 +23,14 @@ MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
/* Alternate access to the same flash storage as AXIM flash, but not writable by the boot loader. */
ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
AXIM_FLASH_OVERFLOW (r) : ORIGIN = 0x08005000, LENGTH = 12K
AXIM_FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K
@ -39,14 +40,19 @@ MEMORY
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_OVERFLOW", AXIM_FLASH_OVERFLOW)
REGION_ALIAS("FLASH", ITCM_FLASH)
REGION_ALIAS("WRITABLE_FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("FLASH1", ITCM_FLASH1)
REGION_ALIAS("WRITABLE_FLASH1", AXIM_FLASH1)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", DTCM_RAM)
/* Put various bits and bobs of data into the main chunk of flash as we have enough of it */
REGION_ALIAS("MOVABLE_FLASH", AXIM_FLASH1)
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -32,7 +32,7 @@ SECTIONS
PROVIDE (isr_vector_table_base = .);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH AT >AXIM_FLASH
} >FLASH AT >WRITABLE_FLASH
/* The program code and other data goes into FLASH */
.text :
@ -51,7 +51,7 @@ SECTIONS
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH1 AT >AXIM_FLASH1
} >FLASH1 AT >WRITABLE_FLASH1
/* Critical program code goes into ITCM RAM */
/* Copy specific fast-executing code to ITCM RAM */
@ -64,18 +64,18 @@ SECTIONS
*(.tcm_code*)
. = ALIGN(4);
tcm_code_end = .;
} >ITCM_RAM AT >AXIM_FLASH1
} >ITCM_RAM AT >WRITABLE_FLASH1
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH
} >MOVABLE_FLASH
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH AT >AXIM_FLASH
} >MOVABLE_FLASH
.pg_registry :
{
@ -83,14 +83,14 @@ SECTIONS
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH AT >AXIM_FLASH
} >MOVABLE_FLASH
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH_OVERFLOW
} >FLASH1 AT >WRITABLE_FLASH1
/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
@ -120,7 +120,7 @@ SECTIONS
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT >AXIM_FLASH1
} >RAM AT >WRITABLE_FLASH1
/* Uninitialized data section */
. = ALIGN(4);
@ -166,7 +166,7 @@ SECTIONS
. = ALIGN(4);
_efastram_data = .; /* define a global symbol at data end */
} >FASTRAM AT >AXIM_FLASH1
} >FASTRAM AT >WRITABLE_FLASH1
. = ALIGN(4);
.fastram_bss (NOLOAD) :

View file

@ -35,4 +35,8 @@ REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
REGION_ALIAS("VECTAB", CCM)
INCLUDE "stm32_flash_split_g4.ld"
/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */
REGION_ALIAS("MOVABLE_FLASH", FLASH)
INCLUDE "stm32_flash_g4_split.ld"

View file

@ -1,7 +1,7 @@
/*
*****************************************************************************
**
** File : stm32_flash_split.ld
** File : stm32_flash_g4_split.ld
**
** Abstract : Common linker script for STM32 devices.
**
@ -75,12 +75,15 @@ SECTIONS
} >FLASH1
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM.extab : {
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >MOVABLE_FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
} >MOVABLE_FLASH
.preinit_array :
{

View file

@ -38,7 +38,9 @@ ENTRY(Reset_Handler)
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 118K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 1664K : 1792K
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x081E0000 : 0x08200000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 128K : 0K
@ -55,17 +57,6 @@ MEMORY
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
/* INCLUDE "stm32_flash_f7_split.ld" */
/*
*****************************************************************************
**
** File : stm32_flash_f7_split.ld
**
** Abstract : Common linker script for STM32 devices.
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
@ -127,13 +118,13 @@ SECTIONS
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH
} >FLASH1
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH
} >FLASH1
.pg_registry :
{
@ -178,7 +169,7 @@ SECTIONS
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT >FLASH
} >RAM AT >FLASH1
/* Uninitialized data section */
. = ALIGN(4);
@ -224,7 +215,7 @@ SECTIONS
. = ALIGN(4);
_efastram_data = .; /* define a global symbol at data end */
} >FASTRAM AT >FLASH
} >FASTRAM AT >FLASH1
. = ALIGN(4);
.fastram_bss (NOLOAD) :
@ -253,7 +244,7 @@ SECTIONS
*(.dmaram_data*) /* .data* sections */
. = ALIGN(32);
_edmaram_data = .; /* define a global symbol at data end */
} >RAM AT >FLASH
} >RAM AT >FLASH1
. = ALIGN(32);
.dmaram_bss (NOLOAD) :

View file

@ -41,4 +41,4 @@ SECTIONS
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}
}

View file

@ -26,4 +26,4 @@ SECTIONS
. = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH);
__firmware_end__ = .;
} >EXST_HASH
}
}