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

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

64 lines
1.4 KiB
Plaintext
Raw Normal View History

# hw definition file for processing by chibios_pins.py
# for SP/Racing Extreme H7 hardware.
# MCU class and specific type
MCU STM32H7xx STM32H750xx
# board ID for firmware load
APJ_BOARD_ID 1060
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000
MCU_CLOCKRATE_MHZ 480
# 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 16
EXT_FLASH_RESERVE_START_KB 1024
EXT_FLASH_RESERVE_END_KB 448
# 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_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PE3 LED_BOOTLOADER OUTPUT LOW # Red LED
define HAL_LED_ON 0
# QuadSPI Flash
PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH
PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH
PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH
PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH
PB10 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH
PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
QSPIDEV w25q-dtr QUADSPI1 MODE3 100*MHZ 24 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# Add CS pins to ensure they are high in bootloader
PB12 ICM20602_2_CS CS
PA15 ICM20602_1_CS CS
PE11 AT7456E_CS CS
## pull up VTX power
PB01 VTX_PWR OUTPUT HIGH GPIO(81)