Skip to content

Commit

Permalink
Merge pull request #10318 from jflyper/bfdev-h7-h7a3
Browse files Browse the repository at this point in the history
[H7] H7A3 support
  • Loading branch information
mikeller committed Nov 4, 2020
2 parents 7979960 + 697d0f7 commit 4bf3e99
Show file tree
Hide file tree
Showing 17 changed files with 1,364 additions and 50 deletions.
35 changes: 33 additions & 2 deletions make/mcu/STM32H7.mk
Expand Up @@ -153,8 +153,9 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER

#
# H743xI : 2M FLASH, 1M RAM (H753xI also)
# H743xG : 1M FLASH, 1M RAM (H753xG also)
# H743xI : 2M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xI also)
# H743xG : 1M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xG also)
# H7A3xI : 2M FLASH, 1MB AXI SRAM + 160KB AHB & SRD SRAM
# H750xB : 128K FLASH, 1M RAM
#
ifeq ($(TARGET),$(filter $(TARGET),$(H743xI_TARGETS)))
Expand All @@ -172,6 +173,36 @@ MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h743.ld
endif

else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xIQ_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xxQ
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 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.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif

else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xI_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 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.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif

else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS)))
DEVICE_FLAGS += -DSTM32H750xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld
Expand Down
2 changes: 1 addition & 1 deletion make/targets.mk
Expand Up @@ -19,7 +19,7 @@ endif
F4_TARGETS := $(F405_TARGETS) $(F411_TARGETS) $(F446_TARGETS)
F7_TARGETS := $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)
G4_TARGETS := $(G4X3_TARGETS)
H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS)
H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS) $(H7A3xI_TARGETS) $(H7A3xIQ_TARGETS)

ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
Expand Down
289 changes: 289 additions & 0 deletions src/link/stm32_flash_h7a3_2m.ld
@@ -0,0 +1,289 @@
/*
*****************************************************************************
**
** File : stm32_flash_h7a3_2m.ld
**
** Abstract : Linker script for STM32H743xI Device with
**
** Note
** Flash sector (erase unit) is 8KB
**
*****************************************************************************
*/

/* Entry Point */
ENTRY(Reset_Handler)

/*
0x00000000 to 0x0000FFFF 64K ITCM
0x20000000 to 0x2001FFFF 128K DTCM
0x24000000 to 0x2403FFFF 256K AXI SRAM1, CD domain, main RAM
0x24040000 to 0x2409FFFF 384K AXI SRAM2, CD domain, main RAM
0x240A0000 to 0x240FFFFF 384K AXI SRAM3, CD domain, main RAM
0x30000000 to 0x3000FFFF 64K AHB_SRAM1, CD domain, unused
0x30010000 to 0x3001FFFF 64K AHB_SRAM2, CD domain, unused
0x38000000 to 0x3800FFFF 32K SRD_SRAM, SRD domain, unused
0x38800000 to 0x38800FFF 4K BKP_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
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K /* 2 sectors */
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 16K /* 2 sectors */
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 2016K

ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 1024K

D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* AHB_SRAM1 + AHB_SRAM2 */

MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}

REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)

/* 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 */

/* Base address where the config is stored. */
__config_start = ORIGIN(FLASH_CONFIG);
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);

/* 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);
} >FLASH

/* 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 */
} >FLASH1

/* 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 >FLASH1

.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH

.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH

.pg_registry :
{
PROVIDE_HIDDEN (__pg_registry_start = .);
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH

.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH

/* 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 >FLASH

/* 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 >FLASH

. = 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) }
}
2 changes: 2 additions & 0 deletions src/main/build/build_config.c
Expand Up @@ -72,6 +72,8 @@ mcuTypeId_e getMcuTypeId(void)
default:
return MCU_TYPE_H743_REV_UNKNOWN;
}
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
return MCU_TYPE_H7A3;
#else
return MCU_TYPE_UNKNOWN;
#endif
Expand Down
1 change: 1 addition & 0 deletions src/main/build/build_config.h
Expand Up @@ -57,6 +57,7 @@ typedef enum {
MCU_TYPE_H743_REV_Y,
MCU_TYPE_H743_REV_X,
MCU_TYPE_H743_REV_V,
MCU_TYPE_H7A3,
MCU_TYPE_UNKNOWN = 255,
} mcuTypeId_e;

Expand Down
1 change: 1 addition & 0 deletions src/main/cli/cli.c
Expand Up @@ -305,6 +305,7 @@ static const char *mcuTypeNames[] = {
"H743 (Rev.Y)",
"H743 (Rev.X)",
"H743 (Rev.V)",
"H7A3",
};

static const char *configurationStates[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" };
Expand Down

0 comments on commit 4bf3e99

Please sign in to comment.