mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
6968d67a05
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
45 lines
807 B
Plaintext
45 lines
807 B
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for minimal F405 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 125
|
|
|
|
# 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
|
|
PB9 LED_BOOTLOADER OUTPUT LOW
|
|
PA14 LED_ACTIVITY 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
|
|
PB10 MAX7456_CS CS
|
|
PC1 SDCARD_CS CS
|
|
PC0 M25P16_CS CS
|
|
PC2 MPU6000_CS CS
|