mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
48c21299f8
hwdef for DevEBoxH7v2 pin definitions for STM32H750 add QSPI to DevEBox bootloader add external flash to DevEBox rename EXTERNAL_PROG_FLASH_MB to EXT_FLASH_SIZE_MB Add support for EXT_FLASH_RESERVE_START_KB and EXT_FLASH_RESERVE_END_KB Disable HAL_ENABLE_SAVE_PERSISTENT_PARAMS when there is no bootloader flash available relax storage health status with SD card backend don't check SD card health unless USE_POSIX binary sections rearranged on external ram manage RAMFUNC through ldscript and optimize function placement in external flash inline timer functions optimize placement of ChibiOS and functions in ITCM and AXI RAM fix chibios features on bootloader build with external flash change H750 memory layout increase line storage for SD card based parameters comment external flash linker script move vtables into DTCM update ram map for H757 enable crashdump support with external flash correct bootloader pins and generator on SPRacingH7/DevEBoxH7v2 setup external flash reserve regions allow different RAM_MAP for external flash on H750 and H757
138 lines
2.7 KiB
Plaintext
138 lines
2.7 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for DevEBox H7 hardware based on SPRacingH7 pinout
|
|
# configured to boot from external flash
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H750xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1061
|
|
|
|
# crystal frequency, setup to use external oscillator
|
|
OSCILLATOR_HZ 25000000
|
|
|
|
STM32_ST_USE_TIMER 2
|
|
|
|
# reserve 256 bytes for comms between app and bootloader
|
|
RAM_RESERVE_START 256
|
|
|
|
define NO_DATAFLASH TRUE
|
|
|
|
FLASH_SIZE_KB 128
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
EXT_FLASH_SIZE_MB 8
|
|
EXT_FLASH_RESERVE_START_KB 1024
|
|
EXT_FLASH_RESERVE_END_KB 448
|
|
|
|
# only one I2C bus
|
|
I2C_ORDER I2C1
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 EMPTY EMPTY UART8
|
|
|
|
# Buzzer - DMA timer channel use by LEDs
|
|
PD7 BUZZER OUTPUT GPIO(80) LOW
|
|
define HAL_BUZZER_PIN 80
|
|
define HAL_BUZZER_ON 1
|
|
define HAL_BUZZER_OFF 0
|
|
|
|
# USB
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# Debug
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI3 MPU6500 #1
|
|
PA15 MPU6500_1_CS CS
|
|
PB3 SPI3_SCK SPI3
|
|
PB4 SPI3_MISO SPI3
|
|
PD6 SPI3_MOSI SPI3
|
|
|
|
# I2C1 for baro
|
|
PB8 I2C1_SCL I2C1 PULLUP
|
|
PB9 I2C1_SDA I2C1 PULLUP
|
|
|
|
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC0 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
PC4 RSSI_IN ADC1
|
|
define BOARD_RSSI_ANA_PIN 0
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_VOLT_PIN 13
|
|
define HAL_BATT_CURR_PIN 12
|
|
define HAL_BATT_VOLT_SCALE 10.9
|
|
define HAL_BATT_CURR_SCALE 28.5
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
|
|
PC5 RSSI_ADC ADC1
|
|
|
|
# USART1
|
|
PB15 USART1_RX USART1
|
|
PB14 USART1_TX USART1
|
|
|
|
# USART2 (RCIN)
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2 ALT(1)
|
|
define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
|
|
|
# USART3
|
|
PD9 USART3_RX USART3
|
|
PD8 USART3_TX USART3
|
|
|
|
# UART4
|
|
PD0 UART4_RX UART4
|
|
PD1 UART4_TX UART4
|
|
|
|
# UART5
|
|
PB5 UART5_RX UART5
|
|
PB13 UART5_TX UART5
|
|
|
|
# UART8
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
# SD card
|
|
PC8 SDMMC1_D0 SDMMC1
|
|
PC9 SDMMC1_D1 SDMMC1
|
|
PC10 SDMMC1_D2 SDMMC1
|
|
PC11 SDMMC1_D3 SDMMC1
|
|
PC12 SDMMC1_CK SDMMC1
|
|
PD2 SDMMC1_CMD SDMMC1
|
|
|
|
# QuadSPI Flash
|
|
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
|
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
|
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
|
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
|
PB6 QUADSPI_BK1_NCS QUADSPI1
|
|
PB2 QUADSPI_CLK QUADSPI1
|
|
|
|
# Motors
|
|
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) # M1
|
|
PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51) # M2
|
|
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) # M3
|
|
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) # M4
|
|
|
|
PA1 LED0 OUTPUT LOW GPIO(90) # Blue LED
|
|
|
|
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
|
define ALLOW_ARM_NO_COMPASS
|
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
|
|
|
define HAL_OS_FATFS_IO 1
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 4
|
|
|
|
define HAL_USE_EMPTY_STORAGE 1
|
|
#define STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# Nucleo LED
|
|
PB0 LED1 OUTPUT LOW
|