mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -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
50 lines
874 B
Plaintext
50 lines
874 B
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for crazyflie2.0
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 12
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
STM32_PLLM_VALUE 8
|
|
|
|
define STM32_ST_USE_TIMER 5
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# don't allow bootloader to use more than 16k
|
|
FLASH_USE_MAX_KB 16
|
|
|
|
# bootloader is installed at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# LEDs
|
|
PD2 LED_BOOTLOADER OUTPUT HIGH
|
|
PC0 LED_ACTIVITY OUTPUT HIGH
|
|
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
|
|
PC12 E_CS0 CS
|
|
PB4 E_CS1 CS
|
|
PB5 E_CS2 CS
|
|
PB8 E_CS3 CS
|