mirror of https://github.com/ArduPilot/ardupilot
298 lines
8.1 KiB
Plaintext
298 lines
8.1 KiB
Plaintext
###########################################################################################################################################################
|
|
# hw definition file for processing by chibios_hwdef.py
|
|
# STM32H743ZIT6
|
|
# mRo Control Zero Classic flight controller
|
|
# 12x PWM / IO - DMA capable and switchable 3.3v (default) / 5v Logic
|
|
# A Dual CAN based flight controller
|
|
# 3x IMUs (BMI088 6DOF, ICM20602 6DOF, ICM20948 9DOF)
|
|
# Baro, FRAM (256kb), SDCARD Socket, JTAG
|
|
# 5x UARTs (2x with hardware flow control), 2x CAN, 1x SPI, 2x I2C
|
|
# Onboard 3 color LED and buzzer
|
|
# Identical case and connector layout to the original 3DR / mRo Pixhawk
|
|
# M10048B - Initial Release
|
|
###########################################################################################################################################################
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# USB setup
|
|
USB_STRING_MANUFACTURER "mRo"
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1022
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# with 2M flash we can afford to optimize for speed
|
|
env OPTIMIZE -O2
|
|
|
|
# start on 2th sector (1st sector for bootloader)
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
# use FRAM for storage
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# Enable RAMTROM parameter storage.
|
|
define HAL_WITH_RAMTRON 1
|
|
|
|
# RC Input set for Interrupt not DMA
|
|
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
|
|
|
# also USART6_RX for serial RC
|
|
|
|
# Control of Spektrum power pin
|
|
PE4 SPEKTRUM_PWR OUTPUT LOW GPIO(70)
|
|
define HAL_GPIO_SPEKTRUM_PWR 70
|
|
|
|
# Spektrum Power is Active Low
|
|
define HAL_SPEKTRUM_PWR_ENABLED 0
|
|
|
|
# Spektrum RC Input pin, used as GPIO for bind for Satellite Receivers
|
|
PG0 SPEKTRUM_RC INPUT PULLUP GPIO(71)
|
|
define HAL_GPIO_SPEKTRUM_RC 71
|
|
|
|
# Order of I2C buses
|
|
I2C_ORDER I2C1 I2C4
|
|
|
|
# Now the first I2C bus. The pin speeds are automatically setup
|
|
# correctly, but can be overridden here if needed.
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
# Now the first I2C bus. The pin speeds are automatically setup
|
|
# correctly, but can be overridden here if needed.
|
|
PF14 I2C4_SCL I2C4
|
|
PF15 I2C4_SDA I2C4
|
|
|
|
# this board has no internal I2C busses
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# order of UARTs (and USB) and suggested usage
|
|
# USART2 Telem 1 (Flow Control)
|
|
# USART3 Telem 2 (Flow Control)
|
|
# UART4 GPS with I2C1
|
|
# UART7 GPS2 with I2C4
|
|
# UART8 FRSKY Telem
|
|
# USART1 Additional UART
|
|
|
|
# UART6 RC input (Only RX pin is connected)
|
|
|
|
SERIAL_ORDER OTG1 USART2 USART3 UART4 UART7 UART8 USART1 OTG2
|
|
|
|
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
|
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
|
|
|
# Another USART, this one for telem1. This one has RTS and CTS lines.
|
|
# USART2 telem1
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2
|
|
|
|
# The telem2 USART, this one for telem2. This one has RTS and CTS lines.
|
|
# USART3 telem2
|
|
PD8 USART3_TX USART3
|
|
PD9 USART3_RX USART3
|
|
PD11 USART3_CTS USART3
|
|
PD12 USART3_RTS USART3
|
|
|
|
# UART4 GPS
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
|
|
# UART7 GPS2
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
# UART8 FrSky Telemetry
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
# USART1 Spektrum RX
|
|
PB6 USART1_TX USART1
|
|
PB7 USART1_RX USART1
|
|
|
|
# This is the pin to enable the 3.3v sensors rail. It can be used to power
|
|
# cycle sensors to recover them in case there are problems with power on
|
|
# timing affecting sensor stability. We pull it high by default.
|
|
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH GPIO(72)
|
|
|
|
# This is the pin to enable the 1.8v sensors rail. It can be used to power
|
|
# cycle sensors to recover them in case there are problems with power on
|
|
# timing affecting sensor stability. We pull it high by default.
|
|
PC13 VDD_1V8_SENSORS_EN OUTPUT HIGH GPIO(73)
|
|
|
|
# This defines more ADC inputs.
|
|
PB0 AUX_ADC1 ADC1 SCALE(1)
|
|
PB1 AUX_ADC2 ADC1 SCALE(1)
|
|
|
|
# And the analog input for airspeed (rarely used these days).
|
|
PC5 PRESSURE_SENS ADC1 SCALE(2)
|
|
|
|
# RSSI Analog Input
|
|
PC0 RSSI_IN ADC1
|
|
|
|
# Safety Switch Input
|
|
PA10 SAFETY_IN INPUT
|
|
|
|
PE6 LED_SAFETY OUTPUT
|
|
|
|
PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# Now the VDD sense pin. This is used to sense primary board voltage.
|
|
PA4 VDD_5V_SENS ADC1 SCALE(2)
|
|
|
|
# Now setup the default battery pins driver analog pins and default
|
|
# scaling for the power brick.
|
|
define HAL_BATT_VOLT_PIN 4
|
|
define HAL_BATT_CURR_PIN 15
|
|
define HAL_BATT_VOLT_SCALE 10.1
|
|
define HAL_BATT_CURR_SCALE 17.0
|
|
|
|
#SPI1 ICM_20602 / ICM_20948
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
#SPI2 FRAM / DPS310
|
|
PB10 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
|
|
#SPI5 BMI088
|
|
PF7 SPI5_SCK SPI5
|
|
PF8 SPI5_MISO SPI5
|
|
PF9 SPI5_MOSI SPI5
|
|
|
|
#SPI6 EXTERNAL
|
|
PG13 SPI6_SCK SPI6
|
|
PG12 SPI6_MISO SPI6
|
|
PG14 SPI6_MOSI SPI6
|
|
|
|
# This is the pin that senses USB being connected. It is an input pin
|
|
# setup as OPENDRAIN.
|
|
PA9 VBUS INPUT OPENDRAIN
|
|
|
|
# Pins that USB is connected to.
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# PWM output for buzzer
|
|
PF6 TIM16_CH1 TIM16 GPIO(74) ALARM
|
|
|
|
# Now setup the pins for the microSD card, if available.
|
|
PC8 SDMMC1_D0 SDMMC1
|
|
PC9 SDMMC1_D1 SDMMC1
|
|
PC10 SDMMC1_D2 SDMMC1
|
|
PC11 SDMMC1_D3 SDMMC1
|
|
PC12 SDMMC1_CK SDMMC1
|
|
PD2 SDMMC1_CMD SDMMC1
|
|
|
|
# More CS pins for more sensors. The labels for all CS pins need to
|
|
# match the SPI device table later in this file.
|
|
PD7 BARO_CS CS
|
|
PD10 FRAM_CS CS SPEED_VERYLOW
|
|
PE15 ICM_20948_CS CS
|
|
PF0 BMI088_ACCEL_CS CS
|
|
PF10 BMI088_GYRO_CS CS
|
|
PG3 ICM_20602_CS CS
|
|
PG9 EXT_SPI_CS CS
|
|
PG10 EXT2_SPI_CS CS
|
|
|
|
# the first CAN bus
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
PF11 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(75)
|
|
|
|
# the second CAN bus
|
|
PB12 CAN2_RX CAN2
|
|
PB13 CAN2_TX CAN2
|
|
|
|
PF12 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(76)
|
|
|
|
# Now we start defining some PWM pins. We also map these pins to GPIO
|
|
# values, so users can set BRD_PWM_COUNT to choose how many of the PWM
|
|
# outputs on the primary MCU are setup as PWM and how many as
|
|
# GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs
|
|
# starting at 50.
|
|
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
|
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
|
|
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
|
|
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
|
|
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
|
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
|
PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56)
|
|
PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57)
|
|
PB11 TIM2_CH4 TIM2 PWM(9) GPIO(58)
|
|
PE5 TIM15_CH1 TIM15 PWM(10) GPIO(59)
|
|
PC6 TIM8_CH1 TIM8 PWM(11) GPIO(60)
|
|
PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61)
|
|
|
|
# This is the invensense data-ready pin. We don't use it in the
|
|
# default driver.
|
|
PG2 MPU_DRDY INPUT
|
|
|
|
# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v
|
|
PG6 PWM_VOLT_SEL OUTPUT LOW GPIO(77)
|
|
define HAL_GPIO_PWM_VOLT_PIN 77
|
|
define HAL_GPIO_PWM_VOLT_3v3 0
|
|
|
|
# Power flag pins: these tell the MCU the status of the various power
|
|
# supplies that are available. The pin names need to exactly match the
|
|
# names used in AnalogIn.cpp.
|
|
PC1 VDD_BRICK_nVALID INPUT PULLUP
|
|
|
|
SPIDEV bmi088_g SPI5 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV bmi088_a SPI5 DEVID2 BMI088_ACCEL_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV icm20608 SPI1 DEVID2 ICM_20602_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV icm20948 SPI1 DEVID1 ICM_20948_CS MODE3 2*MHZ 4*MHZ
|
|
SPIDEV dps310 SPI2 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ
|
|
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
|
|
# Now some defines for logging and terrain data files.
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
# allow to have have a dedicated safety switch pin
|
|
define HAL_HAVE_SAFETY_SWITCH 1
|
|
|
|
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
# Control Zero has a TriColor LED, Red, Green, Blue
|
|
define HAL_HAVE_PIXRACER_LED
|
|
|
|
define HAL_GPIO_LED_ON 0
|
|
define HAL_GPIO_LED_OFF 1
|
|
|
|
# LED setup for PixracerLED driver
|
|
PB4 LED_R OUTPUT HIGH GPIO(0)
|
|
PB5 LED_G OUTPUT HIGH GPIO(1)
|
|
PB3 LED_B OUTPUT HIGH GPIO(2)
|
|
|
|
define HAL_GPIO_A_LED_PIN 0
|
|
define HAL_GPIO_B_LED_PIN 1
|
|
define HAL_GPIO_C_LED_PIN 2
|
|
|
|
# 3 IMUs
|
|
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE
|
|
IMU Invensense SPI:icm20608 ROTATION_ROLL_180_YAW_90
|
|
IMU Invensensev2 SPI:icm20948 ROTATION_ROLL_180_YAW_90
|
|
|
|
# 1 baro
|
|
BARO DPS280 SPI:dps310
|
|
|
|
# 1 compass
|
|
COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180
|
|
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|