mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
2b0a30a2c5
this modifies the ld script to use the maximum size available for the bootloader, so we can't accidentially grow the bootloader beyond its max size
52 lines
1.0 KiB
Plaintext
52 lines
1.0 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for H743 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# USB setup
|
|
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
|
|
USB_PRODUCT 0x1016
|
|
USB_STRING_MANUFACTURER "Hex/ProfiCNC"
|
|
USB_STRING_PRODUCT "CubeOrange-BL"
|
|
USB_STRING_SERIAL "%SERIAL%"
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 140
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# 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
|
|
|
|
define HAL_LED_ON 0
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 UART7
|
|
|
|
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
# Pin for PWM Voltage Selection
|
|
PB4 PWM_VOLT_SEL OUTPUT HIGH
|
|
|
|
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
|