mirror of https://github.com/ArduPilot/ardupilot
293 lines
6.5 KiB
Plaintext
Executable File
293 lines
6.5 KiB
Plaintext
Executable File
# hw definition file for processing by chibios_hwdef.py for CUAV-Nora
|
|
|
|
# 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
|
|
|
|
# with 2M flash we can afford to optimize for speed
|
|
env OPTIMIZE -O2
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 2
|
|
|
|
# bootloader takes first sector
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2
|
|
|
|
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
|
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
|
|
|
# now we define the pins that USB is connected on
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# Port switching for USB HS and FS,high = USB_FS , LOW = USB_HS
|
|
PH15 USB_HS_ENABLE OUTPUT HIGH
|
|
define USB_HW_ENABLE_HS 0
|
|
|
|
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI1 - internal sensors
|
|
PG11 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PD7 SPI1_MOSI SPI1
|
|
|
|
# SPI2 - FRAM
|
|
PI1 SPI2_SCK SPI2
|
|
PI2 SPI2_MISO SPI2
|
|
PI3 SPI2_MOSI SPI2
|
|
|
|
# SPI4 - sensors2
|
|
PE2 SPI4_SCK SPI4
|
|
PE13 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
|
|
# SPI5 - external1
|
|
PF7 SPI5_SCK SPI5
|
|
PF8 SPI5_MISO SPI5
|
|
PF9 SPI5_MOSI SPI5
|
|
|
|
# SPI6 - external2
|
|
PG13 SPI6_SCK SPI6
|
|
PG12 SPI6_MISO SPI6
|
|
PA7 SPI6_MOSI SPI6
|
|
|
|
# sensor
|
|
|
|
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
|
|
|
|
# external CS pins, SPI5 connector
|
|
PI4 EXT1_CS1 CS
|
|
PI10 EXT1_CS2 CS
|
|
PI13 EXT1_CS3 CS
|
|
|
|
# I2C buses
|
|
|
|
# I2C1 is on GPS port
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
# I2C2 on GPS2 connector
|
|
PF1 I2C2_SCL I2C2
|
|
PF0 I2C2_SDA I2C2
|
|
|
|
# I2C3 for onboard mag
|
|
PH7 I2C3_SCL I2C3
|
|
PH8 I2C3_SDA I2C3
|
|
|
|
# I2C4 is on BDMA on DMAMUX2
|
|
PF14 I2C4_SCL I2C4
|
|
PF15 I2C4_SDA I2C4
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C3 I2C1 I2C2 I2C4
|
|
|
|
define HAL_I2C_INTERNAL_MASK 1
|
|
|
|
# enable pins
|
|
PE3 VDD_3V3_SENSORS_EN OUTPUT LOW
|
|
|
|
# start peripheral power off, then enable after init
|
|
# this prevents a problem with radios that use RTS for
|
|
# bootloader hold
|
|
PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH
|
|
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
|
|
|
|
PG5 VDD_5V_RC_EN OUTPUT HIGH
|
|
PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
|
|
|
# drdy pins
|
|
PE7 DRDY1_ADIS16470 INPUT
|
|
PH5 DRDY2_ICM20649 INPUT
|
|
PB14 DRDY3_BMI088_GYRO1 INPUT
|
|
PB15 DRDY4_BMI088_ACC1 INPUT
|
|
PJ0 DRDY5_ICM20689 INPUT
|
|
PC13 DRDY6_BMI088_GYRO2 INPUT
|
|
PI14 DRDY7_BMI088_ACC2 INPUT
|
|
PE4 DRDY8_RM3100 INPUT
|
|
|
|
# UARTs
|
|
|
|
# USART2 is telem1
|
|
PD6 USART2_RX USART2
|
|
PD5 USART2_TX USART2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
|
|
# USART1 is GPS1
|
|
PB7 USART1_RX USART1 NODMA
|
|
PB6 USART1_TX USART1 NODMA
|
|
|
|
# UART4 GPS2
|
|
PD0 UART4_RX UART4 NODMA
|
|
PD1 UART4_TX UART4 NODMA
|
|
|
|
# USART6 is telem2
|
|
PG9 USART6_RX USART6
|
|
PG14 USART6_TX USART6
|
|
PG15 USART6_CTS USART6
|
|
PG8 USART6_RTS USART6
|
|
|
|
# UART7 is debug
|
|
PF6 UART7_RX UART7 NODMA
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
# SBUS, DSM port
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
# PWM AUX channels
|
|
PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50)
|
|
PH11 TIM5_CH2 TIM5 PWM(2) GPIO(51)
|
|
PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52)
|
|
PI0 TIM5_CH4 TIM5 PWM(4) GPIO(53)
|
|
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
|
|
PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
|
|
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56)
|
|
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
|
|
|
|
PE9 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
|
PE11 TIM1_CH2 TIM1 PWM(10) GPIO(59)
|
|
PA10 TIM1_CH3 TIM1 PWM(11) GPIO(60)
|
|
PE14 TIM1_CH4 TIM1 PWM(12) GPIO(61)
|
|
PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA
|
|
PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA
|
|
|
|
# allow for 14 PWMs by default
|
|
define BOARD_PWM_COUNT_DEFAULT 14
|
|
|
|
# PWM output for buzzer
|
|
PE5 TIM15_CH1 TIM15 GPIO(77) ALARM
|
|
|
|
# RC input
|
|
PB4 TIM3_CH1 TIM3 RCININT PULLUP LOW
|
|
|
|
# analog in
|
|
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# ADC3.3/ADC6.6
|
|
PC4 SPARE1_ADC1 ADC1 SCALE(1)
|
|
PA4 SPARE2_ADC1 ADC1 SCALE(1)
|
|
|
|
PF12 RSSI_IN ADC1 SCALE(1)
|
|
|
|
PC5 VDD_5V_SENS ADC1 SCALE(2)
|
|
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
|
|
|
# CAN bus
|
|
PI9 CAN1_RX CAN1
|
|
PH13 CAN1_TX CAN1
|
|
|
|
# 2nd CAN bus. Cannot be used at same time as USB_HS
|
|
PB12 CAN2_RX CAN2
|
|
PB13 CAN2_TX CAN2
|
|
|
|
# control for silent (no output) for CAN
|
|
PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
|
PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
|
|
|
|
# GPIOs
|
|
|
|
PA8 HEATER_EN OUTPUT LOW GPIO(80)
|
|
define HAL_HEATER_GPIO_PIN 80
|
|
define HAL_HAVE_IMU_HEATER 1
|
|
|
|
PG1 VDD_BRICK_VALID INPUT PULLUP
|
|
PG2 VDD_BRICK2_VALID INPUT PULLUP
|
|
PG0 nVBUS INPUT PULLUP
|
|
PJ3 VDD_5V_HIPOWER_OC INPUT PULLUP
|
|
PJ4 VDD_5V_PERIPH_OC INPUT PULLUP
|
|
PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH
|
|
|
|
# SPI devices
|
|
SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ
|
|
SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ
|
|
SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ
|
|
|
|
# two baro
|
|
BARO MS56XX SPI:ms5611_imu
|
|
BARO MS56XX SPI:ms5611_board
|
|
|
|
# three IMUs
|
|
IMU Invensense SPI:icm20689 ROTATION_NONE
|
|
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270
|
|
IMU Invensensev2 SPI:icm20649 ROTATION_NONE
|
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
|
|
|
# compasses
|
|
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
|
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90
|
|
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
|
|
|
|
|
# microSD support
|
|
PC8 SDMMC1_D0 SDMMC1
|
|
PC9 SDMMC1_D1 SDMMC1
|
|
PC10 SDMMC1_D2 SDMMC1
|
|
PC11 SDMMC1_D3 SDMMC1
|
|
PC12 SDMMC1_CK SDMMC1
|
|
PD2 SDMMC1_CMD SDMMC1
|
|
|
|
# red LED marked as B/E
|
|
|
|
PI5 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
|
|
PI6 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
|
|
PI7 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)
|
|
|
|
define HAL_GPIO_A_LED_PIN 0
|
|
define HAL_GPIO_B_LED_PIN 1
|
|
define HAL_GPIO_C_LED_PIN 2
|
|
|
|
define HAL_GPIO_LED_ON 0
|
|
define HAL_GPIO_LED_OFF 1
|
|
|
|
# use pixracer style 3-LED indicators
|
|
define HAL_HAVE_PIXRACER_LED
|
|
|
|
# enable RAMTROM parameter storage
|
|
define HAL_STORAGE_SIZE 16384
|
|
define HAL_WITH_RAMTRON 1
|
|
|
|
# allow to have have a dedicated safety switch pin
|
|
define HAL_HAVE_SAFETY_SWITCH 1
|
|
PE12 LED_SAFETY OUTPUT
|
|
PE10 SAFETY_IN INPUT PULLDOWN
|
|
|
|
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
DMA_PRIORITY ADC* SPI1* TIM*UP*
|
|
DMA_NOSHARE SPI1* TIM*UP*
|