ardupilot/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat

76 lines
1.3 KiB
Plaintext

# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 8000000
define STM32_HSE_BYPASS
# board ID for firmware load
APJ_BOARD_ID 139
# the nucleo seems to have trouble with flashing the last sector?
FLASH_SIZE_KB 2048
FLASH_RESERVE_START_KB 128
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
UART_ORDER OTG1 UART7
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# UART7 is debug
PF6 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
define HAL_SPI_CHECK_CLOCK_FREQ
# sensor CS
PA4 MPU_CS CS
PC7 BARO_CS CS
PB0 LED1 OUTPUT LOW
PB7 LED2 OUTPUT LOW
# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI3
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
# SPI devices
SPIDEV mpu6000 SPI3 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ
SPIDEV ms5611 SPI3 DEVID2 BARO_CS MODE3 8*MHZ 8*MHZ
# analog in
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
# probe for an invensense IMU
IMU Invensense SPI:mpu6000 ROTATION_NONE
# and ms5611 baro
BARO MS56XX SPI:ms56xx
# define HAL_DISABLE_DCACHE