mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
Removing Custom Defaults (#12425)
This commit is contained in:
parent
68136910d0
commit
ee77239db1
48 changed files with 155 additions and 552 deletions
5
Makefile
5
Makefile
|
@ -214,11 +214,6 @@ TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
||||||
|
|
||||||
.DEFAULT_GOAL := hex
|
.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) \
|
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(ROOT)/lib/main/MAVLink
|
$(ROOT)/lib/main/MAVLink
|
||||||
|
|
||||||
|
|
|
@ -18,21 +18,16 @@
|
||||||
*****************************************************************************
|
*****************************************************************************
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
FLASH : 0x0800 0000 -- 0x083E FFFF
|
FLASH : 0x0800 0000 -- 0x083E FFFF
|
||||||
MEM : 0x2000 0000 -- 0x2007 FFFF
|
MEM : 0x2000 0000 -- 0x2007 FFFF
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||||
FLASH_CDEF (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 3984K: 4000K
|
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 4000K
|
||||||
FLASH_CDEF_EXT (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x083EC000 : 0x083F0000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
|
|
||||||
|
|
||||||
SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K
|
SYSTEM_MEMORY (rx) : ORIGIN = 0x1FFF0000, LENGTH = 16K
|
||||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K
|
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */
|
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K /* external ram */
|
||||||
|
|
|
@ -88,7 +88,6 @@ SECTIONS
|
||||||
tcm_code_end = .;
|
tcm_code_end = .;
|
||||||
} >RAM AT >FLASH1
|
} >RAM AT >FLASH1
|
||||||
|
|
||||||
|
|
||||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||||
.ARM : {
|
.ARM : {
|
||||||
__exidx_start = .;
|
__exidx_start = .;
|
||||||
|
@ -130,22 +129,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -66,7 +66,6 @@ SECTIONS
|
||||||
ccm_code_end = .;
|
ccm_code_end = .;
|
||||||
} >CCM AT >FLASH
|
} >CCM AT >FLASH
|
||||||
|
|
||||||
|
|
||||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||||
.ARM : {
|
.ARM : {
|
||||||
__exidx_start = .;
|
__exidx_start = .;
|
||||||
|
|
|
@ -19,11 +19,9 @@
|
||||||
/* Specify the memory areas */
|
/* Specify the memory areas */
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 976K : 992K
|
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K
|
||||||
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
|
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||||
|
|
||||||
|
|
|
@ -20,11 +20,9 @@
|
||||||
/* Specify the memory areas */
|
/* Specify the memory areas */
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 464K : 480K
|
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 16K : 0K
|
|
||||||
|
|
||||||
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
|
||||||
|
|
||||||
|
|
|
@ -116,22 +116,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -26,12 +26,10 @@ MEMORY
|
||||||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
|
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K
|
||||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
|
ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K
|
||||||
|
|
||||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
|
||||||
/* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */
|
/* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */
|
||||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 464K : 480K
|
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 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
|
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||||
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
|
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
|
||||||
|
@ -41,11 +39,9 @@ MEMORY
|
||||||
|
|
||||||
REGION_ALIAS("FLASH", AXIM_FLASH)
|
REGION_ALIAS("FLASH", AXIM_FLASH)
|
||||||
REGION_ALIAS("WRITABLE_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_CONFIG", AXIM_FLASH_CONFIG)
|
||||||
REGION_ALIAS("FLASH1", AXIM_FLASH1)
|
REGION_ALIAS("FLASH1", AXIM_FLASH1)
|
||||||
REGION_ALIAS("WRITABLE_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("STACKRAM", DTCM_RAM)
|
||||||
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
||||||
|
|
|
@ -28,13 +28,10 @@ MEMORY
|
||||||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
||||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K
|
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K
|
||||||
|
|
||||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
|
|
||||||
AXIM_FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
|
|
||||||
/* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */
|
/* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */
|
||||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
||||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 928K : 960K
|
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 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
|
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||||
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
|
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
|
||||||
|
@ -44,11 +41,9 @@ MEMORY
|
||||||
|
|
||||||
REGION_ALIAS("FLASH", ITCM_FLASH)
|
REGION_ALIAS("FLASH", ITCM_FLASH)
|
||||||
REGION_ALIAS("WRITABLE_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_CONFIG", AXIM_FLASH_CONFIG)
|
||||||
REGION_ALIAS("FLASH1", ITCM_FLASH1)
|
REGION_ALIAS("FLASH1", ITCM_FLASH1)
|
||||||
REGION_ALIAS("WRITABLE_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("STACKRAM", DTCM_RAM)
|
||||||
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
REGION_ALIAS("FASTRAM", DTCM_RAM)
|
||||||
|
|
|
@ -28,9 +28,7 @@ MEMORY
|
||||||
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K
|
||||||
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
|
ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K
|
||||||
|
|
||||||
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||||
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
|
|
||||||
AXIM_FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 12K
|
|
||||||
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
|
||||||
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K
|
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K
|
||||||
|
|
||||||
|
|
|
@ -92,22 +92,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >WRITABLE_FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -13,11 +13,8 @@
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
||||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 8K
|
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 8K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08006000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 480K : 488K
|
FLASH1 (rx) : ORIGIN = 0x08006000, LENGTH = 496K
|
||||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x0807E000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 8K : 0K
|
|
||||||
|
|
||||||
|
|
||||||
SYSTEM_MEMORY (r) : ORIGIN = 0x1FFF0000, LENGTH = 64K
|
SYSTEM_MEMORY (r) : ORIGIN = 0x1FFF0000, LENGTH = 64K
|
||||||
/* Below are the true lengths for normal and close coupled RAM
|
/* Below are the true lengths for normal and close coupled RAM
|
||||||
|
|
|
@ -119,22 +119,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -36,13 +36,9 @@ ENTRY(Reset_Handler)
|
||||||
/* Specify the memory areas */
|
/* Specify the memory areas */
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
|
|
||||||
FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K
|
|
||||||
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
|
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 640K : 768K
|
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 768K
|
||||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x081E0000 : 0x08200000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 128K : 0K
|
|
||||||
|
|
||||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
@ -139,21 +135,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -37,13 +37,9 @@ ENTRY(Reset_Handler)
|
||||||
/* Specify the memory areas */
|
/* Specify the memory areas */
|
||||||
MEMORY
|
MEMORY
|
||||||
{
|
{
|
||||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
|
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||||
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
|
|
||||||
FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K
|
|
||||||
|
|
||||||
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
|
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
|
||||||
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 1664K : 1792K
|
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 1792K
|
||||||
FLASH_CUSTOM_DEFAULTS_EXTENDED (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 0x081E0000 : 0x08200000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 128K : 0K
|
|
||||||
|
|
||||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||||
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
@ -141,21 +137,6 @@ SECTIONS
|
||||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||||
} >FLASH1
|
} >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 */
|
/* used by the startup to initialize data */
|
||||||
_sidata = LOADADDR(.data);
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
|
|
@ -140,4 +140,3 @@ SECTIONS
|
||||||
|
|
||||||
INCLUDE "stm32_h723_common_post.ld"
|
INCLUDE "stm32_h723_common_post.ld"
|
||||||
INCLUDE "stm32_ram_h723_exst_post.ld"
|
INCLUDE "stm32_ram_h723_exst_post.ld"
|
||||||
|
|
||||||
|
|
|
@ -140,4 +140,3 @@ SECTIONS
|
||||||
|
|
||||||
INCLUDE "stm32_h730_common_post.ld"
|
INCLUDE "stm32_h730_common_post.ld"
|
||||||
INCLUDE "stm32_ram_h730_exst_post.ld"
|
INCLUDE "stm32_ram_h730_exst_post.ld"
|
||||||
|
|
||||||
|
|
|
@ -141,4 +141,3 @@ SECTIONS
|
||||||
|
|
||||||
INCLUDE "stm32_h750_common_post.ld"
|
INCLUDE "stm32_h750_common_post.ld"
|
||||||
INCLUDE "stm32_ram_h750_exst_post.ld"
|
INCLUDE "stm32_ram_h750_exst_post.ld"
|
||||||
|
|
||||||
|
|
|
@ -209,33 +209,9 @@ static bool signatureUpdated = false;
|
||||||
static const char* const emptyName = "-";
|
static const char* const emptyName = "-";
|
||||||
static const char* const emptyString = "";
|
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_CHANGESET_ID_LENGTH 8
|
||||||
#define MAX_DATE_LENGTH 20
|
#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_INVALID_NAME "INVALID NAME: %s"
|
||||||
#define ERROR_MESSAGE "%s CANNOT BE CHANGED. CURRENT VALUE: '%s'"
|
#define ERROR_MESSAGE "%s CANNOT BE CHANGED. CURRENT VALUE: '%s'"
|
||||||
|
|
||||||
|
@ -714,33 +690,14 @@ static bool isReadingConfigFromCopy(void)
|
||||||
|
|
||||||
static bool isWritingConfigToCopy(void)
|
static bool isWritingConfigToCopy(void)
|
||||||
{
|
{
|
||||||
return configIsInCopy
|
return configIsInCopy;
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
&& !processingCustomDefaults
|
|
||||||
#endif
|
|
||||||
;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
static void backupAndResetConfigs(void)
|
||||||
static bool cliProcessCustomDefaults(bool quiet);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static void backupAndResetConfigs(const bool useCustomDefaults)
|
|
||||||
{
|
{
|
||||||
backupConfigs();
|
backupConfigs();
|
||||||
|
|
||||||
// reset all configs to defaults to do differencing
|
// reset all configs to defaults to do differencing
|
||||||
resetConfig();
|
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)
|
static uint8_t getPidProfileIndexToUse(void)
|
||||||
|
@ -955,16 +912,9 @@ static void cliRepeat(char ch, uint8_t len)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void cliPrompt(void)
|
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)
|
static void cliShowParseError(const char *cmdName)
|
||||||
{
|
{
|
||||||
|
@ -4202,11 +4152,6 @@ static void cliBatch(const char *cmdName, char *cmdline)
|
||||||
|
|
||||||
static bool prepareSave(void)
|
static bool prepareSave(void)
|
||||||
{
|
{
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
if (processingCustomDefaults) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_CLI_BATCH
|
#ifdef USE_CLI_BATCH
|
||||||
if (commandBatchActive && commandBatchError) {
|
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)
|
static void cliDefaults(const char *cmdName, char *cmdline)
|
||||||
{
|
{
|
||||||
bool saveConfigs = true;
|
bool saveConfigs = true;
|
||||||
uint16_t parameterGroupId = 0;
|
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 *saveptr;
|
||||||
char* tok = strtok_r(cmdline, " ", &saveptr);
|
char* tok = strtok_r(cmdline, " ", &saveptr);
|
||||||
|
@ -4330,35 +4219,12 @@ static void cliDefaults(const char *cmdName, char *cmdline)
|
||||||
|
|
||||||
if (!parameterGroupId) {
|
if (!parameterGroupId) {
|
||||||
cliShowParseError(cmdName);
|
cliShowParseError(cmdName);
|
||||||
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
} else if (strcasestr(tok, "group_id")) {
|
} else if (strcasestr(tok, "group_id")) {
|
||||||
expectParameterGroupId = true;
|
expectParameterGroupId = true;
|
||||||
} else if (strcasestr(tok, "nosave")) {
|
} else if (strcasestr(tok, "nosave")) {
|
||||||
saveConfigs = false;
|
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 {
|
} else {
|
||||||
cliShowParseError(cmdName);
|
cliShowParseError(cmdName);
|
||||||
|
|
||||||
|
@ -4392,12 +4258,6 @@ static void cliDefaults(const char *cmdName, char *cmdline)
|
||||||
commandBatchError = false;
|
commandBatchError = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
if (useCustomDefaults) {
|
|
||||||
cliProcessCustomDefaults(false);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_SIMPLIFIED_TUNING)
|
#if defined(USE_SIMPLIFIED_TUNING)
|
||||||
applySimplifiedTuningAllProfiles();
|
applySimplifiedTuningAllProfiles();
|
||||||
#endif
|
#endif
|
||||||
|
@ -4436,7 +4296,7 @@ STATIC_UNIT_TESTED void cliGet(const char *cmdName, char *cmdline)
|
||||||
pidProfileIndexToUse = getCurrentPidProfileIndex();
|
pidProfileIndexToUse = getCurrentPidProfileIndex();
|
||||||
rateProfileIndexToUse = getCurrentControlRateProfileIndex();
|
rateProfileIndexToUse = getCurrentControlRateProfileIndex();
|
||||||
|
|
||||||
backupAndResetConfigs(true);
|
backupAndResetConfigs();
|
||||||
|
|
||||||
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
|
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
|
||||||
if (strcasestr(valueTable[i].name, cmdline)) {
|
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",
|
cliPrintf("# %s / %s (%s) %s %s / %s (%s) MSP API: %s",
|
||||||
FC_FIRMWARE_NAME,
|
FC_FIRMWARE_NAME,
|
||||||
targetName,
|
targetName,
|
||||||
|
@ -4963,26 +4818,21 @@ static void printVersion(const char *cmdName, bool printBoardInfo)
|
||||||
|
|
||||||
cliPrintLinefeed();
|
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 defined(USE_BOARD_INFO)
|
||||||
if (printBoardInfo && strlen(getManufacturerId()) && strlen(getBoardName())) {
|
if (printBoardInfo && strlen(getManufacturerId()) && strlen(getBoardName())) {
|
||||||
cliPrintLinef("# board: manufacturer_id: %s, board_name: %s", getManufacturerId(), getBoardName());
|
cliPrintLinef("# board: manufacturer_id: %s, board_name: %s", getManufacturerId(), getBoardName());
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
UNUSED(printBoardInfo);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliVersion(const char *cmdName, char *cmdline)
|
static void cliVersion(const char *cmdName, char *cmdline)
|
||||||
{
|
{
|
||||||
|
UNUSED(cmdName);
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
|
||||||
printVersion(cmdName, true);
|
printVersion(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_RC_SMOOTHING_FILTER
|
#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
|
dumpMask = dumpMask | BARE; // show the diff / dump without extra commands and board specific data
|
||||||
}
|
}
|
||||||
|
|
||||||
backupAndResetConfigs((dumpMask & BARE) == 0);
|
backupAndResetConfigs();
|
||||||
|
|
||||||
#ifdef USE_CLI_BATCH
|
#ifdef USE_CLI_BATCH
|
||||||
bool batchModeEnabled = false;
|
bool batchModeEnabled = false;
|
||||||
#endif
|
#endif
|
||||||
if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
|
if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
|
||||||
cliPrintHashLine("version");
|
cliPrintHashLine("version");
|
||||||
printVersion(cmdName, false);
|
printVersion(false);
|
||||||
|
|
||||||
if (!(dumpMask & BARE)) {
|
if (!(dumpMask & BARE)) {
|
||||||
#ifdef USE_CLI_BATCH
|
#ifdef USE_CLI_BATCH
|
||||||
|
@ -6522,11 +6372,7 @@ const clicmd_t cmdTable[] = {
|
||||||
#ifdef USE_LED_STRIP_STATUS_MODE
|
#ifdef USE_LED_STRIP_STATUS_MODE
|
||||||
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
|
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{show} {nosave} {bare} {group_id <id>}", cliDefaults),
|
|
||||||
#else
|
|
||||||
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{nosave}", cliDefaults),
|
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),
|
CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff),
|
||||||
#ifdef USE_RESOURCE_MGMT
|
#ifdef USE_RESOURCE_MGMT
|
||||||
|
|
||||||
|
@ -6699,12 +6545,6 @@ static void processCharacter(const char c)
|
||||||
// enter pressed
|
// enter pressed
|
||||||
cliPrintLinefeed();
|
cliPrintLinefeed();
|
||||||
|
|
||||||
#if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS)
|
|
||||||
if (processingCustomDefaults) {
|
|
||||||
cliPrint("d: ");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Strip comment starting with # from line
|
// Strip comment starting with # from line
|
||||||
char *p = cliBuffer;
|
char *p = cliBuffer;
|
||||||
p = strchr(p, '#');
|
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)
|
void cliEnter(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
cliMode = true;
|
cliMode = true;
|
||||||
|
|
|
@ -797,20 +797,9 @@ void writeEEPROM(void)
|
||||||
writeUnmodifiedConfigToEEPROM();
|
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();
|
writeUnmodifiedConfigToEEPROM();
|
||||||
|
|
||||||
|
@ -822,7 +811,7 @@ void ensureEEPROMStructureIsValid(void)
|
||||||
if (isEEPROMStructureValid()) {
|
if (isEEPROMStructureValid()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
resetEEPROM(false);
|
resetEEPROM();
|
||||||
}
|
}
|
||||||
|
|
||||||
void saveConfigAndNotify(void)
|
void saveConfigAndNotify(void)
|
||||||
|
|
|
@ -60,7 +60,7 @@ struct pidProfile_s;
|
||||||
extern struct pidProfile_s *currentPidProfile;
|
extern struct pidProfile_s *currentPidProfile;
|
||||||
|
|
||||||
void initEEPROM(void);
|
void initEEPROM(void);
|
||||||
bool resetEEPROM(bool useCustomDefaults);
|
bool resetEEPROM(void);
|
||||||
bool readEEPROM(void);
|
bool readEEPROM(void);
|
||||||
void writeEEPROM(void);
|
void writeEEPROM(void);
|
||||||
void writeUnmodifiedConfigToEEPROM(void);
|
void writeUnmodifiedConfigToEEPROM(void);
|
||||||
|
|
|
@ -72,7 +72,6 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
#define USE_TIMER_AF
|
#define USE_TIMER_AF
|
||||||
#define USE_DMA_SPEC
|
#define USE_DMA_SPEC
|
||||||
#define USE_PERSISTENT_OBJECTS
|
#define USE_PERSISTENT_OBJECTS
|
||||||
#define USE_CUSTOM_DEFAULTS_ADDRESS
|
|
||||||
#define USE_ADC_INTERNAL
|
#define USE_ADC_INTERNAL
|
||||||
|
|
||||||
#define USE_LATE_TASK_STATISTICS
|
#define USE_LATE_TASK_STATISTICS
|
||||||
|
|
|
@ -125,7 +125,6 @@
|
||||||
#define USE_MCO
|
#define USE_MCO
|
||||||
#define USE_DMA_SPEC
|
#define USE_DMA_SPEC
|
||||||
#define USE_PERSISTENT_OBJECTS
|
#define USE_PERSISTENT_OBJECTS
|
||||||
#define USE_CUSTOM_DEFAULTS_ADDRESS
|
|
||||||
#define USE_LATE_TASK_STATISTICS
|
#define USE_LATE_TASK_STATISTICS
|
||||||
|
|
||||||
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
|
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
|
||||||
|
@ -148,7 +147,6 @@
|
||||||
#define USE_MCO
|
#define USE_MCO
|
||||||
#define USE_DMA_SPEC
|
#define USE_DMA_SPEC
|
||||||
#define USE_PERSISTENT_OBJECTS
|
#define USE_PERSISTENT_OBJECTS
|
||||||
#define USE_CUSTOM_DEFAULTS_ADDRESS
|
|
||||||
#define USE_LATE_TASK_STATISTICS
|
#define USE_LATE_TASK_STATISTICS
|
||||||
#endif // STM32F7
|
#endif // STM32F7
|
||||||
|
|
||||||
|
|
|
@ -408,7 +408,7 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!readSuccess || !isEEPROMVersionValid() || strncasecmp(systemConfig()->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER))) {
|
if (!readSuccess || !isEEPROMVersionValid() || strncasecmp(systemConfig()->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER))) {
|
||||||
resetEEPROM(false);
|
resetEEPROM();
|
||||||
}
|
}
|
||||||
|
|
||||||
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
systemState |= SYSTEM_STATE_CONFIG_LOADED;
|
||||||
|
@ -463,7 +463,7 @@ void init(void)
|
||||||
bothButtonsHeld = buttonAPressed() && buttonBPressed();
|
bothButtonsHeld = buttonAPressed() && buttonBPressed();
|
||||||
if (bothButtonsHeld) {
|
if (bothButtonsHeld) {
|
||||||
if (--secondsRemaining == 0) {
|
if (--secondsRemaining == 0) {
|
||||||
resetEEPROM(false);
|
resetEEPROM();
|
||||||
#ifdef USE_PERSISTENT_OBJECTS
|
#ifdef USE_PERSISTENT_OBJECTS
|
||||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
|
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -672,12 +672,7 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce
|
||||||
#if defined(USE_FLASH_BOOT_LOADER)
|
#if defined(USE_FLASH_BOOT_LOADER)
|
||||||
targetCapabilities |= BIT(TARGET_HAS_FLASH_BOOTLOADER);
|
targetCapabilities |= BIT(TARGET_HAS_FLASH_BOOTLOADER);
|
||||||
#endif
|
#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 defined(USE_RX_BIND)
|
||||||
if (getRxBindSupported()) {
|
if (getRxBindSupported()) {
|
||||||
targetCapabilities |= BIT(TARGET_SUPPORTS_RX_BIND);
|
targetCapabilities |= BIT(TARGET_SUPPORTS_RX_BIND);
|
||||||
|
@ -2487,25 +2482,14 @@ static mspResult_e mspFcProcessOutCommandWithArg(mspDescriptor_t srcDesc, int16_
|
||||||
|
|
||||||
case MSP_RESET_CONF:
|
case MSP_RESET_CONF:
|
||||||
{
|
{
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
defaultsType_e defaultsType = DEFAULTS_TYPE_CUSTOM;
|
|
||||||
#endif
|
|
||||||
if (sbufBytesRemaining(src) >= 1) {
|
if (sbufBytesRemaining(src) >= 1) {
|
||||||
// Added in MSP API 1.42
|
// Added in MSP API 1.42
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
defaultsType = sbufReadU8(src);
|
|
||||||
#else
|
|
||||||
sbufReadU8(src);
|
sbufReadU8(src);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool success = false;
|
bool success = false;
|
||||||
if (!ARMING_FLAG(ARMED)) {
|
if (!ARMING_FLAG(ARMED)) {
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
success = resetEEPROM();
|
||||||
success = resetEEPROM(defaultsType == DEFAULTS_TYPE_CUSTOM);
|
|
||||||
#else
|
|
||||||
success = resetEEPROM(false);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (success && mspPostProcessFn) {
|
if (success && mspPostProcessFn) {
|
||||||
rebootMode = MSP_REBOOT_FIRMWARE;
|
rebootMode = MSP_REBOOT_FIRMWARE;
|
||||||
|
|
|
@ -663,9 +663,6 @@ bool gyroInit(void)
|
||||||
detectedSensors[SENSOR_INDEX_GYRO] = gyro.gyroSensor2.gyroDev.gyroHardware;
|
detectedSensors[SENSOR_INDEX_GYRO] = gyro.gyroSensor2.gyroDev.gyroHardware;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_CUSTOM_DEFAULTS
|
|
||||||
eepromWriteRequired = eepromWriteRequired && systemConfig()->configurationState != CONFIGURATION_STATE_DEFAULTS_BARE;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (eepromWriteRequired) {
|
if (eepromWriteRequired) {
|
||||||
writeEEPROM();
|
writeEEPROM();
|
||||||
|
|
|
@ -59,11 +59,10 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_PWM_OUTPUT
|
#define USE_PWM_OUTPUT
|
||||||
|
|
||||||
// Remove these undefines as support is added
|
// Remove these undefines as support is added
|
||||||
#undef USE_BEEPER
|
//#undef USE_BEEPER
|
||||||
#undef USE_LED_STRIP
|
#undef USE_LED_STRIP
|
||||||
#undef USE_TRANSPONDER
|
#undef USE_TRANSPONDER
|
||||||
#undef USE_DSHOT
|
#undef USE_DSHOT
|
||||||
|
@ -73,10 +72,10 @@
|
||||||
#undef USE_RX_SPI
|
#undef USE_RX_SPI
|
||||||
#undef USE_RX_CC2500
|
#undef USE_RX_CC2500
|
||||||
#undef USE_RX_EXPRESSLRS
|
#undef USE_RX_EXPRESSLRS
|
||||||
#undef USE_CMS
|
//#undef USE_CMS
|
||||||
#undef USE_OSD
|
//#undef USE_OSD
|
||||||
#undef USE_BLACKBOX
|
#undef USE_BLACKBOX
|
||||||
#undef USE_SDCARD
|
//#undef USE_SDCARD
|
||||||
//#undef USE_BARO
|
//#undef USE_BARO
|
||||||
//#undef USE_MAG
|
//#undef USE_MAG
|
||||||
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||||
|
|
|
@ -76,7 +76,6 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
||||||
|
|
|
@ -73,7 +73,6 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
||||||
|
|
|
@ -83,7 +83,6 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x8000) // 32K sectors
|
#define FLASH_PAGE_SIZE ((uint32_t)0x8000) // 32K sectors
|
||||||
|
|
|
@ -74,8 +74,5 @@
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
||||||
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
#define FLASH_PAGE_SIZE ((uint32_t)0x4000) // 16K sectors
|
||||||
|
|
|
@ -73,8 +73,6 @@
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_TIMER_UP_CONFIG
|
#define USE_TIMER_UP_CONFIG
|
||||||
|
|
||||||
|
|
|
@ -94,10 +94,6 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#if !defined(USE_EXST)
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_TIMER_UP_CONFIG
|
#define USE_TIMER_UP_CONFIG
|
||||||
|
|
||||||
|
|
|
@ -82,8 +82,6 @@
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
#define USE_CUSTOM_DEFAULTS
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_TIMER_UP_CONFIG
|
#define USE_TIMER_UP_CONFIG
|
||||||
|
|
||||||
|
|
|
@ -548,10 +548,6 @@ extern uint8_t __config_end;
|
||||||
#undef USE_ABSOLUTE_CONTROL
|
#undef USE_ABSOLUTE_CONTROL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_CUSTOM_DEFAULTS)
|
|
||||||
#define USE_CUSTOM_DEFAULTS_ADDRESS
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_RX_EXPRESSLRS)
|
#if defined(USE_RX_EXPRESSLRS)
|
||||||
// ELRS depends on CRSF telemetry
|
// ELRS depends on CRSF telemetry
|
||||||
#if !defined(USE_TELEMETRY)
|
#if !defined(USE_TELEMETRY)
|
||||||
|
|
|
@ -272,7 +272,7 @@ void beeperOffSet(uint32_t) {}
|
||||||
void beeperOffClear(uint32_t) {}
|
void beeperOffClear(uint32_t) {}
|
||||||
void beeperOffClearAll(void) {}
|
void beeperOffClearAll(void) {}
|
||||||
bool parseColor(int, const char *) {return false; }
|
bool parseColor(int, const char *) {return false; }
|
||||||
bool resetEEPROM(bool) { return true; }
|
bool resetEEPROM(void) { return true; }
|
||||||
void bufWriterFlush(bufWriter_t *) {}
|
void bufWriterFlush(bufWriter_t *) {}
|
||||||
void mixerResetDisarmedMotors(void) {}
|
void mixerResetDisarmedMotors(void) {}
|
||||||
void gpsEnablePassthrough(struct serialPort_s *) {}
|
void gpsEnablePassthrough(struct serialPort_s *) {}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue