AP_HAL_ChibiOS: add support for NucleoH755 board

This addition allows for cheap testing of a STM32H755 (dual core). This borrows the setup file STM32H757xx.py, as there are almost no changes between the chips. CRSF in and out, gps, ICM20948, BMP388, settings saving to on board flash all working.

PWM(3) pin change

Changed PWM(3) pin to one exposed on connector
This commit is contained in:
Walter Dunckel 2022-03-27 17:24:48 -07:00 committed by Andrew Tridgell
parent 35a2ca62ee
commit b0c3fae662
3 changed files with 199 additions and 0 deletions

View File

@ -0,0 +1,9 @@
SERIAL3_BAUD 57
SERIAL3_PROTOCOL 5
SERIAL3_OPTIONS 256
SERIAL4_BAUD 115
SERIAL4_PROTOCOL 23
SERIAL4_OPTIONS 0

View File

@ -0,0 +1,43 @@
# hw definition file for processing by chibios_hwdef.py
# for H755 bootloader - H755 is almost identical to H757, so utilizing its STM32H757xx.py file
# MCU class and specific type
MCU STM32H7xx STM32H757xx
# crystal frequency
OSCILLATOR_HZ 8000000
define CORE_CM7
define SMPS_PWR
# board ID for firmware load
APJ_BOARD_ID 139
# the nucleo seems to have trouble with flashing the last sector?
FLASH_SIZE_KB 2048
# the location where the bootloader will put the firmware
# the H755 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 256
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# order of UARTs (and USB)
SERIAL_ORDER OTG1
#LED setup
PB0 LED_BOOTLOADER OUTPUT LOW
PB14 LED_ACTIVITY OUTPUT LOW
define HAL_LED_ON 0
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PC7 BARO_CS CS

View File

@ -0,0 +1,147 @@
# hw definition file for processing by chibios_hwdef.py
# for H755 - H755 is almost identical to H757, so utilizing its STM32H757xx.py file
AUTOBUILD_TARGETS None
# MCU class and specific type
MCU STM32H7xx STM32H757xx
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_ST_USE_TIMER 5
define CORE_CM7
define SMPS_PWR
# board ID for firmware load
APJ_BOARD_ID 139
# the nucleo seems to have trouble with flashing the last sector?
FLASH_SIZE_KB 2048
FLASH_BOOTLOADER_LOAD_KB 256
FLASH_RESERVE_START_KB 256
define HAL_STORAGE_SIZE 32768
STORAGE_FLASH_PAGE 14
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART2 UART7 USART1 UART4 UART5
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# order of UARTs and suggested uses
# USART2 TELEM1
# UART7 TELEM2
# USART1 GPS
# UART4 RCIN/OUT Telem
# UART5 DEBUG
# telem1 USART2
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# telem2 UART7
PF9 UART7_CTS UART7
PF8 UART7_RTS UART7
PF7 UART7_TX UART7
PF6 UART7_RX UART7
# GPS USART1
PB7 USART1_RX USART1
PB6 USART1_TX USART1
# RCIN/OUT UART4
PB9 UART4_TX UART4
PB8 UART4_RX UART4
# debug uart5
PB13 UART5_TX UART5
PB12 UART5_RX UART5
# Now setup the pins for the microSD card, if available.
PC8 SDMMC1_D0 SDMMC1
PC9 SDMMC1_D1 SDMMC1
PC10 SDMMC1_D2 SDMMC1
PC11 SDMMC1_D3 SDMMC1
PC12 SDMMC1_CK SDMMC1
PD2 SDMMC1_CMD SDMMC1
# CAN Busses
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# PWM Output
PB1 TIM8_CH3N TIM8 PWM(1) GPIO(50)
PA0 TIM2_CH1 TIM2 PWM(2) GPIO(51)
PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
PA3 TIM2_CH4 TIM2 PWM(5) GPIO(54)
PD12 TIM4_CH1 TIM4 PWM(6) GPIO(55)
PD13 TIM4_CH2 TIM4 PWM(7) GPIO(56)
PD14 TIM4_CH3 TIM4 PWM(8) GPIO(57)
PD15 TIM4_CH4 TIM4 PWM(9) GPIO(58)
PE5 TIM15_CH1 TIM15 PWM(10) GPIO(59)
PE6 TIM15_CH2 TIM15 PWM(11) GPIO(60)
PA8 TIM1_CH1 TIM1 PWM(12) GPIO(61) # for WS2812 LED
define HAL_SPI_CHECK_CLOCK_FREQ
# sensor CS
PC7 MPU_CS CS
# status LEDs
define HAL_LED_ON 0
PB0 LED OUTPUT HIGH GPIO(0) #Green
PE1 LED1 OUTPUT HIGH GPIO(2) #Yellow
PB14 LED2 OUTPUT HIGH GPIO(1) #Red
define HAL_GPIO_A_LED_PIN 0
define HAL_GPIO_B_LED_PIN 1
define HAL_GPIO_C_LED_PIN 2
define HAL_GPIO_LED_OFF 1
define HAL_GPIO_LED_ON 0
# I2C
I2C_ORDER I2C2
define HAL_I2C_INTERNAL_MASK 0
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
define HAL_OS_FATFS_IO 1
# Now some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# barometers
BARO BMP388 I2C:0:0x77
# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI3
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
# SPI devices
SPIDEV icm20948 SPI3 DEVID1 MPU_CS MODE3 4*MHZ 8*MHZ
# analog in
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC3 BATT_CURRENT_SENS ADC1 SCALE(1)
# probe for an invensense IMU
IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270
# compass as part of ICM20948 on newer cubes
COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90