ardupilot/libraries/AP_HAL_ChibiOS/hwdef/fmuv4/hwdef-bl.dat
Andrew Tridgell 10416f92c4 HAL_ChibiOS: set CS pins high while in bootloader
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
2020-05-11 13:48:28 +10:00

57 lines
962 B
Plaintext

# hw definition file for processing by chibios_hwdef.py
# for FMUv4 bootloader
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# board ID for firmware load
APJ_BOARD_ID 11
# crystal frequency
OSCILLATOR_HZ 24000000
# board voltage
STM32_VDD 330U
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 2048
# order of UARTs (and USB)
UART_ORDER OTG1 USART2
PB1 LED_BOOTLOADER OUTPUT
PB3 LED_ACTIVITY OUTPUT
define HAL_LED_ON 1
PA9 VBUS INPUT
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
define HAL_STORAGE_SIZE 16384
# location of application code
FLASH_BOOTLOADER_LOAD_KB 16
# bootloader loads at start of flash
FLASH_RESERVE_START_KB 0
# Add CS pins to ensure they are high in bootloader
PC2 MPU9250_CS CS
PC15 20608_CS CS
PD7 BARO_CS CS
PD10 FRAM_CS CS
PE15 MAG_CS CS