Support compilation of EXST (EXTERNAL STORAGE) targets (#8377)
Support compilation of EXST (EXTERNAL STORAGE) targets
This commit is contained in:
commit
e3c8b1b46a
52
Makefile
52
Makefile
|
@ -24,6 +24,9 @@ OPTIONS ?=
|
|||
# compile for OpenPilot BootLoader support
|
||||
OPBL ?= no
|
||||
|
||||
# compile for External Storage Bootloader support
|
||||
EXST ?= no
|
||||
|
||||
# Debugger optons:
|
||||
# empty - ordinary build with all optimizations enabled
|
||||
# RELWITHDEBINFO - ordinary build with debug symbols and all optimizations enabled
|
||||
|
@ -275,14 +278,18 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
|
|||
#
|
||||
# Things we will build
|
||||
#
|
||||
TARGET_S19 = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).s19
|
||||
TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
|
||||
TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
|
||||
TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
||||
TARGET_EXST_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_EXST.elf
|
||||
TARGET_UNPATCHED_BIN = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_UNPATCHED.bin
|
||||
TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).lst
|
||||
TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
||||
TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC))))
|
||||
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||
|
||||
TARGET_EXST_HASH_SECTION_FILE = $(OBJECT_DIR)/$(TARGET)/exst_hash_section.bin
|
||||
|
||||
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
||||
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
||||
|
@ -298,14 +305,52 @@ $(OBJECT_DIR)/$(TARGET)/build/version.o : $(SRC)
|
|||
$(TARGET_LST): $(TARGET_ELF)
|
||||
$(V0) $(OBJDUMP) -S --disassemble $< > $@
|
||||
|
||||
|
||||
$(TARGET_S19): $(TARGET_ELF)
|
||||
@echo "Creating srec/S19 $(TARGET_S19)" "$(STDOUT)"
|
||||
$(V1) $(OBJCOPY) --output-target=srec $(TARGET_S19)
|
||||
|
||||
ifeq ($(EXST),no)
|
||||
$(TARGET_BIN): $(TARGET_ELF)
|
||||
@echo "Creating BIN $(TARGET_BIN)" "$(STDOUT)"
|
||||
$(V1) $(OBJCOPY) -O binary $< $@
|
||||
|
||||
$(TARGET_HEX): $(TARGET_ELF)
|
||||
@echo "Creating HEX $(TARGET_HEX)" "$(STDOUT)"
|
||||
$(V1) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
|
||||
|
||||
$(TARGET_BIN): $(TARGET_ELF)
|
||||
@echo "Creating BIN $(TARGET_BIN)" "$(STDOUT)"
|
||||
else
|
||||
CLEAN_ARTIFACTS += $(TARGET_UNPATCHED_BIN) $(TARGET_EXST_HASH_SECTION_FILE) $(TARGET_EXST_ELF)
|
||||
|
||||
$(TARGET_UNPATCHED_BIN): $(TARGET_ELF)
|
||||
@echo "Creating BIN (without checksum) $(TARGET_UNPATCHED_BIN)" "$(STDOUT)"
|
||||
$(V1) $(OBJCOPY) -O binary $< $@
|
||||
|
||||
$(TARGET_BIN): $(TARGET_UNPATCHED_BIN)
|
||||
@echo "Creating EXST $(TARGET_BIN)" "$(STDOUT)"
|
||||
# Linker script should allow .bin generation from a .elf which results in a file that is the same length as the FIRMWARE_SIZE.
|
||||
# These 'dd' commands will pad a short binary to length FIRMWARE_SIZE.
|
||||
$(V1) dd if=/dev/zero ibs=1k count=$(FIRMWARE_SIZE) of=$(TARGET_BIN)
|
||||
$(V1) dd if=$(TARGET_UNPATCHED_BIN) of=$(TARGET_BIN) conv=notrunc
|
||||
|
||||
@echo "Generating MD5 hash of binary" "$(STDOUT)"
|
||||
$(V1) openssl dgst -md5 $(TARGET_BIN) > $(TARGET_UNPATCHED_BIN).md5
|
||||
|
||||
@echo "Patching MD5 hash into binary" "$(STDOUT)"
|
||||
$(V1) cat $(TARGET_UNPATCHED_BIN).md5 | awk '{printf("%08x: %s",(1024*$(FIRMWARE_SIZE))-16,$$2);}' | xxd -r - $(TARGET_BIN)
|
||||
$(V1) echo $(FIRMWARE_SIZE) | awk '{printf("-s 0x%08x -l 16 -c 16 %s",(1024*$$1)-16,"$(TARGET_BIN)");}' | xargs xxd
|
||||
|
||||
@echo "Patching MD5 hash into exst elf" "$(STDOUT)"
|
||||
$(OBJCOPY) $(TARGET_ELF) --dump-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE)
|
||||
$(V1) cat $(TARGET_UNPATCHED_BIN).md5 | awk '{printf("%08x: %s",64-16,$$2);}' | xxd -r - $(TARGET_EXST_HASH_SECTION_FILE)
|
||||
$(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE)
|
||||
|
||||
$(TARGET_HEX): $(TARGET_BIN)
|
||||
@echo "Creating EXST HEX from patched EXST ELF $(TARGET_HEX)" "$(STDOUT)"
|
||||
$(V1) $(OBJCOPY) -O ihex --set-start 0x8000000 $(TARGET_EXST_ELF) $@
|
||||
|
||||
endif
|
||||
|
||||
$(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT)
|
||||
@echo "Linking $(TARGET)" "$(STDOUT)"
|
||||
$(V1) $(CROSS_CC) -o $@ $(filter-out %.ld,$^) $(LD_FLAGS)
|
||||
|
@ -468,6 +513,9 @@ endif
|
|||
binary:
|
||||
$(V0) $(MAKE) -j $(TARGET_BIN)
|
||||
|
||||
srec:
|
||||
$(V0) $(MAKE) -j $(TARGET_S19)
|
||||
|
||||
hex:
|
||||
$(V0) $(MAKE) -j $(TARGET_HEX)
|
||||
|
||||
|
|
|
@ -0,0 +1,107 @@
|
|||
# EXST bootloader
|
||||
|
||||
The EXST (External Storage) system requires that the targets' CPU has a small program, called a bootloader, that provides functionality to load firmware from an external storage into the CPU's RAM so that the firmware can be executed.
|
||||
|
||||
Example external storage systems include:
|
||||
* External Flash using Firmware Partition
|
||||
* File on an SD card.
|
||||
|
||||
EXST targets also have the requirement of providing a mechansim to load and save configuration ('eeprom'). options for this include:
|
||||
|
||||
* CPU Embedded flash page.
|
||||
* External Flash using Config Partition
|
||||
* File on an SD card.
|
||||
|
||||
Since external storage systems can become corrupted, and communication errors can occur, Bootloaders should verify correct loading of the firmware from an external storage system, or after transferring via a debugger. An hash is provided for this purpose.
|
||||
|
||||
Bootloaders are not limited to just one storage system.
|
||||
|
||||
Bootloaders may offer additional functionality, such as:
|
||||
* a means to update the firmware on an external storage medium (e.g. via DFU)
|
||||
* update one external storage system from another (i.e. update external flash from file on SD card)
|
||||
* backup, select, swap or erase firmware
|
||||
* backup, select, swap or erase configuration.
|
||||
|
||||
Users should consult the manual that came with their EXST bootloader-equipped flight controller for details on how to use any such features.
|
||||
|
||||
The build system provides a way to build files suitable for transferring onto an external storage medium via the standard 'bin'/'hex' make goals.
|
||||
|
||||
```
|
||||
make TARGET=<targetname>
|
||||
```
|
||||
|
||||
This results in the usual `*.bin` and `*.hex` files and also a `*_EXST.elf` file which have been patched to contain information required for bootloader operation.
|
||||
|
||||
The `.bin` file is a binary file which should be transferred to the storage medium and is suitable for distribution.
|
||||
The `.hex` file is a hex file which can be used by tools for uploading to a bootloader and is suitable for distribution.
|
||||
|
||||
For developers there is a `_EXST.elf` file which is a standard `.elf` file that has had one section replaced, this file is suitable for uploading to targets using a debugger such as GDB.
|
||||
|
||||
For details on the memory sections used refer to the linker files.
|
||||
|
||||
## EXST format
|
||||
|
||||
The format for EXST targets is as follows:
|
||||
|
||||
* Firmware.
|
||||
* Bootloader block.
|
||||
|
||||
The bootloader block is 64 bytes.
|
||||
|
||||
For example a 448K EXST `.bin` file is comprised as follows:
|
||||
|
||||
| Start Address | End address | Usage |
|
||||
| ------------- | ----------- | ---------------- |
|
||||
| 0x00000 | 0x6FFBF | Firmware section |
|
||||
| 0x6FFC0 | 0x6FFFF | Bootloader block |
|
||||
|
||||
|
||||
## EXST bootloader block
|
||||
|
||||
The bootloader block is comprised as follows:
|
||||
|
||||
|
||||
| Start Address | End address | Usage |
|
||||
| ------------- | ----------- | ---------------- |
|
||||
| 0x00 | 0x00 | Block Format |
|
||||
| 0x01 | 0x3F | Block Content |
|
||||
|
||||
Block Formats
|
||||
|
||||
| Value | Meaning |
|
||||
| ----- | ----------------- |
|
||||
| 0x00 | Block format 0x00 |
|
||||
|
||||
### Block Format 0x00 Content
|
||||
|
||||
Note: addresses relative to start of bootloader block
|
||||
|
||||
| Start Address | End address | Usage |
|
||||
| ------------- | ----------- | ---------------- |
|
||||
| 0x01 | 0x01 | Checksum/Hash method |
|
||||
| 0x02 | 0x2F | Reserved, fill with 0x00 |
|
||||
| 0x30 | 0x3F | Checksum value, pad with trailing 0x00 |
|
||||
|
||||
Checksum Hash methods
|
||||
|
||||
| Value | Meaning |
|
||||
| ----- | ---------------- |
|
||||
| 0x00 | No checksum. |
|
||||
| 0x01 | MD5. |
|
||||
|
||||
Checksum locations:
|
||||
|
||||
| Start Address | End address | Usage |
|
||||
| ------------- | ----------- | ---------------- |
|
||||
| 0x30 | 0x3F | MD5 hash of firmware section |
|
||||
|
||||
The bootloader should make no attempt to use any reserved area otherwise this prevents it's future use by the firmware.
|
||||
|
||||
The bootloader should ensure this block is in RAM when the firmware is loaded. i.e. copy the entire EXST image.
|
||||
|
||||
As the reserved area is under control of the build system, not the bootloader, additional information can stored there for use by the firmware or future bootloaders. Extreme care must be taken not to break the bootloaders ability to load firmware. Consultation with the developers for any changes to this area is required.
|
||||
|
||||
### Example possible future enhancements for the EXST bootloader block
|
||||
|
||||
* Hardware layout identification - to allow the firmware to identify the hardware, such that IO pins and peripherals can be reserved/initialised.
|
||||
* Alternative hashes/CRCs.
|
|
@ -168,10 +168,18 @@ STARTUP_SRC = startup_stm32h743xx.s
|
|||
TARGET_FLASH := 2048
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32H750xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750.ld
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld
|
||||
STARTUP_SRC = startup_stm32h743xx.s
|
||||
TARGET_FLASH := 128
|
||||
|
||||
ifeq ($(EXST),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
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_exst.ld
|
||||
endif
|
||||
|
||||
ifneq ($(DEBUG),GDB)
|
||||
OPTIMISE_DEFAULT := -Os
|
||||
OPTIMISE_SPEED := -Os
|
||||
|
|
|
@ -183,6 +183,10 @@ COMMON_DEVICE_SRC = \
|
|||
|
||||
COMMON_SRC := $(COMMON_SRC) $(COMMON_DEVICE_SRC)
|
||||
|
||||
ifeq ($(EXST),yes)
|
||||
TARGET_FLAGS := -DUSE_EXST $(TARGET_FLAGS)
|
||||
endif
|
||||
|
||||
ifeq ($(SIMULATOR_BUILD),yes)
|
||||
TARGET_FLAGS := -DSIMULATOR_BUILD $(TARGET_FLAGS)
|
||||
endif
|
||||
|
|
|
@ -6,15 +6,14 @@ $(error The target specified, $(TARGET), cannot be built. Use one of the ALT tar
|
|||
endif
|
||||
|
||||
BASE_TARGET := $(call get_base_target,$(TARGET))
|
||||
ifneq ($(TARGET),$(BASE_TARGET))
|
||||
include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
|
||||
endif
|
||||
# silently ignore if the file is not present. Allows for target specific.
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
|
||||
|
||||
ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET))
|
||||
OPBL = yes
|
||||
endif
|
||||
|
||||
# silently ignore if the file is not present. Allows for target specific.
|
||||
# silently ignore if the file is not present. Allows for target defaults.
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
||||
|
||||
F4_TARGETS := $(F405_TARGETS) $(F411_TARGETS) $(F446_TARGETS)
|
||||
|
|
|
@ -23,7 +23,6 @@ ALT_TARGETS = $(sort $(notdir $(BASE_ALT_PAIRS)))
|
|||
BASE_TARGETS = $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)))))
|
||||
NOBUILD_TARGETS = $(sort $(filter-out target,$(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.nomk)))))
|
||||
OPBL_TARGETS = $(sort $(filter %_OPBL,$(ALT_TARGETS)))
|
||||
|
||||
VALID_TARGETS = $(sort $(filter-out $(NOBUILD_TARGETS),$(BASE_TARGETS) $(ALT_TARGETS)))
|
||||
|
||||
# For alt targets, returns their base target name.
|
||||
|
|
|
@ -262,7 +262,11 @@ void systemResetToBootloader(void)
|
|||
}
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_EXST
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_FLASH_BOOTLOADER_REQUEST);
|
||||
#else
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST);
|
||||
#endif
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash_h7x3_2m.ld
|
||||
** File : stm32_flash_h750_128k.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32H743xI Device with
|
||||
** 512K AXI-RAM mapped onto AXI bus on D1 domain
|
||||
|
@ -66,12 +66,6 @@ ENTRY(Reset_Handler)
|
|||
/* Highest address of the user mode stack */
|
||||
_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */
|
||||
|
||||
/* Base address where the config is stored. */
|
||||
/*
|
||||
__config_start = ORIGIN(FLASH_CONFIG);
|
||||
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);
|
||||
*/
|
||||
|
||||
/* Base address where the quad spi. */
|
||||
__quad_spi_start = ORIGIN(QUADSPI);
|
||||
|
|
@ -0,0 +1,320 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash_h750_exst.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 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
|
||||
then executes code at the CODE_RAM address.
|
||||
|
||||
Currently, this is inefficient as there are two copies of some sections in RAM. e.g. .tcm_code.
|
||||
|
||||
It would be technically possible to free more RAM by having a more intelligent build system
|
||||
and bootloader which creates files for each of the sections that are usually copied from flash
|
||||
to ram and one section for the main code. e.g. one file for .tcm_code, one file for .data and
|
||||
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
|
||||
possible.
|
||||
|
||||
*/
|
||||
|
||||
/* see .exst section below */
|
||||
_exst_hash_size = 64;
|
||||
|
||||
/* 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 (rx) : ORIGIN = 0x24010000, LENGTH = 448K - _exst_hash_size
|
||||
EXST_HASH (rx) : ORIGIN = 0x24010000 + LENGTH(CODE_RAM), LENGTH = _exst_hash_size
|
||||
|
||||
D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */
|
||||
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
QUADSPI (rx) : ORIGIN = 0x90000000, 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); /* end of RAM */
|
||||
|
||||
/* Base address where the quad spi. */
|
||||
__quad_spi_start = ORIGIN(QUADSPI);
|
||||
|
||||
/* 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 CODE_RAM */
|
||||
.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 CODE_RAM */
|
||||
.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 AT >CODE_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 AT >CODE_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 AT >CODE_RAM
|
||||
|
||||
. = 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) :
|
||||
{
|
||||
_sdmaram = .;
|
||||
_dmaram_start__ = _sdmaram;
|
||||
KEEP(*(.DMA_RAM))
|
||||
_edmaram = .;
|
||||
_dmaram_end__ = _edmaram;
|
||||
} >D2_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
|
||||
|
||||
/* Create space for a hash. Currently an MD5 has is used, which is 16 */
|
||||
/* bytes long. however the last 64 bytes are RESERVED for hash related */
|
||||
.exst_hash :
|
||||
{
|
||||
/* 64 bytes is the size of an MD5 hashing block size. */
|
||||
. = ORIGIN(EXST_HASH);
|
||||
|
||||
BYTE(0x00); /* block format */
|
||||
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);
|
||||
LONG(0x00000000);
|
||||
LONG(0x00000000);
|
||||
LONG(0x00000000);
|
||||
. = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH);
|
||||
__firmware_end__ = .;
|
||||
} >EXST_HASH
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -546,7 +546,11 @@ void MPU_Config()
|
|||
// The Base Address 0x24000000 is the SRAM1 accessible by the SDIO internal DMA.
|
||||
MPU_InitStruct.Enable = MPU_REGION_ENABLE;
|
||||
MPU_InitStruct.BaseAddress = 0x24000000;
|
||||
#if defined(USE_EXST)
|
||||
MPU_InitStruct.Size = MPU_REGION_SIZE_64KB;
|
||||
#else
|
||||
MPU_InitStruct.Size = MPU_REGION_SIZE_512KB;
|
||||
#endif
|
||||
MPU_InitStruct.AccessPermission = MPU_REGION_FULL_ACCESS;
|
||||
MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE;
|
||||
MPU_InitStruct.IsCacheable = MPU_ACCESS_CACHEABLE;
|
||||
|
@ -577,7 +581,12 @@ void resetMPU(void)
|
|||
/* Disable the MPU */
|
||||
HAL_MPU_Disable();
|
||||
|
||||
#if !defined(USE_EXST)
|
||||
uint8_t highestRegion = MPU_REGION_NUMBER15;
|
||||
#else
|
||||
uint8_t highestRegion = MPU_REGION_NUMBER7;// currently 8-15 reserved by bootloader. Bootloader may write-protect the firmware region, this firmware can examine and undo this at it's peril.
|
||||
#endif
|
||||
|
||||
|
||||
// disable all existing regions
|
||||
for (uint8_t region = MPU_REGION_NUMBER0; region <= highestRegion; region++) {
|
||||
|
@ -594,7 +603,11 @@ void SystemInit (void)
|
|||
|
||||
initialiseMemorySections();
|
||||
|
||||
#if !defined(USE_EXST)
|
||||
// only stand-alone and bootloader firmware needs to do this.
|
||||
// if it's done in the EXST firmware as well as the BOOTLOADER firmware you get a reset loop.
|
||||
systemCheckResetReason();
|
||||
#endif
|
||||
|
||||
// FPU settings
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
|
@ -666,6 +679,8 @@ void SystemInit (void)
|
|||
/* Configure the Vector Table location add offset address ------------------*/
|
||||
#if defined(VECT_TAB_SRAM)
|
||||
SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
|
||||
#elif defined(USE_EXST)
|
||||
// Don't touch the vector table, the bootloader will have already set it.
|
||||
#else
|
||||
SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue