mirror of https://github.com/ArduPilot/ardupilot
55 lines
1.2 KiB
Plaintext
55 lines
1.2 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for SkystarsH7HD bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1075
|
|
|
|
# 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
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1
|
|
|
|
# H743 has 16 pages of 128k each
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# PA10 IO-debug-console
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
PB3 BUZZER OUTPUT LOW
|
|
|
|
PE3 LED_BOOTLOADER OUTPUT HIGH
|
|
PE4 LED_ACTIVITY OUTPUT HIGH
|
|
define HAL_LED_ON 0
|
|
define HAL_LED_OFF 1
|
|
|
|
# default to all pins low to avoid ESD issues
|
|
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PC15 BMI270_CS1 CS
|
|
PB12 AT7456E_CS CS
|
|
PA15 FLASH_CS CS
|
|
PE11 BMI270_CS2 CS
|
|
|
|
## pull up VTX power so that it is enabled in bootloader
|
|
PC5 VTX_PWR OUTPUT HIGH # labelled as "Pit-1"
|
|
# pull up PIN-EN so that Video 1 is selected by default
|
|
PC2 VID_SELECT OUTPUT HIGH # labelled as "PIN-EN"
|
|
PD2 CAM_C OUTPUT LOW # labelled as "CAM-C"
|