diff --git a/Makefile b/Makefile index 8b0cab8345..daf4aaf65e 100644 --- a/Makefile +++ b/Makefile @@ -27,6 +27,9 @@ OPBL ?= no # compile for External Storage Bootloader support EXST ?= no +# compile for target loaded into RAM +RAM_BASED ?= no + # Debugger optons: # empty - ordinary build with all optimizations enabled # RELWITHDEBINFO - ordinary build with debug symbols and all optimizations enabled diff --git a/docs/boards/Board - NucleoH743 RAM based.md b/docs/boards/Board - NucleoH743 RAM based.md new file mode 100644 index 0000000000..7a1056c4d2 --- /dev/null +++ b/docs/boards/Board - NucleoH743 RAM based.md @@ -0,0 +1,35 @@ +# Board - Nucleo H743 - RAM based image + +This target for the Nucleo H743 is loaded entirely into the MCU RAM, thus facilitating quick turnaround development testing, without subjecting the flash storage to wear. + +In order to flash / run it, the ST-Link tool available from ST Microelectronics has to be used. + +## Board preparation + +For the MCU to run the firmware from RAM after a reset, the boot address has to be changed: + +- open the 'Option Bytes' dialog: + +!['Option Bytes' menu entry](images/NUCLEOH743_RAMBASED_option_bytes.png) + +- set the high word of BOOT\_ADD0 to `0x2401`: + +![set boot address](images/NUCLEOH743_RAMBASED_boot_address.png) + +- click 'Apply'. + +## Installation + +Since the firmware image is only stored in RAM, this has to be done after every power cycle of the board. + +- open the 'Program' dialog: + +!['Program' menu entry](images/NUCLEOH743_RAMBASED_program.png) + +- click 'Browse', select the 'NUCLEOH743\_RAMBASED' hex image; +- make sure 'Reset after programming' is checked; +- click 'Start' to start programming: + +![load / run the program](images/NUCLEOH743_RAMBASED_run.png) + +- After programming has completed the firmware will be run. diff --git a/docs/boards/images/NUCLEOH743_RAMBASED_boot_address.png b/docs/boards/images/NUCLEOH743_RAMBASED_boot_address.png new file mode 100644 index 0000000000..21d44f6cee Binary files /dev/null and b/docs/boards/images/NUCLEOH743_RAMBASED_boot_address.png differ diff --git a/docs/boards/images/NUCLEOH743_RAMBASED_option_bytes.png b/docs/boards/images/NUCLEOH743_RAMBASED_option_bytes.png new file mode 100644 index 0000000000..a30eda6159 Binary files /dev/null and b/docs/boards/images/NUCLEOH743_RAMBASED_option_bytes.png differ diff --git a/docs/boards/images/NUCLEOH743_RAMBASED_program.png b/docs/boards/images/NUCLEOH743_RAMBASED_program.png new file mode 100644 index 0000000000..29e62def02 Binary files /dev/null and b/docs/boards/images/NUCLEOH743_RAMBASED_program.png differ diff --git a/docs/boards/images/NUCLEOH743_RAMBASED_run.png b/docs/boards/images/NUCLEOH743_RAMBASED_run.png new file mode 100644 index 0000000000..97de9f67fe Binary files /dev/null and b/docs/boards/images/NUCLEOH743_RAMBASED_run.png differ diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk index 8d165ba75c..a3ccf14aa0 100644 --- a/make/mcu/STM32H7.mk +++ b/make/mcu/STM32H7.mk @@ -164,6 +164,15 @@ DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld STARTUP_SRC = startup_stm32h743xx.s TARGET_FLASH := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 + +ifeq ($(RAM_BASED),yes) +FIRMWARE_SIZE := 448 +# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware +# and the maximum size of the data stored on the external storage device. +TARGET_FLASH := FIRMWARE_SIZE +DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_ram_based.ld +endif + else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS))) DEVICE_FLAGS += -DSTM32H750xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld diff --git a/make/source.mk b/make/source.mk index d98ed91594..855a436b87 100644 --- a/make/source.mk +++ b/make/source.mk @@ -190,6 +190,10 @@ ifeq ($(EXST),yes) TARGET_FLAGS := -DUSE_EXST $(TARGET_FLAGS) endif +ifeq ($(RAM_BASED),yes) +TARGET_FLAGS := -DUSE_EXST -DEEPROM_IN_RAM $(TARGET_FLAGS) +endif + ifeq ($(SIMULATOR_BUILD),yes) TARGET_FLAGS := -DSIMULATOR_BUILD $(TARGET_FLAGS) endif diff --git a/src/link/stm32_flash_h743_ram_based.ld b/src/link/stm32_flash_h743_ram_based.ld new file mode 100644 index 0000000000..442917675f --- /dev/null +++ b/src/link/stm32_flash_h743_ram_based.ld @@ -0,0 +1,296 @@ +/* +***************************************************************************** +** +** File : stm32_flash_h7x3_2m.ld +** +** Abstract : Linker script for STM32H743xI Device with +** 512K AXI-RAM mapped onto AXI bus on D1 domain +** 128K SRAM1 mapped on D2 domain +** 128K SRAM2 mapped on D2 domain +** 32K SRAM3 mapped on D2 domain +** 64K SRAM4 mapped on D3 domain +** 64K ITCM +** 128K DTCM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x0000FFFF 64K ITCM +0x20000000 to 0x2001FFFF 128K DTCM +0x24000000 to 0x2407FFFF 512K AXI SRAM, D1 domain, main RAM +0x30000000 to 0x3001FFFF 128K SRAM1, D2 domain, unused +0x30020000 to 0x3003FFFF 128K SRAM2, D2 domain, unused +0x30040000 to 0x30047FFF 32K SRAM3, D2 domain, unused +0x38000000 to 0x3800FFFF 64K SRAM4, D3 domain, unused +0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x0801FFFF 128K isr vector, startup code, +0x08020000 to 0x0803FFFF 128K config, // FLASH_Sector_1 +0x08040000 to 0x081FFFFF 1792K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 64K + CODE_RAM (rwx) : ORIGIN = 0x24010000, LENGTH = 448K + + D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ + + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) + +/* INCLUDE "stm32_flash_f7_split.ld" */ +/* +***************************************************************************** +** +** File : stm32_flash_f7_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - 8; /* Reserve 2 x 4bytes for info across reset */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x800; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(512); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >CODE_RAM + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >CODE_RAM + + /* Critical program code goes into ITCM RAM */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >CODE_RAM + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) __exidx_end = .; + } >CODE_RAM + + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >CODE_RAM + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >CODE_RAM + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .sram2 (NOLOAD) : + { + /* This is used by the startup in order to initialize the .sram2 secion */ + _ssram2 = .; /* define a global symbol at sram2 start */ + __sram2_start__ = _ssram2; + *(.sram2) + *(SORT_BY_ALIGNMENT(.sram2*)) + + . = ALIGN(4); + _esram2 = .; /* define a global symbol at sram2 end */ + __sram2_end__ = _esram2; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_RAM section for unsuspecting developers */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM + + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .DMA_RAM (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmaram_start = .); + _sdmaram = .; + _dmaram_start__ = _sdmaram; + KEEP(*(.DMA_RAM)) + PROVIDE(dmaram_end = .); + _edmaram = .; + _dmaram_end__ = _edmaram; + } >D2_RAM + + .DMA_RW_D2 (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarw_start = .); + _sdmarw = .; + _dmarw_start__ = _sdmarw; + KEEP(*(.DMA_RW)) + PROVIDE(dmarw_end = .); + _edmarw = .; + _dmarw_end__ = _edmarw; + } >D2_RAM + + .DMA_RW_AXI (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarwaxi_start = .); + _sdmarwaxi = .; + _dmarwaxi_start__ = _sdmarwaxi; + KEEP(*(.DMA_RW_AXI)) + PROVIDE(dmarwaxi_end = .); + _edmarwaxi = .; + _dmarwaxi_end__ = _edmarwaxi; + } >RAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >RAM + + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */ + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/NUCLEOH743/NUCLEOH743_RAMBASED.mk b/src/main/target/NUCLEOH743/NUCLEOH743_RAMBASED.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/NUCLEOH743/target.mk b/src/main/target/NUCLEOH743/target.mk index 7c65aee48f..dd255509b6 100644 --- a/src/main/target/NUCLEOH743/target.mk +++ b/src/main/target/NUCLEOH743/target.mk @@ -1,7 +1,11 @@ H743xI_TARGETS += $(TARGET) -#FEATURES += SDCARD VCP + FEATURES += VCP ONBOARDFLASH +ifeq ($(TARGET), NUCLEOH743_RAMBASED) +RAM_BASED = yes +endif + # Top level Makefile adds, if not defined, HSE_VALUE, as default for F4 targets. # We don't want to assume any particular value until de facto design is established, # so we set the value here. diff --git a/unified_targets/configs/OMNIBUSF4_test.config b/unified_targets/configs/OMNIBUSF4_test.config new file mode 100644 index 0000000000..e44a0a329d --- /dev/null +++ b/unified_targets/configs/OMNIBUSF4_test.config @@ -0,0 +1,22 @@ +# Betaflight / STM32F405 (S405) 4.1.0 May 22 2019 / 02:24:46 (1541466da) MSP API: 1.42 + +board_name OMNIBUSF4 +manufacturer_id AIRB + +# resources +resource LED_STRIP 1 A01 +resource LED 1 B05 + +# timer +timer A01 AF2 +# pin A01: TIM5 CH2 (AF2) + +# dma +dma ADC 2 1 +# ADC 2: DMA2 Stream 3 Channel 1 +dma pin A01 0 +# pin A01: DMA1 Stream 4 Channel 6 + +# master +set gyro_1_bustype = SPI +set gyro_1_spibus = 1