mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -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
54 lines
1.0 KiB
Plaintext
54 lines
1.0 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for Holybro KakuteF7 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F7xx STM32F745xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 123
|
|
|
|
# crystal frequency, setup to use external oscillator
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
define STM32_LSECLK 32768U
|
|
define STM32_LSEDRV (3U << 3U)
|
|
|
|
define STM32_PLLSRC STM32_PLLSRC_HSE
|
|
define STM32_PLLM_VALUE 8
|
|
define STM32_PLLN_VALUE 432
|
|
define STM32_PLLP_VALUE 2
|
|
define STM32_PLLQ_VALUE 9
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# bootloader starts at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# the location where the bootloader will put the firmware
|
|
FLASH_BOOTLOADER_LOAD_KB 96
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1
|
|
|
|
# PA10 IO-debug-console
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
PA2 LED_BOOTLOADER OUTPUT LOW
|
|
define HAL_LED_ON 0
|
|
|
|
define HAL_USE_EMPTY_STORAGE 1
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PA4 SDCARD_CS CS
|
|
PB12 MAX7456_CS CS
|
|
PE4 ICM20689_CS CS
|