mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -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
72 lines
1.4 KiB
Plaintext
72 lines
1.4 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for F765 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F7xx STM32F767xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
define STM32_LSECLK 32768U
|
|
define STM32_LSEDRV (3U << 3U)
|
|
define STM32_PLLSRC STM32_PLLSRC_HSE
|
|
define STM32_PLLM_VALUE 8
|
|
define STM32_PLLN_VALUE 216
|
|
define STM32_PLLP_VALUE 2
|
|
define STM32_PLLQ_VALUE 9
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 50
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# bootloader is installed at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# the location where the bootloader will put the firmware
|
|
FLASH_BOOTLOADER_LOAD_KB 32
|
|
|
|
PC6 LED_BOOTLOADER OUTPUT HIGH
|
|
PC7 LED_ACTIVITY OUTPUT HIGH
|
|
define HAL_LED_ON 0
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 USART2 UART7
|
|
|
|
# USART2 is telem1
|
|
PD6 USART2_RX USART2
|
|
PD5 USART2_TX USART2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
|
|
PF6 UART7_RX UART7 NODMA
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
define HAL_USE_EMPTY_STORAGE 1
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PF10 MS5611_CS CS
|
|
PF2 ICM20689_CS CS SPEED_VERYLOW
|
|
PF3 ICM20602_CS CS SPEED_VERYLOW
|
|
PF4 BMI055_G_CS CS
|
|
PG10 BMI055_A_CS CS
|
|
PF5 FRAM_CS CS SPEED_VERYLOW
|
|
PF11 SPARE_CS CS
|
|
PH5 AUXMEM_CS CS
|
|
PI4 EXTERNAL1_CS1 CS
|
|
PI10 EXTERNAL1_CS2 CS
|
|
PI11 EXTERNAL1_CS3 CS
|
|
PI6 EXTERNAL2_CS1 CS
|
|
PI7 EXTERNAL2_CS2 CS
|
|
PI8 EXTERNAL2_CS3 CS
|