mirror of https://github.com/ArduPilot/ardupilot
286 lines
6.2 KiB
Plaintext
286 lines
6.2 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 7100
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# with 2M flash we can afford to optimize for speed
|
|
env OPTIMIZE -O2
|
|
|
|
# bootloader takes first sector
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART2 USART6 USART1 USART3 UART8 UART4 OTG2 UART7
|
|
|
|
# USB
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# UARTs
|
|
# USART2 is telem1
|
|
PD6 USART2_RX USART2
|
|
PD5 USART2_TX USART2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
|
|
# USART6 is telem2
|
|
PC7 USART6_RX USART6
|
|
PC6 USART6_TX USART6
|
|
PG15 USART6_CTS USART6
|
|
PG8 USART6_RTS USART6
|
|
|
|
# USART1 is GPS1
|
|
PB15 USART1_RX USART1 NODMA
|
|
PB14 USART1_TX USART1 NODMA
|
|
|
|
# UART3 is GPS2
|
|
PD9 USART3_RX USART3 NODMA
|
|
PD8 USART3_TX USART3 NODMA
|
|
|
|
# SBUS, DSM port
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
# RS232
|
|
PH14 UART4_RX UART4 NODMA
|
|
PH13 UART4_TX UART4 NODMA
|
|
|
|
# UART7 is debug
|
|
PF6 UART7_RX UART7 NODMA
|
|
PF7 UART7_TX UART7 NODMA
|
|
|
|
# debug pins
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI1 - sensors1
|
|
PG11 SPI1_SCK SPI1
|
|
PG9 SPI1_MISO SPI1
|
|
PD7 SPI1_MOSI SPI1
|
|
|
|
# SPI2 - compass
|
|
PI1 SPI2_SCK SPI2
|
|
PI2 SPI2_MISO SPI2
|
|
PI3 SPI2_MOSI SPI2
|
|
|
|
# SPI4 - sensors2 - baro1
|
|
PE12 SPI4_SCK SPI4
|
|
PE13 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
|
|
# SPI6 - sensors3 - baro2
|
|
PG13 SPI6_SCK SPI6
|
|
PB4 SPI6_MISO SPI6
|
|
PG14 SPI6_MOSI SPI6
|
|
|
|
# SPI5 - FRAM
|
|
PK0 SPI5_SCK SPI5
|
|
PJ11 SPI5_MISO SPI5
|
|
PJ10 SPI5_MOSI SPI5
|
|
|
|
# sensor CS
|
|
PG10 IMU1_CS CS
|
|
PJ2 IMU2_CS CS
|
|
PI4 IMU3_CS CS
|
|
PE8 RM3100_CS CS
|
|
PE4 BAROMETER1_CS CS
|
|
PI9 BAROMETER2_CS CS
|
|
PK2 FRAM_CS CS
|
|
|
|
# RESERVE CS
|
|
PE10 RESERVE_CS1 CS
|
|
PI14 RESERVE_CS2 CS
|
|
PI15 RESERVE_CS3 CS
|
|
|
|
# drdy pins
|
|
PH4 DRDY1_ADIS16470 INPUT GPIO(93)
|
|
PH10 DRDY2_ICM42688 INPUT
|
|
PE9 DRDY3_RM3100 INPUT
|
|
PH5 DRDY4_ICM42688 INPUT
|
|
|
|
# use GPIO(93) for data ready on ADIS16470
|
|
define ADIS_DRDY_PIN 93
|
|
|
|
# I2C buses
|
|
|
|
# I2C1 is on I2C1 port
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
# I2C2 on I2C2 port
|
|
PF1 I2C2_SCL I2C2
|
|
PF0 I2C2_SDA I2C2
|
|
|
|
# I2C3 is on GPS2 port
|
|
PH7 I2C3_SCL I2C3
|
|
PH8 I2C3_SDA I2C3
|
|
|
|
# I2C4 is on GPS1 port
|
|
PF14 I2C4_SCL I2C4
|
|
PF15 I2C4_SDA I2C4
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C1 I2C2 I2C3 I2C4
|
|
|
|
NODMA I2C*
|
|
define STM32_I2C_USE_DMA FALSE
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# 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 LOW
|
|
PG4 VDD_5V_PERIPH_EN OUTPUT LOW
|
|
|
|
PD10 VDD_5V_RC_EN OUTPUT HIGH
|
|
PG7 VDD_3V3_SD_CARD_EN OUTPUT LOW
|
|
|
|
# PWM AUX channels
|
|
PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR
|
|
PB3 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
|
PB10 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR
|
|
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
|
PK1 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR
|
|
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
|
PJ9 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR
|
|
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
|
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58)
|
|
PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59)
|
|
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60)
|
|
PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61)
|
|
PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA
|
|
PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA
|
|
|
|
# PWM output for buzzer
|
|
PE5 TIM15_CH1 TIM15 GPIO(77) ALARM
|
|
|
|
# RC input
|
|
PB1 TIM3_CH4 TIM3 RCININT PULLDOWN LOW
|
|
|
|
# analog in
|
|
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PF11 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
PA5 SPARE1_ADC1 ADC1 SCALE(1)
|
|
PA6 SPARE2_ADC1 ADC1 SCALE(2)
|
|
|
|
PB0 RSSI_IN ADC1 SCALE(1)
|
|
|
|
PC0 VDD_5V_SENS ADC1 SCALE(2)
|
|
PC2 SCALED_V3V3 ADC1 SCALE(2)
|
|
|
|
PF12 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3)
|
|
|
|
# CAN bus
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
PB5 CAN2_RX CAN2
|
|
PB6 CAN2_TX CAN2
|
|
|
|
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_nVALID INPUT PULLUP
|
|
PG2 VDD_BRICK2_nVALID INPUT PULLUP
|
|
PG0 VBUS_nVALID INPUT PULLUP
|
|
PJ3 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
|
PJ4 VDD_5V_PERIPH_nOC INPUT PULLUP
|
|
|
|
# SPI devices
|
|
SPIDEV adis16470 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 2*MHZ
|
|
SPIDEV imu1_res SPI1 DEVID2 RESERVE_CS1 MODE3 2*MHZ 8*MHZ
|
|
SPIDEV rm3100 SPI2 DEVID1 RM3100_CS MODE3 1*MHZ 1*MHZ
|
|
SPIDEV imu2 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV baro1 SPI4 DEVID2 BAROMETER1_CS MODE3 20*MHZ 20*MHZ
|
|
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
SPIDEV imu3 SPI6 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV baro2 SPI6 DEVID2 BAROMETER2_CS MODE3 20*MHZ 20*MHZ
|
|
|
|
# two baro
|
|
BARO MS56XX SPI:baro1
|
|
BARO MS56XX SPI:baro2
|
|
|
|
# three IMUs
|
|
IMU ADIS1647x SPI:adis16470 ROTATION_PITCH_180_YAW_270 ADIS_DRDY_PIN
|
|
IMU Invensensev3 SPI:imu1_res ROTATION_PITCH_180_YAW_270
|
|
IMU Invensensev3 SPI:imu2 ROTATION_PITCH_180_YAW_270
|
|
IMU Invensensev3 SPI:imu3 ROTATION_PITCH_180
|
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 7
|
|
|
|
# compasses
|
|
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
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 AP_NOTIFY_GPIO_LED_RGB_RED_PIN 0
|
|
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 1
|
|
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 2
|
|
|
|
# use pixracer style 3-LED indicators
|
|
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
|
|
|
|
# enable RAMTROM parameter storage
|
|
define HAL_STORAGE_SIZE 32768
|
|
define HAL_WITH_RAMTRON 1
|
|
|
|
# allow to have have a dedicated safety switch pin
|
|
define HAL_HAVE_SAFETY_SWITCH 1
|
|
PE2 LED_SAFETY OUTPUT
|
|
PI13 SAFETY_IN INPUT PULLDOWN
|
|
|
|
# build ABIN for flash-from-bootloader support:
|
|
env BUILD_ABIN False
|
|
|
|
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
DMA_PRIORITY ADC* SPI1* TIM*UP*
|
|
DMA_NOSHARE SPI1* TIM*UP*
|
|
|
|
# Enable Sagetech MXS ADSB transponder
|
|
define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
define HAL_BATT_CURR_PIN 2
|
|
define HAL_BATT_VOLT_PIN 16
|
|
define HAL_BATT_CURR_SCALE 60.61
|
|
define HAL_BATT_VOLT_SCALE 15.7
|
|
|
|
# setup the parameter for the ADC rssi
|
|
define BOARD_RSSI_ANA_PIN 9
|