mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
Experimental support for on-board custom defaults.
This commit is contained in:
parent
b310f9b348
commit
7518ec67f5
19 changed files with 390 additions and 174 deletions
|
@ -24,7 +24,8 @@ MEMORY
|
|||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 976K : 992K
|
||||
FLASH_CUSTOM_DEFAULTS (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
|
||||
|
||||
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||
|
||||
|
@ -38,4 +39,8 @@ REGION_ALIAS("STACKRAM", CCM)
|
|||
REGION_ALIAS("FASTRAM", CCM)
|
||||
REGION_ALIAS("VECTAB", RAM)
|
||||
|
||||
/* Base address where the defaults are stored. */
|
||||
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
|
||||
INCLUDE "stm32_flash_split.ld"
|
||||
|
|
|
@ -24,7 +24,8 @@ MEMORY
|
|||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 464K : 480K
|
||||
FLASH_CUSTOM_DEFAULTS (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
|
||||
|
||||
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||
|
||||
|
@ -36,4 +37,8 @@ REGION_ALIAS("STACKRAM", RAM)
|
|||
REGION_ALIAS("FASTRAM", RAM)
|
||||
REGION_ALIAS("VECTAB", RAM)
|
||||
|
||||
/* Base address where the defaults are stored. */
|
||||
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
|
||||
INCLUDE "stm32_flash_split.ld"
|
||||
|
|
|
@ -31,7 +31,8 @@ MEMORY
|
|||
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 464K : 480K
|
||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
|
||||
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
|
||||
|
@ -42,9 +43,14 @@ MEMORY
|
|||
REGION_ALIAS("FLASH", AXIM_FLASH)
|
||||
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
|
||||
REGION_ALIAS("FLASH1", AXIM_FLASH1)
|
||||
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
|
||||
REGION_ALIAS("STACKRAM", DTCM_RAM)
|
||||
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
||||
REGION_ALIAS("RAM", SRAM1)
|
||||
|
||||
/* Base address where the defaults are stored. */
|
||||
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
|
||||
INCLUDE "stm32_flash_f7_split.ld"
|
||||
|
|
|
@ -33,7 +33,8 @@ MEMORY
|
|||
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 928K : 960K
|
||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x080F8000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 32K : 0K
|
||||
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
|
||||
|
@ -44,9 +45,14 @@ MEMORY
|
|||
REGION_ALIAS("FLASH", ITCM_FLASH)
|
||||
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
|
||||
REGION_ALIAS("FLASH1", ITCM_FLASH1)
|
||||
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
|
||||
REGION_ALIAS("STACKRAM", DTCM_RAM)
|
||||
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
||||
REGION_ALIAS("RAM", SRAM1)
|
||||
|
||||
/* Base address where the defaults are stored. */
|
||||
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
|
||||
INCLUDE "stm32_flash_f7_split.ld"
|
||||
|
|
|
@ -34,6 +34,13 @@ SECTIONS
|
|||
. = ALIGN(4);
|
||||
} >FLASH AT >AXIM_FLASH
|
||||
|
||||
/* Storage for the address for the configuration section so we can grab it out of the hex file */
|
||||
.custom_defaults :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.custom_defaults_address)
|
||||
} >FLASH1 AT >AXIM_FLASH1
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
|
|
|
@ -55,6 +55,13 @@ SECTIONS
|
|||
. = ALIGN(4);
|
||||
} >SYSTEM_MEMORY
|
||||
|
||||
/* Storage for the address for the configuration section so we can grab it out of the hex file */
|
||||
.custom_defaults :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.custom_defaults_address)
|
||||
} >FLASH1
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue