mirror of https://github.com/ArduPilot/ardupilot
254 lines
5.4 KiB
Plaintext
254 lines
5.4 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py for YJUAV_A6Ultra
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1144
|
|
|
|
env OPTIMIZE -O2
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# bootloader takes first sector
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART2 USART6 USART3 USART1 UART8 UART7 OTG2
|
|
|
|
# now we define the pins that USB is connected on
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# USART2 TELEM1
|
|
PD6 USART2_RX USART2
|
|
PD5 USART2_TX USART2
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
|
|
# USART6 TELEM2
|
|
PC7 USART6_RX USART6
|
|
PC6 USART6_TX USART6
|
|
PG13 USART6_CTS USART6
|
|
PG8 USART6_RTS USART6
|
|
|
|
# USART3 GPS1
|
|
PD9 USART3_RX USART3
|
|
PD8 USART3_TX USART3
|
|
|
|
# USART1 GPS2
|
|
PB7 USART1_RX USART1
|
|
PA9 USART1_TX USART1
|
|
|
|
# SBUS, DSM port
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
# UART7 DEBUG
|
|
PE7 UART7_RX UART7 NODMA
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI1 -IMU1
|
|
PB3 SPI1_SCK SPI1
|
|
PB4 SPI1_MISO SPI1
|
|
PD7 SPI1_MOSI SPI1
|
|
|
|
# SPI6 -IMU2
|
|
PA5 SPI6_SCK SPI6
|
|
PA6 SPI6_MISO SPI6
|
|
PA7 SPI6_MOSI SPI6
|
|
|
|
# SPI5 -IMU3
|
|
PF7 SPI5_SCK SPI5
|
|
PF8 SPI5_MISO SPI5
|
|
PF9 SPI5_MOSI SPI5
|
|
|
|
# SPI4 -Extra SPI
|
|
PE12 SPI4_SCK SPI4
|
|
PE13 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
|
|
# sensors cs
|
|
PE4 IMU1_CS CS
|
|
PF3 IMU2_CS CS
|
|
PF4 IMU3_CS CS
|
|
PE10 FRAM_CS CS
|
|
PE9 BAROMETER1_CS CS
|
|
PE3 BAROMETER2_CS CS
|
|
PC15 RESERVE_CS CS
|
|
|
|
# Extra SPI CS
|
|
PE5 EXT_CS CS
|
|
|
|
# I2C buses
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
PH7 I2C3_SCL I2C3
|
|
PH8 I2C3_SDA I2C3
|
|
|
|
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 1
|
|
|
|
# PWM channels
|
|
PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR
|
|
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
|
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR
|
|
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
|
PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR
|
|
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
|
PA10 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR
|
|
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
|
PB5 TIM3_CH2 TIM3 PWM(9) GPIO(58)
|
|
PB0 TIM3_CH3 TIM3 PWM(10) GPIO(59)
|
|
PB1 TIM3_CH4 TIM3 PWM(11) GPIO(60)
|
|
PH6 TIM12_CH1 TIM12 PWM(12) GPIO(61) NODMA
|
|
PH9 TIM12_CH2 TIM12 PWM(13) GPIO(62) NODMA
|
|
|
|
# PWM output for buzzer
|
|
PD14 TIM4_CH3 TIM4 GPIO(77) ALARM
|
|
|
|
# RC input
|
|
PI7 TIM8_CH3 TIM8 RCININT PULLUP LOW
|
|
|
|
# Analog in
|
|
PC4 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
|
|
PA0 BATT2_CURRENT_SENS ADC1 SCALE(1)
|
|
PC2 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
|
|
|
|
# Analog sys 5v
|
|
PF12 VDD_5V_SENS ADC1 SCALE(2)
|
|
|
|
# ADC3.3/ADC6.6
|
|
PC5 SPARE1_ADC1 ADC1 SCALE(1)
|
|
PC0 SPARE2_ADC1 ADC1 SCALE(2)
|
|
|
|
PC1 RSSI_IN ADC1 SCALE(1)
|
|
|
|
PC3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3)
|
|
|
|
# CAN bus
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
PB12 CAN2_RX CAN2
|
|
PB13 CAN2_TX CAN2
|
|
|
|
# GPIOs
|
|
PC13 HEATER_EN OUTPUT LOW GPIO(80)
|
|
define HAL_HEATER_GPIO_PIN 80
|
|
define HAL_HAVE_IMU_HEATER 1
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
define HAL_BATT_VOLT_PIN 2
|
|
define HAL_BATT_CURR_PIN 4
|
|
define HAL_BATT_VOLT_SCALE 21
|
|
define HAL_BATT_CURR_SCALE 34.6
|
|
|
|
# batt2 default disable
|
|
define HAL_BATT2_VOLT_PIN 12
|
|
define HAL_BATT2_CURR_PIN 16
|
|
define HAL_BATT2_VOLT_SCALE 21
|
|
define HAL_BATT2_CURR_SCALE 34.6
|
|
|
|
#analog rssi pin (also could be used as analog airspeed input)
|
|
# PC1
|
|
define BOARD_RSSI_ANA_PIN 11
|
|
|
|
# enable pins
|
|
PC14 VDD_3V3_SENSORS_EN OUTPUT LOW
|
|
|
|
# red LED marked as B/E
|
|
PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
|
|
PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
|
|
PG0 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
|
|
|
|
# allow to have have a dedicated safety switch pin
|
|
define HAL_HAVE_SAFETY_SWITCH 1
|
|
PB15 LED_SAFETY OUTPUT
|
|
PA4 SAFETY_IN INPUT PULLDOWN
|
|
|
|
# SPI devices
|
|
SPIDEV imu1 SPI6 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV imu2 SPI6 DEVID2 IMU2_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV imu3 SPI1 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV dps310_1 SPI1 DEVID2 BAROMETER1_CS MODE3 5*MHZ 5*MHZ
|
|
SPIDEV dps310_2 SPI5 DEVID1 BAROMETER2_CS MODE3 5*MHZ 5*MHZ
|
|
SPIDEV ramtron SPI5 DEVID2 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
|
|
# IMU1
|
|
IMU Invensense SPI:imu1 ROTATION_NONE
|
|
IMU Invensensev3 SPI:imu1 ROTATION_NONE
|
|
|
|
# IMU2
|
|
IMU Invensense SPI:imu2 ROTATION_NONE
|
|
IMU Invensensev3 SPI:imu2 ROTATION_NONE
|
|
|
|
# IMU3
|
|
IMU Invensense SPI:imu3 ROTATION_NONE
|
|
IMU Invensensev3 SPI:imu3 ROTATION_NONE
|
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
|
|
|
# baro
|
|
BARO DPS310 SPI:dps310_1
|
|
BARO DPS310 SPI:dps310_2
|
|
|
|
# compass
|
|
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
|
|
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
|
COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_180
|
|
|
|
# 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
|
|
|
|
# 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"
|
|
|
|
# enable RAMTROM parameter storage
|
|
define HAL_STORAGE_SIZE 32768
|
|
define HAL_WITH_RAMTRON 1
|
|
|
|
DMA_PRIORITY SPI1* SPI6* TIM*UP*
|
|
DMA_NOSHARE SPI1* SPI6* TIM*UP*
|