From ee77239db1b38e7e6c770b1958cf48aa059d5f00 Mon Sep 17 00:00:00 2001 From: J Blackman Date: Fri, 3 Mar 2023 05:39:44 +1100 Subject: [PATCH] Removing Custom Defaults (#12425) --- Makefile | 5 - src/link/at32_flash_f43xM.ld | 13 +- src/link/at32_flash_f4_split.ld | 21 +-- src/link/stm32_flash.ld | 11 +- src/link/stm32_flash_f405.ld | 6 +- src/link/stm32_flash_f411.ld | 6 +- src/link/stm32_flash_f4_split.ld | 16 -- src/link/stm32_flash_f722.ld | 8 +- src/link/stm32_flash_f74x.ld | 27 ++- src/link/stm32_flash_f765.ld | 4 +- src/link/stm32_flash_f7_split.ld | 36 ++-- src/link/stm32_flash_g474.ld | 5 +- src/link/stm32_flash_g4_split.ld | 16 -- src/link/stm32_flash_h723_1m.ld | 43 ++--- src/link/stm32_flash_h743_2m.ld | 43 ++--- src/link/stm32_flash_h750_128k.ld | 2 +- src/link/stm32_flash_h750_1m.ld | 2 +- src/link/stm32_h723_common.ld | 30 ++-- src/link/stm32_h723_common_post.ld | 2 +- src/link/stm32_h730_common.ld | 16 +- src/link/stm32_h730_common_post.ld | 2 +- src/link/stm32_h750_common.ld | 20 +-- src/link/stm32_h750_common_post.ld | 2 +- src/link/stm32_ram_h723_exst.ld | 7 +- src/link/stm32_ram_h723_exst_post.ld | 6 +- src/link/stm32_ram_h730_exst.ld | 7 +- src/link/stm32_ram_h730_exst_post.ld | 6 +- src/link/stm32_ram_h743.ld | 20 +-- src/link/stm32_ram_h750_exst.ld | 9 +- src/link/stm32_ram_h750_exst_post.ld | 6 +- src/main/cli/cli.c | 232 ++------------------------ src/main/config/config.c | 17 +- src/main/config/config.h | 2 +- src/main/drivers/at32/platform_mcu.h | 1 - src/main/drivers/stm32/platform_mcu.h | 2 - src/main/fc/init.c | 4 +- src/main/msp/msp.c | 20 +-- src/main/sensors/gyro_init.c | 3 - src/main/target/AT32F435/target.h | 9 +- src/main/target/STM32F405/target.h | 1 - src/main/target/STM32F411/target.h | 1 - src/main/target/STM32F745/target.h | 1 - src/main/target/STM32F7X2/target.h | 3 - src/main/target/STM32G47X/target.h | 2 - src/main/target/STM32H723/target.h | 4 - src/main/target/STM32H743/target.h | 2 - src/main/target/common_post.h | 4 - src/test/unit/cli_unittest.cc | 2 +- 48 files changed, 155 insertions(+), 552 deletions(-) diff --git a/Makefile b/Makefile index feee264554..be232150f1 100644 --- a/Makefile +++ b/Makefile @@ -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 diff --git a/src/link/at32_flash_f43xM.ld b/src/link/at32_flash_f43xM.ld index ea9f620f0d..90d88e282e 100644 --- a/src/link/at32_flash_f43xM.ld +++ b/src/link/at32_flash_f43xM.ld @@ -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 */ diff --git a/src/link/at32_flash_f4_split.ld b/src/link/at32_flash_f4_split.ld index 9f762f5db8..de2cf5fed7 100644 --- a/src/link/at32_flash_f4_split.ld +++ b/src/link/at32_flash_f4_split.ld @@ -73,7 +73,7 @@ SECTIONS . = ALIGN(4); _etext = .; /* define a global symbols at end of code */ } >FLASH1 - + /* Critical program code goes into RAM */ @@ -81,14 +81,13 @@ SECTIONS .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 = .; @@ -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); diff --git a/src/link/stm32_flash.ld b/src/link/stm32_flash.ld index c88e3fc53a..b52f835635 100644 --- a/src/link/stm32_flash.ld +++ b/src/link/stm32_flash.ld @@ -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 = .; @@ -138,7 +137,7 @@ SECTIONS _ebss = .; /* define a global symbol at bss end */ __bss_end__ = _ebss; } >RAM - + .fastram_bss (NOLOAD) : { __fastram_bss_start__ = .; diff --git a/src/link/stm32_flash_f405.ld b/src/link/stm32_flash_f405.ld index 4920114c93..e69e281d38 100644 --- a/src/link/stm32_flash_f405.ld +++ b/src/link/stm32_flash_f405.ld @@ -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 diff --git a/src/link/stm32_flash_f411.ld b/src/link/stm32_flash_f411.ld index 98555ce42a..b61b9e8587 100644 --- a/src/link/stm32_flash_f411.ld +++ b/src/link/stm32_flash_f411.ld @@ -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 diff --git a/src/link/stm32_flash_f4_split.ld b/src/link/stm32_flash_f4_split.ld index f799ae4b5d..fa4cbdd129 100644 --- a/src/link/stm32_flash_f4_split.ld +++ b/src/link/stm32_flash_f4_split.ld @@ -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); diff --git a/src/link/stm32_flash_f722.ld b/src/link/stm32_flash_f722.ld index 8e6d75dbdc..85d26e49e0 100644 --- a/src/link/stm32_flash_f722.ld +++ b/src/link/stm32_flash_f722.ld @@ -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 @@ -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) diff --git a/src/link/stm32_flash_f74x.ld b/src/link/stm32_flash_f74x.ld index bf066366a0..b809315f12 100644 --- a/src/link/stm32_flash_f74x.ld +++ b/src/link/stm32_flash_f74x.ld @@ -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 + 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 + 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) diff --git a/src/link/stm32_flash_f765.ld b/src/link/stm32_flash_f765.ld index 65b2f922ad..bb4e417482 100644 --- a/src/link/stm32_flash_f765.ld +++ b/src/link/stm32_flash_f765.ld @@ -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 diff --git a/src/link/stm32_flash_f7_split.ld b/src/link/stm32_flash_f7_split.ld index d73f0f4a8d..ad4d154c6d 100644 --- a/src/link/stm32_flash_f7_split.ld +++ b/src/link/stm32_flash_f7_split.ld @@ -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 = .; @@ -84,7 +84,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >MOVABLE_FLASH - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); @@ -92,22 +92,6 @@ SECTIONS 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); diff --git a/src/link/stm32_flash_g474.ld b/src/link/stm32_flash_g474.ld index 63edfffdab..7074fa01c0 100644 --- a/src/link/stm32_flash_g474.ld +++ b/src/link/stm32_flash_g474.ld @@ -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 diff --git a/src/link/stm32_flash_g4_split.ld b/src/link/stm32_flash_g4_split.ld index 7820c38964..c31f6c6fea 100644 --- a/src/link/stm32_flash_g4_split.ld +++ b/src/link/stm32_flash_g4_split.ld @@ -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); diff --git a/src/link/stm32_flash_h723_1m.ld b/src/link/stm32_flash_h723_1m.ld index 3f437c95c2..05373575ba 100644 --- a/src/link/stm32_flash_h723_1m.ld +++ b/src/link/stm32_flash_h723_1m.ld @@ -36,13 +36,9 @@ ENTRY(Reset_Handler) /* Specify the memory areas */ MEMORY { - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K - FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K - FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K - + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K - FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 640K : 768K - FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x081E0000 : 0x08200000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 128K : 0K + FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 768K ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K @@ -101,24 +97,24 @@ SECTIONS } >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 >FLASH1 - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH1 - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -131,7 +127,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >FLASH1 - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); @@ -139,21 +135,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 = .; - *(.custom_defaults); - } >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); diff --git a/src/link/stm32_flash_h743_2m.ld b/src/link/stm32_flash_h743_2m.ld index 911e482fba..9a283377a3 100644 --- a/src/link/stm32_flash_h743_2m.ld +++ b/src/link/stm32_flash_h743_2m.ld @@ -37,13 +37,9 @@ ENTRY(Reset_Handler) /* Specify the memory areas */ MEMORY { - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K - FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K - FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K - + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K 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 + FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 1792K ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K @@ -103,24 +99,24 @@ SECTIONS } >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 >FLASH1 - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH1 - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -133,7 +129,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >FLASH1 - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); @@ -141,21 +137,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 = .; - *(.custom_defaults); - } >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); diff --git a/src/link/stm32_flash_h750_128k.ld b/src/link/stm32_flash_h750_128k.ld index 727da9f001..d3da82433a 100644 --- a/src/link/stm32_flash_h750_128k.ld +++ b/src/link/stm32_flash_h750_128k.ld @@ -43,7 +43,7 @@ MEMORY D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K - QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K + QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K } REGION_ALIAS("STACKRAM", DTCM_RAM) diff --git a/src/link/stm32_flash_h750_1m.ld b/src/link/stm32_flash_h750_1m.ld index 48afdbd299..c4bfdc53c6 100644 --- a/src/link/stm32_flash_h750_1m.ld +++ b/src/link/stm32_flash_h750_1m.ld @@ -43,7 +43,7 @@ MEMORY D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K - QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K + QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K } REGION_ALIAS("STACKRAM", DTCM_RAM) diff --git a/src/link/stm32_h723_common.ld b/src/link/stm32_h723_common.ld index d10f3d957f..f076f967cf 100644 --- a/src/link/stm32_h723_common.ld +++ b/src/link/stm32_h723_common.ld @@ -36,7 +36,7 @@ SECTIONS . = ALIGN(512); /* Vector table offset must be multiple of 0x200 */ PROVIDE (ram_isr_vector_table_base = .); . += (isr_vector_table_end - isr_vector_table_base); - . = ALIGN(4); + . = ALIGN(4); PROVIDE (ram_isr_vector_table_end = .); } >DTCM_RAM @@ -60,24 +60,24 @@ SECTIONS } >MAIN /* 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 >MAIN - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) } >MAIN - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -90,7 +90,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >MAIN - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); @@ -114,16 +114,16 @@ SECTIONS } >DTCM_RAM AT >MAIN /* Non-critical program code goes into RAM */ - /* Copy specific slow-executing code to RAM */ - ram_code = LOADADDR(.ram_code); + /* Copy specific slow-executing code to RAM */ + ram_code = LOADADDR(.ram_code); .ram_code : { . = ALIGN(4); - ram_code_start = .; + ram_code_start = .; *(.ram_code) *(.ram_code*) . = ALIGN(4); - ram_code_end = .; + ram_code_end = .; } >RAM AT >MAIN /* Uninitialized data section */ diff --git a/src/link/stm32_h723_common_post.ld b/src/link/stm32_h723_common_post.ld index 89b4224806..cff8246ce5 100644 --- a/src/link/stm32_h723_common_post.ld +++ b/src/link/stm32_h723_common_post.ld @@ -31,7 +31,7 @@ SECTIONS *(.mb1rodata) /* read-only data (constants) */ *(.mb1rodata*) } >MEMORY_B1 - + /* Remove information from the standard libraries */ /DISCARD/ : { diff --git a/src/link/stm32_h730_common.ld b/src/link/stm32_h730_common.ld index d10f3d957f..2f763cde17 100644 --- a/src/link/stm32_h730_common.ld +++ b/src/link/stm32_h730_common.ld @@ -36,7 +36,7 @@ SECTIONS . = ALIGN(512); /* Vector table offset must be multiple of 0x200 */ PROVIDE (ram_isr_vector_table_base = .); . += (isr_vector_table_end - isr_vector_table_base); - . = ALIGN(4); + . = ALIGN(4); PROVIDE (ram_isr_vector_table_end = .); } >DTCM_RAM @@ -76,8 +76,8 @@ SECTIONS { *(.ARM.extab* .gnu.linkonce.armextab.*) } >MAIN - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -90,7 +90,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >MAIN - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); @@ -114,16 +114,16 @@ SECTIONS } >DTCM_RAM AT >MAIN /* Non-critical program code goes into RAM */ - /* Copy specific slow-executing code to RAM */ - ram_code = LOADADDR(.ram_code); + /* Copy specific slow-executing code to RAM */ + ram_code = LOADADDR(.ram_code); .ram_code : { . = ALIGN(4); - ram_code_start = .; + ram_code_start = .; *(.ram_code) *(.ram_code*) . = ALIGN(4); - ram_code_end = .; + ram_code_end = .; } >RAM AT >MAIN /* Uninitialized data section */ diff --git a/src/link/stm32_h730_common_post.ld b/src/link/stm32_h730_common_post.ld index 89b4224806..cff8246ce5 100644 --- a/src/link/stm32_h730_common_post.ld +++ b/src/link/stm32_h730_common_post.ld @@ -31,7 +31,7 @@ SECTIONS *(.mb1rodata) /* read-only data (constants) */ *(.mb1rodata*) } >MEMORY_B1 - + /* Remove information from the standard libraries */ /DISCARD/ : { diff --git a/src/link/stm32_h750_common.ld b/src/link/stm32_h750_common.ld index b69eb91b3f..358a626724 100644 --- a/src/link/stm32_h750_common.ld +++ b/src/link/stm32_h750_common.ld @@ -44,24 +44,24 @@ SECTIONS } >MAIN /* 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 >MAIN - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) } >MAIN - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -74,7 +74,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >MAIN - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); diff --git a/src/link/stm32_h750_common_post.ld b/src/link/stm32_h750_common_post.ld index 89b4224806..cff8246ce5 100644 --- a/src/link/stm32_h750_common_post.ld +++ b/src/link/stm32_h750_common_post.ld @@ -31,7 +31,7 @@ SECTIONS *(.mb1rodata) /* read-only data (constants) */ *(.mb1rodata*) } >MEMORY_B1 - + /* Remove information from the standard libraries */ /DISCARD/ : { diff --git a/src/link/stm32_ram_h723_exst.ld b/src/link/stm32_ram_h723_exst.ld index c9f0bcd874..bec8ae63e7 100644 --- a/src/link/stm32_ram_h723_exst.ld +++ b/src/link/stm32_ram_h723_exst.ld @@ -30,7 +30,7 @@ ENTRY(Reset_Handler) 0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 */ -/* +/* For H7 EXFL (External Flash) targets a binary is built that is placed on an external device. The bootloader will enable the memory mapped mode on the CPU which allows code to run directly from @@ -61,7 +61,7 @@ MEMORY MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K OCTOSPI2 (rx) : ORIGIN = 0x70000000, LENGTH = 256M - OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M + OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M OCTOSPI1_CODE (rx): ORIGIN = ORIGIN(OCTOSPI1) + 1M, LENGTH = 1M - _exst_hash_size /* hard coded start address, as required by SPRACINGH7 boot loader, don't change! */ EXST_HASH (rx) : ORIGIN = ORIGIN(OCTOSPI1_CODE) + LENGTH(OCTOSPI1_CODE), LENGTH = _exst_hash_size } @@ -112,7 +112,7 @@ SECTIONS _edmaram = .; _dmaram_end__ = _edmaram; } >RAM - + .DMA_RW_D2 (NOLOAD) : { . = ALIGN(32); @@ -140,4 +140,3 @@ SECTIONS INCLUDE "stm32_h723_common_post.ld" INCLUDE "stm32_ram_h723_exst_post.ld" - diff --git a/src/link/stm32_ram_h723_exst_post.ld b/src/link/stm32_ram_h723_exst_post.ld index 97ed6c28f3..3bee00317f 100644 --- a/src/link/stm32_ram_h723_exst_post.ld +++ b/src/link/stm32_ram_h723_exst_post.ld @@ -11,12 +11,12 @@ SECTIONS BYTE(0x00); /* Checksum method, 0x00 = MD5 hash */ BYTE(0x00); /* Reserved */ BYTE(0x00); /* Reserved */ - + /* Fill the last 60 bytes with data, including an empty hash aligned */ - + /* to the last 16 bytes. */ FILL(0x00000000); /* Reserved */ - + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH) - 16; __md5_hash_address__ = .; LONG(0x00000000); diff --git a/src/link/stm32_ram_h730_exst.ld b/src/link/stm32_ram_h730_exst.ld index 46669d27fa..374f58cd80 100644 --- a/src/link/stm32_ram_h730_exst.ld +++ b/src/link/stm32_ram_h730_exst.ld @@ -30,7 +30,7 @@ ENTRY(Reset_Handler) 0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 */ -/* +/* For H7 EXFL (External Flash) targets a binary is built that is placed on an external device. The bootloader will enable the memory mapped mode on the CPU which allows code to run directly from @@ -61,7 +61,7 @@ MEMORY MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K OCTOSPI2 (rx) : ORIGIN = 0x70000000, LENGTH = 256M - OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M + OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M OCTOSPI1_CODE (rx): ORIGIN = ORIGIN(OCTOSPI1) + 1M, LENGTH = 1M - _exst_hash_size /* hard coded start address, as required by SPRACINGH7 boot loader, don't change! */ EXST_HASH (rx) : ORIGIN = ORIGIN(OCTOSPI1_CODE) + LENGTH(OCTOSPI1_CODE), LENGTH = _exst_hash_size } @@ -112,7 +112,7 @@ SECTIONS _edmaram = .; _dmaram_end__ = _edmaram; } >RAM - + .DMA_RW_D2 (NOLOAD) : { . = ALIGN(32); @@ -140,4 +140,3 @@ SECTIONS INCLUDE "stm32_h730_common_post.ld" INCLUDE "stm32_ram_h730_exst_post.ld" - diff --git a/src/link/stm32_ram_h730_exst_post.ld b/src/link/stm32_ram_h730_exst_post.ld index 97ed6c28f3..3bee00317f 100644 --- a/src/link/stm32_ram_h730_exst_post.ld +++ b/src/link/stm32_ram_h730_exst_post.ld @@ -11,12 +11,12 @@ SECTIONS BYTE(0x00); /* Checksum method, 0x00 = MD5 hash */ BYTE(0x00); /* Reserved */ BYTE(0x00); /* Reserved */ - + /* Fill the last 60 bytes with data, including an empty hash aligned */ - + /* to the last 16 bytes. */ FILL(0x00000000); /* Reserved */ - + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH) - 16; __md5_hash_address__ = .; LONG(0x00000000); diff --git a/src/link/stm32_ram_h743.ld b/src/link/stm32_ram_h743.ld index ebdabe7c6f..ef87f6f9ad 100644 --- a/src/link/stm32_ram_h743.ld +++ b/src/link/stm32_ram_h743.ld @@ -102,24 +102,24 @@ SECTIONS } >RAM /* 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 - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) } >RAM - - .ARM : + + .ARM : { __exidx_start = .; *(.ARM.exidx*) __exidx_end = .; @@ -132,7 +132,7 @@ SECTIONS KEEP (*(SORT(.pg_registry.*))) PROVIDE_HIDDEN (__pg_registry_end = .); } >RAM - + .pg_resetdata : { PROVIDE_HIDDEN (__pg_resetdata_start = .); diff --git a/src/link/stm32_ram_h750_exst.ld b/src/link/stm32_ram_h750_exst.ld index f322122e8d..680708a47e 100644 --- a/src/link/stm32_ram_h750_exst.ld +++ b/src/link/stm32_ram_h750_exst.ld @@ -31,7 +31,7 @@ ENTRY(Reset_Handler) 0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 */ -/* +/* For H7 EXST (External Storage) targets a binary is built that is placed on an external device. The bootloader will then copy this entire binary to RAM, at the CODE_RAM address. The bootloader @@ -46,7 +46,7 @@ to ram and one section for the main code. e.g. one file for .tcm_code, one file one for the main code/data, then load each to the appropriate address and adjust the usual startup code which will no-longer need to duplicate code/data sections from RAM to ITCM/DTCM RAM. -The initial CODE_RAM is sized at 448K to enable all firmware features and to as much RAM free as +The initial CODE_RAM is sized at 448K to enable all firmware features and to as much RAM free as possible. */ @@ -66,7 +66,7 @@ MEMORY D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K - QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K + QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K } REGION_ALIAS("STACKRAM", DTCM_RAM) @@ -113,7 +113,7 @@ SECTIONS _edmaram = .; _dmaram_end__ = _edmaram; } >RAM - + .DMA_RW_D2 (NOLOAD) : { . = ALIGN(32); @@ -141,4 +141,3 @@ SECTIONS INCLUDE "stm32_h750_common_post.ld" INCLUDE "stm32_ram_h750_exst_post.ld" - diff --git a/src/link/stm32_ram_h750_exst_post.ld b/src/link/stm32_ram_h750_exst_post.ld index 97ed6c28f3..3bee00317f 100644 --- a/src/link/stm32_ram_h750_exst_post.ld +++ b/src/link/stm32_ram_h750_exst_post.ld @@ -11,12 +11,12 @@ SECTIONS BYTE(0x00); /* Checksum method, 0x00 = MD5 hash */ BYTE(0x00); /* Reserved */ BYTE(0x00); /* Reserved */ - + /* Fill the last 60 bytes with data, including an empty hash aligned */ - + /* to the last 16 bytes. */ FILL(0x00000000); /* Reserved */ - + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH) - 16; __md5_hash_address__ = .; LONG(0x00000000); diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index da7bf75836..957c7d5cf3 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -209,33 +209,9 @@ static bool signatureUpdated = false; static const char* const emptyName = "-"; static const char* const emptyString = ""; -#if !defined(USE_CUSTOM_DEFAULTS) -#define CUSTOM_DEFAULTS_START ((char*)0) -#define CUSTOM_DEFAULTS_END ((char *)0) -#else -extern char __custom_defaults_start; -extern char __custom_defaults_end; -#define CUSTOM_DEFAULTS_START (&__custom_defaults_start) -#define CUSTOM_DEFAULTS_END (&__custom_defaults_end) - -static bool processingCustomDefaults = false; -static char cliBufferTemp[CLI_IN_BUFFER_SIZE]; - -#define CUSTOM_DEFAULTS_START_PREFIX ("# " FC_FIRMWARE_NAME) - #define MAX_CHANGESET_ID_LENGTH 8 #define MAX_DATE_LENGTH 20 -static bool customDefaultsHeaderParsed = false; -static bool customDefaultsFound = false; - -#endif - -#if defined(USE_CUSTOM_DEFAULTS_ADDRESS) -static char __attribute__ ((section(".custom_defaults_start_address"))) *customDefaultsStart = CUSTOM_DEFAULTS_START; -static char __attribute__ ((section(".custom_defaults_end_address"))) *customDefaultsEnd = CUSTOM_DEFAULTS_END; -#endif - #define ERROR_INVALID_NAME "INVALID NAME: %s" #define ERROR_MESSAGE "%s CANNOT BE CHANGED. CURRENT VALUE: '%s'" @@ -714,33 +690,14 @@ static bool isReadingConfigFromCopy(void) static bool isWritingConfigToCopy(void) { - return configIsInCopy -#if defined(USE_CUSTOM_DEFAULTS) - && !processingCustomDefaults -#endif - ; + return configIsInCopy; } -#if defined(USE_CUSTOM_DEFAULTS) -static bool cliProcessCustomDefaults(bool quiet); -#endif - -static void backupAndResetConfigs(const bool useCustomDefaults) +static void backupAndResetConfigs(void) { backupConfigs(); - // reset all configs to defaults to do differencing resetConfig(); - -#if defined(USE_CUSTOM_DEFAULTS) - if (useCustomDefaults) { - if (!cliProcessCustomDefaults(true)) { - cliPrintLine("###WARNING: NO CUSTOM DEFAULTS FOUND###"); - } - } -#else - UNUSED(useCustomDefaults); -#endif } static uint8_t getPidProfileIndexToUse(void) @@ -956,14 +913,7 @@ static void cliRepeat(char ch, uint8_t len) static void cliPrompt(void) { -#if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS) - if (processingCustomDefaults) { - cliPrint("\r\nd: #"); - } else -#endif - { - cliPrint("\r\n# "); - } + cliPrint("\r\n# "); } static void cliShowParseError(const char *cmdName) @@ -4202,11 +4152,6 @@ static void cliBatch(const char *cmdName, char *cmdline) static bool prepareSave(void) { -#if defined(USE_CUSTOM_DEFAULTS) - if (processingCustomDefaults) { - return true; - } -#endif #ifdef USE_CLI_BATCH if (commandBatchActive && commandBatchError) { @@ -4258,66 +4203,10 @@ static void cliSave(const char *cmdName, char *cmdline) } } -#if defined(USE_CUSTOM_DEFAULTS) -bool resetConfigToCustomDefaults(void) -{ - resetConfig(); - -#ifdef USE_CLI_BATCH - commandBatchError = false; -#endif - - cliProcessCustomDefaults(true); - -#if defined(USE_SIMPLIFIED_TUNING) - applySimplifiedTuningAllProfiles(); -#endif - - return prepareSave(); -} - -static bool customDefaultsHasNext(const char *customDefaultsPtr) -{ - return *customDefaultsPtr && *customDefaultsPtr != 0xFF && customDefaultsPtr < customDefaultsEnd; -} - -static void parseCustomDefaultsHeader(void) -{ - const char *customDefaultsPtr = customDefaultsStart; - if (strncmp(customDefaultsPtr, CUSTOM_DEFAULTS_START_PREFIX, strlen(CUSTOM_DEFAULTS_START_PREFIX)) == 0) { - customDefaultsFound = true; - - customDefaultsPtr = strchr(customDefaultsPtr, '\n'); - if (customDefaultsPtr && customDefaultsHasNext(customDefaultsPtr)) { - customDefaultsPtr++; - } - } - - customDefaultsHeaderParsed = true; -} - -bool hasCustomDefaults(void) -{ - if (!customDefaultsHeaderParsed) { - parseCustomDefaultsHeader(); - } - - return customDefaultsFound; -} -#endif - static void cliDefaults(const char *cmdName, char *cmdline) { bool saveConfigs = true; uint16_t parameterGroupId = 0; -#if defined(USE_CUSTOM_DEFAULTS) - bool useCustomDefaults = true; -#elif defined(USE_CUSTOM_DEFAULTS_ADDRESS) - // Required to keep the linker from eliminating these - if (customDefaultsStart != customDefaultsEnd) { - delay(0); - } -#endif char *saveptr; char* tok = strtok_r(cmdline, " ", &saveptr); @@ -4330,35 +4219,12 @@ static void cliDefaults(const char *cmdName, char *cmdline) if (!parameterGroupId) { cliShowParseError(cmdName); - return; } } else if (strcasestr(tok, "group_id")) { expectParameterGroupId = true; } else if (strcasestr(tok, "nosave")) { saveConfigs = false; -#if defined(USE_CUSTOM_DEFAULTS) - } else if (strcasestr(tok, "bare")) { - useCustomDefaults = false; - } else if (strcasestr(tok, "show")) { - if (index != 0) { - cliShowParseError(cmdName); - } else if (hasCustomDefaults()) { - char *customDefaultsPtr = customDefaultsStart; - while (customDefaultsHasNext(customDefaultsPtr)) { - if (*customDefaultsPtr != '\n') { - cliPrintf("%c", *customDefaultsPtr++); - } else { - cliPrintLinefeed(); - customDefaultsPtr++; - } - } - } else { - cliPrintError(cmdName, "NO CUSTOM DEFAULTS FOUND"); - } - - return; -#endif } else { cliShowParseError(cmdName); @@ -4392,12 +4258,6 @@ static void cliDefaults(const char *cmdName, char *cmdline) commandBatchError = false; #endif -#if defined(USE_CUSTOM_DEFAULTS) - if (useCustomDefaults) { - cliProcessCustomDefaults(false); - } -#endif - #if defined(USE_SIMPLIFIED_TUNING) applySimplifiedTuningAllProfiles(); #endif @@ -4436,7 +4296,7 @@ STATIC_UNIT_TESTED void cliGet(const char *cmdName, char *cmdline) pidProfileIndexToUse = getCurrentPidProfileIndex(); rateProfileIndexToUse = getCurrentControlRateProfileIndex(); - backupAndResetConfigs(true); + backupAndResetConfigs(); for (uint32_t i = 0; i < valueTableEntryCount; i++) { if (strcasestr(valueTable[i].name, cmdline)) { @@ -4943,13 +4803,8 @@ static void cliTasks(const char *cmdName, char *cmdline) } } -static void printVersion(const char *cmdName, bool printBoardInfo) +static void printVersion(bool printBoardInfo) { -#if !(defined(USE_CUSTOM_DEFAULTS)) - UNUSED(cmdName); - UNUSED(printBoardInfo); -#endif - cliPrintf("# %s / %s (%s) %s %s / %s (%s) MSP API: %s", FC_FIRMWARE_NAME, targetName, @@ -4963,26 +4818,21 @@ static void printVersion(const char *cmdName, bool printBoardInfo) cliPrintLinefeed(); -#if defined(USE_CUSTOM_DEFAULTS) - if (hasCustomDefaults()) { - cliPrintHashLine("config: YES"); - } else { - cliPrintError(cmdName, "NO CONFIG FOUND"); - } -#endif // USE_CUSTOM_DEFAULTS - #if defined(USE_BOARD_INFO) if (printBoardInfo && strlen(getManufacturerId()) && strlen(getBoardName())) { cliPrintLinef("# board: manufacturer_id: %s, board_name: %s", getManufacturerId(), getBoardName()); } +#else + UNUSED(printBoardInfo); #endif } static void cliVersion(const char *cmdName, char *cmdline) { + UNUSED(cmdName); UNUSED(cmdline); - printVersion(cmdName, true); + printVersion(true); } #ifdef USE_RC_SMOOTHING_FILTER @@ -6248,14 +6098,14 @@ static void printConfig(const char *cmdName, char *cmdline, bool doDiff) dumpMask = dumpMask | BARE; // show the diff / dump without extra commands and board specific data } - backupAndResetConfigs((dumpMask & BARE) == 0); + backupAndResetConfigs(); #ifdef USE_CLI_BATCH bool batchModeEnabled = false; #endif if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) { cliPrintHashLine("version"); - printVersion(cmdName, false); + printVersion(false); if (!(dumpMask & BARE)) { #ifdef USE_CLI_BATCH @@ -6522,11 +6372,7 @@ const clicmd_t cmdTable[] = { #ifdef USE_LED_STRIP_STATUS_MODE CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor), #endif -#if defined(USE_CUSTOM_DEFAULTS) - CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{show} {nosave} {bare} {group_id }", cliDefaults), -#else CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{nosave}", cliDefaults), -#endif CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff), #ifdef USE_RESOURCE_MGMT @@ -6699,12 +6545,6 @@ static void processCharacter(const char c) // enter pressed cliPrintLinefeed(); -#if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS) - if (processingCustomDefaults) { - cliPrint("d: "); - } -#endif - // Strip comment starting with # from line char *p = cliBuffer; p = strchr(p, '#'); @@ -6826,56 +6666,6 @@ void cliProcess(void) } } -#if defined(USE_CUSTOM_DEFAULTS) -static bool cliProcessCustomDefaults(bool quiet) -{ - if (processingCustomDefaults || !hasCustomDefaults()) { - return false; - } - - bufWriter_t *cliWriterTemp = NULL; - if (quiet -#if !defined(DEBUG_CUSTOM_DEFAULTS) - || true -#endif - ) { - cliWriterTemp = cliWriter; - cliWriter = NULL; - } - if (quiet) { - cliErrorWriter = NULL; - } - - memcpy(cliBufferTemp, cliBuffer, sizeof(cliBuffer)); - uint32_t bufferIndexTemp = bufferIndex; - bufferIndex = 0; - processingCustomDefaults = true; - - char *customDefaultsPtr = customDefaultsStart; - while (customDefaultsHasNext(customDefaultsPtr)) { - processCharacter(*customDefaultsPtr++); - } - - // Process a newline at the very end so that the last command gets executed, - // even when the file did not contain a trailing newline - processCharacter('\r'); - - processingCustomDefaults = false; - - if (cliWriterTemp) { - cliWriter = cliWriterTemp; - cliErrorWriter = cliWriter; - } - - memcpy(cliBuffer, cliBufferTemp, sizeof(cliBuffer)); - bufferIndex = bufferIndexTemp; - - systemConfigMutable()->configurationState = CONFIGURATION_STATE_DEFAULTS_CUSTOM; - - return true; -} -#endif - void cliEnter(serialPort_t *serialPort) { cliMode = true; diff --git a/src/main/config/config.c b/src/main/config/config.c index 98bec7f38a..749c302409 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -797,20 +797,9 @@ void writeEEPROM(void) writeUnmodifiedConfigToEEPROM(); } -bool resetEEPROM(bool useCustomDefaults) +bool resetEEPROM(void) { -#if !defined(USE_CUSTOM_DEFAULTS) - UNUSED(useCustomDefaults); -#else - if (useCustomDefaults) { - if (!resetConfigToCustomDefaults()) { - return false; - } - } else -#endif - { - resetConfig(); - } + resetConfig(); writeUnmodifiedConfigToEEPROM(); @@ -822,7 +811,7 @@ void ensureEEPROMStructureIsValid(void) if (isEEPROMStructureValid()) { return; } - resetEEPROM(false); + resetEEPROM(); } void saveConfigAndNotify(void) diff --git a/src/main/config/config.h b/src/main/config/config.h index 3fe531d85f..3e3ea5131e 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -60,7 +60,7 @@ struct pidProfile_s; extern struct pidProfile_s *currentPidProfile; void initEEPROM(void); -bool resetEEPROM(bool useCustomDefaults); +bool resetEEPROM(void); bool readEEPROM(void); void writeEEPROM(void); void writeUnmodifiedConfigToEEPROM(void); diff --git a/src/main/drivers/at32/platform_mcu.h b/src/main/drivers/at32/platform_mcu.h index 708696b891..655ecb399a 100644 --- a/src/main/drivers/at32/platform_mcu.h +++ b/src/main/drivers/at32/platform_mcu.h @@ -72,7 +72,6 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define USE_TIMER_AF #define USE_DMA_SPEC #define USE_PERSISTENT_OBJECTS -#define USE_CUSTOM_DEFAULTS_ADDRESS #define USE_ADC_INTERNAL #define USE_LATE_TASK_STATISTICS diff --git a/src/main/drivers/stm32/platform_mcu.h b/src/main/drivers/stm32/platform_mcu.h index 3e4e70ade6..4271548f41 100644 --- a/src/main/drivers/stm32/platform_mcu.h +++ b/src/main/drivers/stm32/platform_mcu.h @@ -125,7 +125,6 @@ #define USE_MCO #define USE_DMA_SPEC #define USE_PERSISTENT_OBJECTS -#define USE_CUSTOM_DEFAULTS_ADDRESS #define USE_LATE_TASK_STATISTICS #if defined(STM32F40_41xxx) || defined(STM32F411xE) @@ -148,7 +147,6 @@ #define USE_MCO #define USE_DMA_SPEC #define USE_PERSISTENT_OBJECTS -#define USE_CUSTOM_DEFAULTS_ADDRESS #define USE_LATE_TASK_STATISTICS #endif // STM32F7 diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 5aa410f215..0de8a63e51 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -408,7 +408,7 @@ void init(void) #endif if (!readSuccess || !isEEPROMVersionValid() || strncasecmp(systemConfig()->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER))) { - resetEEPROM(false); + resetEEPROM(); } systemState |= SYSTEM_STATE_CONFIG_LOADED; @@ -463,7 +463,7 @@ void init(void) bothButtonsHeld = buttonAPressed() && buttonBPressed(); if (bothButtonsHeld) { if (--secondsRemaining == 0) { - resetEEPROM(false); + resetEEPROM(); #ifdef USE_PERSISTENT_OBJECTS persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); #endif diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index 4726bb34bc..72e8da47ef 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -672,12 +672,7 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce #if defined(USE_FLASH_BOOT_LOADER) targetCapabilities |= BIT(TARGET_HAS_FLASH_BOOTLOADER); #endif -#if defined(USE_CUSTOM_DEFAULTS) - targetCapabilities |= BIT(TARGET_SUPPORTS_CUSTOM_DEFAULTS); - if (hasCustomDefaults()) { - targetCapabilities |= BIT(TARGET_HAS_CUSTOM_DEFAULTS); - } -#endif + #if defined(USE_RX_BIND) if (getRxBindSupported()) { targetCapabilities |= BIT(TARGET_SUPPORTS_RX_BIND); @@ -2487,25 +2482,14 @@ static mspResult_e mspFcProcessOutCommandWithArg(mspDescriptor_t srcDesc, int16_ case MSP_RESET_CONF: { -#if defined(USE_CUSTOM_DEFAULTS) - defaultsType_e defaultsType = DEFAULTS_TYPE_CUSTOM; -#endif if (sbufBytesRemaining(src) >= 1) { // Added in MSP API 1.42 -#if defined(USE_CUSTOM_DEFAULTS) - defaultsType = sbufReadU8(src); -#else sbufReadU8(src); -#endif } bool success = false; if (!ARMING_FLAG(ARMED)) { -#if defined(USE_CUSTOM_DEFAULTS) - success = resetEEPROM(defaultsType == DEFAULTS_TYPE_CUSTOM); -#else - success = resetEEPROM(false); -#endif + success = resetEEPROM(); if (success && mspPostProcessFn) { rebootMode = MSP_REBOOT_FIRMWARE; diff --git a/src/main/sensors/gyro_init.c b/src/main/sensors/gyro_init.c index 68b0c10366..a072ca37de 100644 --- a/src/main/sensors/gyro_init.c +++ b/src/main/sensors/gyro_init.c @@ -663,9 +663,6 @@ bool gyroInit(void) detectedSensors[SENSOR_INDEX_GYRO] = gyro.gyroSensor2.gyroDev.gyroHardware; } #endif -#ifdef USE_CUSTOM_DEFAULTS - eepromWriteRequired = eepromWriteRequired && systemConfig()->configurationState != CONFIGURATION_STATE_DEFAULTS_BARE; -#endif if (eepromWriteRequired) { writeEEPROM(); diff --git a/src/main/target/AT32F435/target.h b/src/main/target/AT32F435/target.h index 3d6c71eac0..1eb9846ca5 100644 --- a/src/main/target/AT32F435/target.h +++ b/src/main/target/AT32F435/target.h @@ -59,11 +59,10 @@ #define USE_ADC -#define USE_CUSTOM_DEFAULTS #define USE_PWM_OUTPUT // Remove these undefines as support is added -#undef USE_BEEPER +//#undef USE_BEEPER #undef USE_LED_STRIP #undef USE_TRANSPONDER #undef USE_DSHOT @@ -73,10 +72,10 @@ #undef USE_RX_SPI #undef USE_RX_CC2500 #undef USE_RX_EXPRESSLRS -#undef USE_CMS -#undef USE_OSD +//#undef USE_CMS +//#undef USE_OSD #undef USE_BLACKBOX -#undef USE_SDCARD +//#undef USE_SDCARD //#undef USE_BARO //#undef USE_MAG #undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER diff --git a/src/main/target/STM32F405/target.h b/src/main/target/STM32F405/target.h index 53b4e3cbfa..b7e8593948 100644 --- a/src/main/target/STM32F405/target.h +++ b/src/main/target/STM32F405/target.h @@ -76,7 +76,6 @@ #define USE_ADC -#define USE_CUSTOM_DEFAULTS #define USE_EXTI #define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors diff --git a/src/main/target/STM32F411/target.h b/src/main/target/STM32F411/target.h index 4c890ab172..f07f5700e6 100644 --- a/src/main/target/STM32F411/target.h +++ b/src/main/target/STM32F411/target.h @@ -73,7 +73,6 @@ #define USE_ADC -#define USE_CUSTOM_DEFAULTS #define USE_EXTI #define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors diff --git a/src/main/target/STM32F745/target.h b/src/main/target/STM32F745/target.h index b6e3fa69a5..26bd42f6fe 100644 --- a/src/main/target/STM32F745/target.h +++ b/src/main/target/STM32F745/target.h @@ -83,7 +83,6 @@ #define USE_ADC -#define USE_CUSTOM_DEFAULTS #define USE_EXTI #define FLASH_PAGE_SIZE ((uint32_t)0x8000) // 32K sectors diff --git a/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h index f8ba42b49a..6f8e266cd9 100644 --- a/src/main/target/STM32F7X2/target.h +++ b/src/main/target/STM32F7X2/target.h @@ -74,8 +74,5 @@ #define USE_ESCSERIAL #define USE_ADC - -#define USE_CUSTOM_DEFAULTS #define USE_EXTI - #define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors diff --git a/src/main/target/STM32G47X/target.h b/src/main/target/STM32G47X/target.h index 9dfdef5bf1..5b1bce67ff 100644 --- a/src/main/target/STM32G47X/target.h +++ b/src/main/target/STM32G47X/target.h @@ -73,8 +73,6 @@ #define USE_ESCSERIAL #define USE_ADC - -#define USE_CUSTOM_DEFAULTS #define USE_EXTI #define USE_TIMER_UP_CONFIG diff --git a/src/main/target/STM32H723/target.h b/src/main/target/STM32H723/target.h index e7947bd1b7..72fc6c1271 100644 --- a/src/main/target/STM32H723/target.h +++ b/src/main/target/STM32H723/target.h @@ -94,10 +94,6 @@ #define USE_ADC -#if !defined(USE_EXST) -#define USE_CUSTOM_DEFAULTS -#endif - #define USE_EXTI #define USE_TIMER_UP_CONFIG diff --git a/src/main/target/STM32H743/target.h b/src/main/target/STM32H743/target.h index bb6379c732..9714f9da08 100644 --- a/src/main/target/STM32H743/target.h +++ b/src/main/target/STM32H743/target.h @@ -82,8 +82,6 @@ #define USE_ESCSERIAL #define USE_ADC - -#define USE_CUSTOM_DEFAULTS #define USE_EXTI #define USE_TIMER_UP_CONFIG diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index e36db821d3..be7ddda9bb 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -548,10 +548,6 @@ extern uint8_t __config_end; #undef USE_ABSOLUTE_CONTROL #endif -#if defined(USE_CUSTOM_DEFAULTS) -#define USE_CUSTOM_DEFAULTS_ADDRESS -#endif - #if defined(USE_RX_EXPRESSLRS) // ELRS depends on CRSF telemetry #if !defined(USE_TELEMETRY) diff --git a/src/test/unit/cli_unittest.cc b/src/test/unit/cli_unittest.cc index 3810dae587..853278c206 100644 --- a/src/test/unit/cli_unittest.cc +++ b/src/test/unit/cli_unittest.cc @@ -272,7 +272,7 @@ void beeperOffSet(uint32_t) {} void beeperOffClear(uint32_t) {} void beeperOffClearAll(void) {} bool parseColor(int, const char *) {return false; } -bool resetEEPROM(bool) { return true; } +bool resetEEPROM(void) { return true; } void bufWriterFlush(bufWriter_t *) {} void mixerResetDisarmedMotors(void) {} void gpsEnablePassthrough(struct serialPort_s *) {}