mirror of https://github.com/ArduPilot/ardupilot
46 lines
909 B
Plaintext
46 lines
909 B
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for Holybro KakuteH7 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1048
|
|
|
|
# crystal frequency, setup to use external oscillator
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# bootloader starts at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# the location where the bootloader will put the firmware
|
|
FLASH_BOOTLOADER_LOAD_KB 128
|
|
|
|
STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1
|
|
|
|
# PA10 IO-debug-console
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
PC13 BUZZER OUTPUT LOW PULLDOWN
|
|
|
|
PC2 LED_BOOTLOADER OUTPUT LOW
|
|
define HAL_LED_ON 1
|
|
|
|
# default to all pins low to avoid ESD issues
|
|
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PE4 IMU_CS CS
|
|
PA4 SDCARD_CS CS
|
|
PB12 SPARE_CS CS
|