ardupilot/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/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

57 lines
1.0 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# for Matek F405-Wing bootloader
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 127
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
# board voltage
STM32_VDD 330U
# order of UARTs
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA9 USART1_TX USART1
PA10 USART1_RX USART1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PC10 USART3_TX USART3
PC11 USART3_RX USART3
PC12 UART5_TX UART5
PD2 UART5_RX UART5
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0)
PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional
define HAL_LED_ON 0
# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PC14 SDCARD_CS CS
PB12 OSD_CS CS