ardupilot/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroF7/hwdef-bl.dat
Andrew Tridgell d35fff5186 HAL_ChibiOS: set CS pins high while in bootloader
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
2020-03-11 09:53:06 +11:00

67 lines
1.3 KiB
Plaintext

# hw definition file for processing by chibios_hwdef.py
# for F777 bootloader
# MCU class and specific type
MCU STM32F7xx STM32F777xx
# USB setup
USB_STRING_MANUFACTURER "mRo"
# crystal frequency
OSCILLATOR_HZ 24000000
define STM32_LSECLK 32768U
define STM32_LSEDRV (3U << 3U)
define STM32_PLLSRC STM32_PLLSRC_HSE
define STM32_PLLM_VALUE 24
define STM32_PLLN_VALUE 432
define STM32_PLLP_VALUE 2
define STM32_PLLQ_VALUE 9
# board ID for firmware load
APJ_BOARD_ID 141
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 96
PB11 LED_BOOTLOADER OUTPUT
# define all 3 to make LED output White.
PB1 LED_ACTIVITY OUTPUT
PB3 LED_ACTIVITY2 OUTPUT
# PB11 LED_ACTIVITY3 OUTPUT
define HAL_LED_ON 0
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
UART_ORDER OTG1 UART7
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
PE7 UART7_RX UART7
PE8 UART7_TX UART7
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
PC2 ICM_20602_CS CS
PD7 BARO_CS CS
PD10 FRAM_CS CS SPEED_VERYLOW NODMA
PE15 ICM_20948_CS CS
PF10 BMI088_GYRO_CS CS
PF6 BMI088_ACCEL_CS CS