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

51 lines
946 B
Plaintext
Raw Normal View History

# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 8000000
define STM32_HSE_BYPASS
# board ID for firmware load
APJ_BOARD_ID 139
# the nucleo seems to have trouble with flashing the last sector?
2019-02-03 21:41:00 -04:00
FLASH_SIZE_KB 1920
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 128
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
UART_ORDER OTG1
# UART7 is debug
PF6 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
#PB0 LED_BOOTLOADER OUTPUT
#PB7 LED_ACTIVITY OUTPUT
#define HAL_LED_ON 0
define STM32_SERIAL_USE_USART7 TRUE
define HAL_USE_SERIAL TRUE
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384