1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

Added H723 unified target. Fixed H723 linker (#11826)

* Added H723 unified target. Fixed H723 linker

* Fixed a typo in the readme

* Update TARGETS line in mk file
This commit is contained in:
David O'Connor 2022-11-16 08:03:54 -05:00 committed by GitHub
parent d49d8ad4fb
commit 2fd5746dce
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
6 changed files with 243 additions and 37 deletions

View file

@ -27,44 +27,34 @@ ENTRY(Reset_Handler)
0x38000000 to 0x38003FFF 16K SRAM4, D3 domain, unused
0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused
XXX TODO join isr vector, startup and firmware to save some space
0x08000000 to 0x080FFFFF 1024K full flash,
0x08000000 to 0x080FFFFF 1024K full flash
0x08000000 to 0x0801FFFF 128K isr vector, startup code
0x08020000 to 0x080DFFFF 768K firmware
0x080E0000 to 0x080FFFFF 128K config
0x08020000 to 0x0803FFFF 128K config
0x08040000 to 0x080FFFFF 768K firmware
*/
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K
FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K
FLASH1 (rx) : ORIGIN = 0x08020000, LENGTH = 768K
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K
FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 10K
FLASH_UNUSED (r) : ORIGIN = 0x08005000, LENGTH = 108K
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS_EXTENDED) ? 640K : 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
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 320K
D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 32K /* 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)
@ -77,7 +67,7 @@ __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 */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Define output sections */
SECTIONS
@ -126,13 +116,13 @@ SECTIONS
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH
} >FLASH1
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH
} >FLASH1
.pg_registry :
{
@ -140,14 +130,29 @@ SECTIONS
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH
} >FLASH1
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH
} >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 */
_sidata = LOADADDR(.data);
@ -162,7 +167,7 @@ SECTIONS
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >FASTRAM AT >FLASH
} >RAM AT >FLASH1
/* Uninitialized data section */
. = ALIGN(4);
@ -178,7 +183,7 @@ SECTIONS
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >FASTRAM
} >RAM
/* Uninitialized data section */
. = ALIGN(4);
@ -208,7 +213,7 @@ SECTIONS
. = ALIGN(4);
_efastram_data = .; /* define a global symbol at data end */
} >FASTRAM AT >FLASH
} >FASTRAM AT >FLASH1
. = ALIGN(4);
.fastram_bss (NOLOAD) :
@ -237,7 +242,7 @@ SECTIONS
*(.dmaram_data*) /* .data* sections */
. = ALIGN(32);
_edmaram_data = .; /* define a global symbol at data end */
} >RAM AT >FLASH
} >RAM AT >FLASH1
. = ALIGN(32);
.dmaram_bss (NOLOAD) :

View file

@ -24,11 +24,11 @@ CUSTOM_DEFAULTS_EXTENDED = yes
FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
drivers/max7456.c \
drivers/vtx_rtc6705.c \
drivers/vtx_rtc6705_soft_spi.c \
$(RX_SRC)
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
drivers/max7456.c \
drivers/vtx_rtc6705.c \
drivers/vtx_rtc6705_soft_spi.c \
$(RX_SRC)

View file

@ -0,0 +1,2 @@
This unified target supports the STM32H723, H725, H733, and H735 MCUs.
Reference manual: ST RM0468

View file

@ -0,0 +1,22 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
// Needed to suppress the pedantic warning about an empty file
#include <stddef.h>

View file

@ -0,0 +1,143 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SH72"
#define USBD_PRODUCT_STRING "Betaflight STM32H723"
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define USE_I2C_DEVICE_3
#define USE_I2C_DEVICE_4
#define USE_I2C_DEVICE_5
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_UART4
#define USE_UART5
#define USE_UART6
#define USE_UART7
#define USE_UART8
#define USE_UART9
#define USE_LPUART1
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 10)
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define USE_SPI_DEVICE_3
#define USE_SPI_DEVICE_4
#define USE_SPI_DEVICE_5
#define USE_SPI_DEVICE_6
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0xffff
#define TARGET_IO_PORTG 0xffff
#define USE_I2C
#define I2C_FULL_RECONFIGURABILITY
#define USE_BEEPER
#if !defined(CLOUD_BUILD)
#define USE_MAG
#define USE_BARO
#define USE_ACC
#define USE_GYRO
#define USE_ACC_MPU6500
#define USE_GYRO_MPU6500
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
#define USE_ACC_SPI_ICM20689
#define USE_GYRO_SPI_ICM20689
#define USE_ACCGYRO_LSM6DSO
#define USE_ACCGYRO_BMI270
#define USE_GYRO_SPI_ICM42605
#define USE_GYRO_SPI_ICM42688P
#define USE_ACC_SPI_ICM42605
#define USE_ACC_SPI_ICM42688P
#define USE_RX_SPI
#define USE_ACC_MPU6050
#define USE_GYRO_MPU6050
#define USE_ACCGYRO_BMI160
#define USE_FLASHFS
#define USE_FLASH_TOOLS
#define USE_FLASH_M25P16
#define USE_FLASH_W25N01G // 1Gb NAND flash support
#define USE_FLASH_W25M // Stacked die support
#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support
#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support
#define USE_FLASH_W25Q128FV // 16MB Winbond 25Q128
#define USE_MAX7456
#define USE_VTX_RTC6705
#define USE_VTX_RTC6705_SOFTSPI
#define USE_TRANSPONDER
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04
#define USE_RANGEFINDER_TF
#define USE_RX_EXPRESSLRS
#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5
#define USE_RX_SX1280
#define USE_RX_SX127X
#define USE_SDCARD
#endif // CLOUD_BUILD
#ifdef USE_SDCARD
#define USE_SDCARD_SPI
#define USE_SDCARD_SDIO
#endif
#define USE_SPI
#define SPI_FULL_RECONFIGURABILITY
#define USE_VCP
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define UNIFIED_SERIAL_PORT_COUNT 3
#define USE_USB_DETECT
#define USE_ESCSERIAL
#define USE_ADC
#define USE_CUSTOM_DEFAULTS

View file

@ -0,0 +1,34 @@
RX_SRC = \
rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c \
rx/cc2500_redpine.c \
rx/a7105_flysky.c \
rx/cyrf6936_spektrum.c \
drivers/rx/expresslrs_driver.c \
rx/expresslrs.c \
rx/expresslrs_common.c \
rx/expresslrs_telemetry.c \
drivers/rx/rx_cc2500.c \
drivers/rx/rx_a7105.c \
drivers/rx/rx_cyrf6936.c \
drivers/rx/rx_sx127x.c \
drivers/rx/rx_sx1280.c \
H723xG_TARGETS += $(TARGET)
CUSTOM_DEFAULTS_EXTENDED = yes
FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
drivers/max7456.c \
drivers/vtx_rtc6705.c \
drivers/vtx_rtc6705_soft_spi.c \
$(RX_SRC)