mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -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
42 lines
720 B
Plaintext
42 lines
720 B
Plaintext
# hw definition file for KakuteF4 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 122
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
STM32_PLLM_VALUE 8
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# bootloader is installed at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# LEDs
|
|
PB5 LED_BOOTLOADER OUTPUT LOW
|
|
define HAL_LED_ON 0
|
|
|
|
# the location where the bootloader will put the firmware
|
|
FLASH_BOOTLOADER_LOAD_KB 64
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs
|
|
UART_ORDER OTG1
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
define HAL_USE_EMPTY_STORAGE 1
|
|
define HAL_STORAGE_SIZE 15360
|
|
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PB14 MAX7456_CS CS
|
|
PB3 FLASH_CS CS
|
|
PC4 ICM20689_CS CS
|