mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 16:38:30 -04:00
d35fff5186
this appears to be the root cause of the parameter resets on CubeOrange. We need to ensure the CS pin is not floating or random noise on the SPI bus for FRAM can cause the FRAM to become corrupt
67 lines
1.3 KiB
Plaintext
67 lines
1.3 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for H743 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
# USB setup
|
|
USB_VENDOR 0x3162 # ONLY FOR USE BY Holybro
|
|
USB_PRODUCT 0x004B
|
|
USB_STRING_MANUFACTURER "Holybro"
|
|
USB_STRING_PRODUCT "Durandal-BL"
|
|
USB_STRING_SERIAL "%SERIAL%"
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 139
|
|
|
|
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
|
|
|
|
PB1 LED_RED OUTPUT LOW # red
|
|
PC6 LED_ACTIVITY OUTPUT LOW # green
|
|
PC7 LED_BOOTLOADER OUTPUT LOW # blue
|
|
|
|
define HAL_LED_ON 0
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 UART7
|
|
|
|
# UART7 is debug
|
|
PF6 UART7_RX UART7 NODMA
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
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
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PF10 MS5611_CS CS
|
|
PF2 ICM20689_CS CS SPEED_VERYLOW
|
|
PF3 ICM20602_CS CS SPEED_VERYLOW
|
|
PF4 BMI055_G_CS CS
|
|
PG10 BMI055_A_CS CS
|
|
PF5 FRAM_CS CS SPEED_VERYLOW
|
|
PI4 EXT1_CS1 CS
|
|
PI10 EXT1_CS2 CS
|
|
PI6 EXT2_CS1 CS
|
|
PI7 EXT2_CS2 CS
|
|
PI8 EXT2_CS3 CS
|
|
PH5 TSENSE_CS CS
|