ardupilot/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef-bl.dat

67 lines
1.4 KiB
Plaintext
Raw Normal View History

# hw definition file for processing by chibios_pins.py
# for SP/Racing H7RF hardware.
# MCU class and specific type
MCU STM32H7xx STM32H730xx
# board ID for firmware load
APJ_BOARD_ID 1108
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000
MCU_CLOCKRATE_MHZ 520
# limited flash that can't be used
FLASH_SIZE_KB 128
FLASH_RESERVE_START_KB 0
FLASH_RESERVE_END_KB 0
FLASH_BOOTLOADER_LOAD_KB 128
# 16mb external flash
EXT_FLASH_SIZE_MB 2
# order of UARTs (and USB). Allow bootloading on USB and telem1
SERIAL_ORDER OTG1 USART1
# USART1
PB15 USART1_RX USART1
PB14 USART1_TX USART1
# USB
PA11 OTG_HS_DM OTG1
PA12 OTG_HS_DP OTG1
# Debug
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PE3 LED_BOOTLOADER OUTPUT LOW # Red LED
define HAL_LED_ON 0
# OctoSPI Flash
PD11 OCTOSPIM_P1_IO0 OCTOSPI1
PD12 OCTOSPIM_P1_IO1 OCTOSPI1
PE2 OCTOSPIM_P1_IO2 OCTOSPI1
PD13 OCTOSPIM_P1_IO3 OCTOSPI1
PE7 OCTOSPIM_P1_IO4 OCTOSPI1
PE8 OCTOSPIM_P1_IO5 OCTOSPI1
PE9 OCTOSPIM_P1_IO6 OCTOSPI1
PE10 OCTOSPIM_P1_IO7 OCTOSPI1
PB6 OCTOSPIM_P1_NCS OCTOSPI1
PB2 OCTOSPIM_P1_CLK OCTOSPI1
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
OSPIDEV w25q OCTOSPI1 MODE3 130*MHZ 21 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PA15 ICM42688_CS CS
PE11 PIXELOSD_CS CS
## pull up VTX power
PC15 VTX_PWR OUTPUT HIGH GPIO(81)