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
66 lines
1.3 KiB
Plaintext
Executable File
66 lines
1.3 KiB
Plaintext
Executable File
# hw definition file for processing by chibios_hwdef.py
|
|
# for CUAV-Nora board
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1009
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# bootloader is installed at zero offset
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
# the location where the bootloader will put the firmware
|
|
# the H743 has 128k sectors
|
|
FLASH_BOOTLOADER_LOAD_KB 128
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 2
|
|
|
|
PD8 LED_RED OUTPUT OPENDRAIN HIGH # red
|
|
PC7 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue
|
|
PC6 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
|
|
|
define HAL_LED_ON 0
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
# order of UARTs (and USB)
|
|
UART_ORDER OTG1 UART7
|
|
|
|
# UART7 is debug
|
|
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
|
|
|
|
define BOOTLOADER_DEBUG SD7
|
|
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PF10 ADIS16470_CS CS
|
|
PF2 RM3100_CS CS
|
|
PG6 ICM20689_CS CS SPEED_VERYLOW
|
|
PI12 ICM20649_CS CS SPEED_VERYLOW
|
|
PF3 BMI088_A_CS CS
|
|
PF4 BMI088_G_CS CS
|
|
PF5 FRAM_CS CS SPEED_VERYLOW
|
|
PG10 MS5611_IMU_CS CS
|
|
PI8 MS5611_BOARD_CS CS
|
|
PI4 EXT1_CS1 CS
|
|
PI10 EXT1_CS2 CS
|
|
PI6 EXT1_CS3 CS
|