1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

STM32H5: commencing support

This commit is contained in:
blckmn 2025-01-30 20:31:55 +11:00
parent 294f905953
commit 3f86b6577d
5 changed files with 42 additions and 7 deletions

View file

@ -64,6 +64,7 @@ typedef enum {
MCU_TYPE_APM32F407,
MCU_TYPE_AT32F435M,
MCU_TYPE_RP2350B,
MCU_TYPE_STM32H563,
MCU_TYPE_COUNT,
MCU_TYPE_UNKNOWN = 255,
} mcuTypeId_e;

View file

@ -63,6 +63,17 @@ const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB4(GPIOI) },
#endif
};
#elif defined(STM32H5)
const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB4(GPIOA) },
{ RCC_AHB4(GPIOB) },
{ RCC_AHB4(GPIOC) },
{ RCC_AHB4(GPIOD) },
{ RCC_AHB4(GPIOE) },
{ RCC_AHB4(GPIOF) },
{ RCC_AHB4(GPIOG) },
{ RCC_AHB4(GPIOH) },
};
#elif defined(STM32G4)
const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB2(GPIOA) },

View file

@ -197,7 +197,6 @@ SPEED_OPTIMISED_SRC += \
SIZE_OPTIMISED_SRC += \
drivers/bus_i2c_timing.c \
STM32/bus_i2c_hal_init.c \
STM32/serial_usb_vcp.c \
drivers/serial_escserial.c \
drivers/serial_pinconfig.c \
drivers/serial_uart_pinconfig.c

View file

@ -45,6 +45,30 @@
#define STM32G4
#endif
#elif defined(STM32H563xx)
#include "stm32h5xx.h"
#include "stm32h5xx_hal.h"
#include "system_stm32h5xx.h"
#include "stm32h5xx_ll_spi.h"
#include "stm32h5xx_ll_gpio.h"
#include "stm32h5xx_ll_dma.h"
#include "stm32h5xx_ll_rcc.h"
#include "stm32h5xx_ll_bus.h"
#include "stm32h5xx_ll_tim.h"
#include "stm32h5xx_ll_system.h"
// Chip Unique ID on H5
#define U_ID_0 (*(uint32_t*)UID_BASE)
#define U_ID_1 (*(uint32_t*)(UID_BASE + 4))
#define U_ID_2 (*(uint32_t*)(UID_BASE + 8))
#define USE_PIN_AF
#ifndef STM32H5
#define STM32H5
#endif
#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
#include "stm32h7xx.h"
#include "stm32h7xx_hal.h"
@ -320,7 +344,7 @@ extern uint8_t _dmaram_end__;
#define SPI_IO_AF_SDI_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_CS_HIGH_CFG IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#elif defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#elif defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(STM32H5)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
#define SPI_IO_AF_SCK_CFG_HIGH IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define SPI_IO_AF_SCK_CFG_LOW IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN)
@ -350,7 +374,7 @@ extern uint8_t _dmaram_end__;
#define SPI_RX_DATA_REGISTER(base) ((base)->DR)
#endif
#if defined(STM32F4) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32G4) || defined(STM32H5)
#define MAX_SPI_PIN_SEL 2
#elif defined(STM32F7)
#define MAX_SPI_PIN_SEL 4
@ -378,7 +402,7 @@ extern uint8_t _dmaram_end__;
#define UART_RX_BUFFER_ATTRIBUTE /* EMPTY */
#endif
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(STM32H5)
// pin AF mode is configured for each pin individually
#define UART_TRAIT_AF_PIN 1
#elif defined(STM32F4)

View file

@ -312,7 +312,7 @@ uint32_t getFLASHSectorForEEPROM(void)
void configUnlock(void)
{
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(STM32H5)
HAL_FLASH_Unlock();
#elif defined(APM32F4)
DAL_FLASH_Unlock();
@ -325,7 +325,7 @@ void configUnlock(void)
void configLock(void)
{
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(STM32H5)
HAL_FLASH_Lock();
#elif defined(AT32F4)
flash_lock();
@ -342,7 +342,7 @@ void configClearFlags(void)
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
#elif defined(STM32F7)
// NOP
#elif defined(STM32H7)
#elif defined(STM32H7) || defined(STM32H5)
// NOP
#elif defined(STM32G4)
// NOP