Skip to content

Commit

Permalink
Removing Custom Defaults (betaflight#12425)
Browse files Browse the repository at this point in the history
  • Loading branch information
blckmn authored and davidbitton committed Feb 5, 2024
1 parent b5ba490 commit 2c6262e
Show file tree
Hide file tree
Showing 48 changed files with 156 additions and 553 deletions.
5 changes: 0 additions & 5 deletions Makefile
Expand Up @@ -214,11 +214,6 @@ TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))

.DEFAULT_GOAL := hex

ifeq ($(CUSTOM_DEFAULTS_EXTENDED),yes)
TARGET_FLAGS += -DUSE_CUSTOM_DEFAULTS=
EXTRA_LD_FLAGS += -Wl,--defsym=USE_CUSTOM_DEFAULTS_EXTENDED=1
endif

INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/lib/main/MAVLink

Expand Down
13 changes: 4 additions & 9 deletions src/link/at32_flash_f43xM.ld
Expand Up @@ -18,21 +18,16 @@
*****************************************************************************
*/


/*
FLASH : 0x0800 0000 -- 0x083E FFFF
MEM : 0x2000 0000 -- 0x2007 FFFF

FLASH : 0x0800 0000 -- 0x083E FFFF
MEM : 0x2000 0000 -- 0x2007 FFFF
*/

MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CDEF (r) : ORIGIN = 0x08002800, LENGTH = 6K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K
FLASH_CDEF_EXT (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K

FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 4000K
SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */
Expand Down
21 changes: 2 additions & 19 deletions src/link/at32_flash_f4_split.ld
Expand Up @@ -73,22 +73,21 @@ SECTIONS
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH1

/*
Critical program code goes into RAM
*/
tcm_code = LOADADDR(.tcm_code);
.tcm_code :
{
. = ALIGN(4);
tcm_code_start = .;
tcm_code_start = .;
*(.tcm_code)
*(.tcm_code*)
. = ALIGN(4);
tcm_code_end = .;
} >RAM AT >FLASH1


.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
Expand Down Expand Up @@ -130,22 +129,6 @@ SECTIONS
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH1

/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
KEEP (*(.custom_defaults_start_address))
. = ALIGN(4);
KEEP (*(.custom_defaults_end_address))
. = ALIGN(4);
__custom_defaults_internal_start = .;
KEEP (*(.custom_defaults))
. = ALIGN(4);
} >FLASH_CDEF

PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CDEF_EXT) : __custom_defaults_internal_start);
PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CDEF_EXT) + LENGTH(FLASH_CDEF_EXT) : ORIGIN(FLASH_CDEF) + LENGTH(FLASH_CDEF));

/* used by the startup to initialize data */
_sidata = LOADADDR(.data);

Expand Down
11 changes: 5 additions & 6 deletions src/link/stm32_flash.ld
Expand Up @@ -54,19 +54,18 @@ SECTIONS
} >FLASH

/* Critical program code goes into CCM RAM */
/* Copy specific fast-executing code to CCM RAM */
ccm_code = LOADADDR(.ccm_code);
/* Copy specific fast-executing code to CCM RAM */
ccm_code = LOADADDR(.ccm_code);
.ccm_code :
{
. = ALIGN(4);
ccm_code_start = .;
ccm_code_start = .;
*(.ccm_code)
*(.ccm_code*)
. = ALIGN(4);
ccm_code_end = .;
ccm_code_end = .;
} >CCM AT >FLASH


.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
Expand Down Expand Up @@ -138,7 +137,7 @@ SECTIONS
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM

.fastram_bss (NOLOAD) :
{
__fastram_bss_start__ = .;
Expand Down
6 changes: 2 additions & 4 deletions src/link/stm32_flash_f405.ld
Expand Up @@ -19,11 +19,9 @@
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 976K : 992K
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K

SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K

Expand Down
6 changes: 2 additions & 4 deletions src/link/stm32_flash_f411.ld
Expand Up @@ -20,11 +20,9 @@
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 464K : 480K
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K

SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K

Expand Down
16 changes: 0 additions & 16 deletions src/link/stm32_flash_f4_split.ld
Expand Up @@ -116,22 +116,6 @@ SECTIONS
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH1

/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
KEEP (*(.custom_defaults_start_address))
. = ALIGN(4);
KEEP (*(.custom_defaults_end_address))
. = ALIGN(4);
__custom_defaults_internal_start = .;
KEEP (*(.custom_defaults))
. = ALIGN(4);
} >FLASH_CUSTOM_DEFAULTS

PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) : __custom_defaults_internal_start);
PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) + LENGTH(FLASH_CUSTOM_DEFAULTS_EXTENDED) : ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS));

/* used by the startup to initialize data */
_sidata = LOADADDR(.data);

Expand Down
8 changes: 2 additions & 6 deletions src/link/stm32_flash_f722.ld
Expand Up @@ -26,12 +26,10 @@ MEMORY
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K

AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
/* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 464K : 480K
AXIM_FLASH_CUSTOM_DEFAULTS_EXTENDED (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K

DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
Expand All @@ -41,11 +39,9 @@ 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("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)
Expand Down
29 changes: 12 additions & 17 deletions src/link/stm32_flash_f74x.ld
Expand Up @@ -21,34 +21,29 @@
/* Specify the memory areas */
MEMORY
{
ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K
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
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_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
/* 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
AXIM_FLASH_CUSTOM_DEFAULTS_EXTENDED (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x080F8000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 32K : 0K

DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
SRAM2 (rwx) : ORIGIN = 0x2004C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K

DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
SRAM2 (rwx) : ORIGIN = 0x2004C000, LENGTH = 16K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}

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", 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)
Expand Down
4 changes: 1 addition & 3 deletions src/link/stm32_flash_f765.ld
Expand Up @@ -28,9 +28,7 @@ MEMORY
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_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K

Expand Down
36 changes: 10 additions & 26 deletions src/link/stm32_flash_f7_split.ld
Expand Up @@ -54,24 +54,24 @@ SECTIONS
} >FLASH1 AT >WRITABLE_FLASH1

/* Critical program code goes into ITCM RAM */
/* Copy specific fast-executing code to ITCM RAM */
tcm_code = LOADADDR(.tcm_code);
/* Copy specific fast-executing code to ITCM RAM */
tcm_code = LOADADDR(.tcm_code);
.tcm_code :
{
. = ALIGN(4);
tcm_code_start = .;
tcm_code_start = .;
*(.tcm_code)
*(.tcm_code*)
. = ALIGN(4);
tcm_code_end = .;
tcm_code_end = .;
} >ITCM_RAM AT >WRITABLE_FLASH1

.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >MOVABLE_FLASH
.ARM :

.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
Expand All @@ -84,30 +84,14 @@ SECTIONS
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >MOVABLE_FLASH

.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >WRITABLE_FLASH1

/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
KEEP (*(.custom_defaults_start_address))
. = ALIGN(4);
KEEP (*(.custom_defaults_end_address))
. = ALIGN(4);
__custom_defaults_internal_start = .;
KEEP (*(.custom_defaults))
. = ALIGN(4);
} >FLASH_CUSTOM_DEFAULTS

PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) : __custom_defaults_internal_start);
PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) + LENGTH(FLASH_CUSTOM_DEFAULTS_EXTENDED) : ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS));

/* used by the startup to initialize data */
_sidata = LOADADDR(.data);

Expand Down
5 changes: 1 addition & 4 deletions src/link/stm32_flash_g474.ld
Expand Up @@ -13,11 +13,8 @@
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 8K
FLASH1 (rx) : ORIGIN = 0x08006000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 480K : 488K
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x0807E000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 8K : 0K

FLASH1 (rx) : ORIGIN = 0x08006000, LENGTH = 496K

SYSTEM_MEMORY (r) : ORIGIN = 0x1FFF0000, LENGTH = 64K
/* Below are the true lengths for normal and close coupled RAM
Expand Down
16 changes: 0 additions & 16 deletions src/link/stm32_flash_g4_split.ld
Expand Up @@ -119,22 +119,6 @@ SECTIONS
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH1

/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
KEEP (*(.custom_defaults_start_address))
. = ALIGN(4);
KEEP (*(.custom_defaults_end_address))
. = ALIGN(4);
__custom_defaults_internal_start = .;
KEEP (*(.custom_defaults))
. = ALIGN(4);
} >FLASH_CUSTOM_DEFAULTS

PROVIDE_HIDDEN (__custom_defaults_start = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) : __custom_defaults_internal_start);
PROVIDE_HIDDEN (__custom_defaults_end = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? ORIGIN(FLASH_CUSTOM_DEFAULTS_EXTENDED) + LENGTH(FLASH_CUSTOM_DEFAULTS_EXTENDED) : ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS));

/* used by the startup to initialize data */
_sidata = LOADADDR(.data);

Expand Down

0 comments on commit 2c6262e

Please sign in to comment.