mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-07 16:38:30 -04:00
10416f92c4
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
58 lines
1014 B
Plaintext
58 lines
1014 B
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for MindPX-v2 hardware bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F427xx
|
|
|
|
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
|
|
define HAL_CHIBIOS_ARCH_MINDPXV2 1
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 88
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
STM32_PLLM_VALUE 8
|
|
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# flash size
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# location of application code
|
|
FLASH_BOOTLOADER_LOAD_KB 16
|
|
|
|
# bootloader loads at start of flash
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 USART2
|
|
|
|
PA9 VBUS INPUT
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# USART2 serial2 telem1
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2
|
|
|
|
PA8 LED_BOOTLOADER OUTPUT
|
|
define HAL_LED_ON 1
|
|
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PB2 GYRO_CS CS
|
|
PC15 BARO_CS CS
|
|
PD11 ACCEL_MAG_CS CS
|
|
PE3 MPU_CS CS
|
|
PE12 FRAM_CS CS
|
|
PE15 NRF_CS CS
|