ardupilot/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef-bl.dat
Andrew Tridgell d35fff5186 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-03-11 09:53:06 +11:00

51 lines
797 B
Plaintext

# hw definition file for processing by chibios_hwdef.py
# for f4by bootloader
MCU STM32F4xx STM32F407xx
APJ_BOARD_ID 20
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# board voltage
STM32_VDD 330U
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 1024
# order of UARTs (and USB)
UART_ORDER OTG1 USART2
PE3 LED_BOOTLOADER OUTPUT
PE2 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
PD5 USART2_TX USART2
PD6 USART2_RX USART2
FLASH_USE_MAX_KB 16
FLASH_RESERVE_START_KB 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# location of application code
FLASH_BOOTLOADER_LOAD_KB 16
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PB12 FRAM_CS CS SPEED_VERYLOW
PE15 FLASH_CS CS