mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 03:50:02 +03:00
Added support for custom defaults in sector 0.
This commit is contained in:
parent
7518ec67f5
commit
2c8d197ccb
20 changed files with 84 additions and 74 deletions
8
Makefile
8
Makefile
|
@ -31,7 +31,7 @@ EXST ?= no
|
|||
RAM_BASED ?= no
|
||||
|
||||
# reserve space for custom defaults
|
||||
CUSTOM_DEFAULTS ?= no
|
||||
CUSTOM_DEFAULTS_EXTENDED ?= no
|
||||
|
||||
# Debugger optons:
|
||||
# empty - ordinary build with all optimizations enabled
|
||||
|
@ -189,9 +189,9 @@ else
|
|||
.DEFAULT_GOAL := hex
|
||||
endif
|
||||
|
||||
ifeq ($(CUSTOM_DEFAULTS),yes)
|
||||
TARGET_FLAGS += -DUSE_CUSTOM_DEFAULTS
|
||||
EXTRA_LD_FLAGS += -Wl,--defsym=USE_CUSTOM_DEFAULTS=1
|
||||
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) \
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x080FFFFF 1024K full flash,
|
||||
0x08000000 to 0x08003FFF 16K isr vector, startup code,
|
||||
|
@ -22,10 +19,11 @@ ENTRY(Reset_Handler)
|
|||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
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
|
||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
|
||||
|
||||
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||
|
||||
|
@ -39,8 +37,4 @@ 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"
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x080FFFFF 1024K full flash,
|
||||
0x08000000 to 0x08003FFF 16K OPBL,
|
||||
|
|
|
@ -9,12 +9,10 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x0807FFFF 512K full flash,
|
||||
0x08000000 to 0x08003FFF 16K isr vector, startup code,
|
||||
|
||||
0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1
|
||||
0x08008000 to 0x0807FFFF 480K firmware,
|
||||
*/
|
||||
|
@ -22,10 +20,11 @@ ENTRY(Reset_Handler)
|
|||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
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
|
||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
|
||||
|
||||
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||
|
||||
|
@ -37,8 +36,4 @@ 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"
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x0807FFFF 512K full flash,
|
||||
0x08000000 to 0x08003FFF 16K OPBL,
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x0807FFFF 512K full flash,
|
||||
0x08000000 to 0x08003FFF 16K isr vector, startup code,
|
||||
|
@ -22,7 +19,8 @@ ENTRY(Reset_Handler)
|
|||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x0807FFFF 512K full flash
|
||||
0x08000000 to 0x08003FFF 16K ISR vector
|
||||
|
@ -29,10 +26,11 @@ MEMORY
|
|||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
|
||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
|
||||
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
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
|
||||
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
|
||||
|
||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
|
||||
|
@ -41,16 +39,13 @@ MEMORY
|
|||
}
|
||||
|
||||
REGION_ALIAS("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("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
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)
|
||||
|
||||
/* 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"
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x00000000 to 0x00003FFF 16K TCM RAM,
|
||||
|
||||
|
@ -31,10 +28,11 @@ MEMORY
|
|||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K
|
||||
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 22K
|
||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
||||
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
|
||||
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
|
||||
|
@ -43,16 +41,13 @@ MEMORY
|
|||
}
|
||||
|
||||
REGION_ALIAS("FLASH", ITCM_FLASH)
|
||||
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
|
||||
REGION_ALIAS("FLASH1", ITCM_FLASH1)
|
||||
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
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)
|
||||
|
||||
/* 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"
|
||||
|
|
|
@ -9,9 +9,6 @@
|
|||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x00000000 to 0x00003FFF 16K TCM RAM,
|
||||
|
||||
|
@ -30,7 +27,8 @@ MEMORY
|
|||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
|
||||
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 22K
|
||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K
|
||||
|
||||
|
@ -41,6 +39,7 @@ MEMORY
|
|||
}
|
||||
|
||||
REGION_ALIAS("FLASH", AXIM_FLASH)
|
||||
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
|
||||
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
|
||||
REGION_ALIAS("FLASH1", AXIM_FLASH1)
|
||||
|
||||
|
|
|
@ -99,6 +99,21 @@ SECTIONS
|
|||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >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);
|
||||
KEEP (*(.custom_defaults_address))
|
||||
. = ALIGN(4);
|
||||
__custom_defaults_internal_start = .;
|
||||
KEEP (*(.custom_defaults));
|
||||
. = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_internal_end = .;
|
||||
} >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) : __custom_defaults_internal_end);
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
|
|
|
@ -55,13 +55,6 @@ 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 :
|
||||
{
|
||||
|
@ -123,6 +116,21 @@ SECTIONS
|
|||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* 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_address))
|
||||
. = ALIGN(4);
|
||||
__custom_defaults_internal_start = .;
|
||||
KEEP (*(.custom_defaults));
|
||||
. = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
|
||||
__custom_defaults_internal_end = .;
|
||||
} >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) : __custom_defaults_internal_end);
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
|
|
|
@ -212,14 +212,22 @@ static bool signatureUpdated = false;
|
|||
static const char* const emptyName = "-";
|
||||
static const char* const emptyString = "";
|
||||
|
||||
#if defined(USE_CUSTOM_DEFAULTS)
|
||||
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsStart = &__custom_defaults_start;
|
||||
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsEnd = &__custom_defaults_end;
|
||||
#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];
|
||||
#endif
|
||||
|
||||
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsStart = CUSTOM_DEFAULTS_START;
|
||||
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsEnd = CUSTOM_DEFAULTS_END;
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
// sync this with mixerMode_e
|
||||
static const char * const mixerNames[] = {
|
||||
|
@ -4178,6 +4186,11 @@ static void cliDefaults(char *cmdline)
|
|||
bool saveConfigs = true;
|
||||
#if defined(USE_CUSTOM_DEFAULTS)
|
||||
bool useCustomDefaults = true;
|
||||
#else
|
||||
// Required to keep the linker from eliminating these
|
||||
if (customDefaultsStart != customDefaultsEnd) {
|
||||
delay(0);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
|
@ -6454,7 +6467,7 @@ void cliProcessCustomDefaults(void)
|
|||
bufferIndex = 0;
|
||||
processingCustomDefaults = true;
|
||||
|
||||
while (*ptr && ptr != 0xFF && ptr < customDefaultsEnd) {
|
||||
while (*ptr && *ptr != 0xFF && ptr < customDefaultsEnd) {
|
||||
processCommandCharacter(*ptr++);
|
||||
}
|
||||
|
||||
|
|
|
@ -56,6 +56,8 @@
|
|||
#define USBD_PRODUCT_STRING "OmnibusF4"
|
||||
#endif
|
||||
|
||||
#define USE_CUSTOM_DEFAULTS
|
||||
|
||||
#define LED0_PIN PB5
|
||||
#define USE_BEEPER
|
||||
#define BEEPER_PIN PB4
|
||||
|
|
|
@ -2,7 +2,7 @@ F405_TARGETS += $(TARGET)
|
|||
|
||||
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
|
||||
|
||||
CUSTOM_DEFAULTS = yes
|
||||
CUSTOM_DEFAULTS_EXTENDED = yes
|
||||
|
||||
TARGET_SRC = \
|
||||
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
|
||||
|
|
|
@ -2,7 +2,7 @@ F411_TARGETS += $(TARGET)
|
|||
|
||||
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
|
||||
|
||||
CUSTOM_DEFAULTS = yes
|
||||
CUSTOM_DEFAULTS_EXTENDED = yes
|
||||
|
||||
TARGET_SRC = \
|
||||
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
|
||||
|
|
|
@ -2,7 +2,7 @@ F7X5XG_TARGETS += $(TARGET)
|
|||
|
||||
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
|
||||
|
||||
CUSTOM_DEFAULTS = yes
|
||||
CUSTOM_DEFAULTS_EXTENDED = yes
|
||||
|
||||
TARGET_SRC = \
|
||||
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
|
||||
|
|
|
@ -2,7 +2,7 @@ F7X2RE_TARGETS += $(TARGET)
|
|||
|
||||
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
|
||||
|
||||
CUSTOM_DEFAULTS = yes
|
||||
CUSTOM_DEFAULTS_EXTENDED = yes
|
||||
|
||||
TARGET_SRC = \
|
||||
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
|
||||
|
|
|
@ -359,8 +359,6 @@ extern uint8_t eepromData[EEPROM_SIZE];
|
|||
#endif
|
||||
extern uint8_t __config_start; // configured via linker script when building binaries.
|
||||
extern uint8_t __config_end;
|
||||
extern char __custom_defaults_start;
|
||||
extern char __custom_defaults_end;
|
||||
#endif
|
||||
|
||||
#if defined(USE_EXST) && !defined(RAMBASED)
|
||||
|
|
|
@ -117,3 +117,5 @@
|
|||
|
||||
#define USE_RX_FLYSKY
|
||||
#define USE_RX_FLYSKY_SPI_LED
|
||||
|
||||
#define USE_CUSTOM_DEFAULTS
|
||||
|
|
|
@ -357,4 +357,6 @@ bool persistBoardInformation(void) { return true; };
|
|||
void activeAdjustmentRangeReset(void) {}
|
||||
void analyzeModeActivationConditions(void) {}
|
||||
bool isModeActivationConditionConfigured(const modeActivationCondition_t *, const modeActivationCondition_t *) { return false; }
|
||||
|
||||
void delay(uint32_t) {}
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue