mirror of https://github.com/ArduPilot/ardupilot
195 lines
4.4 KiB
Plaintext
195 lines
4.4 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for Diatone MambaH743 mk4 hardware.
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H743xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1073
|
|
|
|
# crystal frequency, setup to use external oscillator
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
MCU_CLOCKRATE_MHZ 480
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 12
|
|
define CH_CFG_ST_RESOLUTION 16
|
|
|
|
# leave 1 sectors free
|
|
FLASH_RESERVE_START_KB 384
|
|
|
|
# use last 2 pages for flash storage
|
|
# H743 has 16 pages of 128k each
|
|
STORAGE_FLASH_PAGE 1
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# enable logging to dataflash
|
|
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
|
|
|
# one I2C bus
|
|
I2C_ORDER I2C1 I2C2
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8
|
|
|
|
# buzzer
|
|
PE3 BUZZER OUTPUT LOW PULLDOWN GPIO(80)
|
|
define HAL_BUZZER_PIN 80
|
|
define AP_NOTIFY_TONEALARM_ENABLED 1
|
|
|
|
# PA10 IO-debug-console
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI1 for BMI270 / MPU6000
|
|
PA4 MPU6000_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# SPI2 for MAX7456 OSD
|
|
PB12 MAX7456_CS CS
|
|
PB13 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
|
|
# SPI3 for flash
|
|
PA15 FLASH_CS CS
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PB2 SPI3_MOSI SPI3
|
|
|
|
# SPI4 for MPU6000_2
|
|
PE11 MPU6000_2_CS CS
|
|
PE12 SPI4_SCK SPI4
|
|
PE13 SPI4_MISO SPI4
|
|
PE14 SPI4_MOSI SPI4
|
|
|
|
# I2C1 for baro
|
|
PB6 I2C1_SCL I2C1
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
# I2C2 for baro
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC3 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
define HAL_BATT_VOLT_PIN 11
|
|
define HAL_BATT_CURR_PIN 13
|
|
define HAL_BATT_VOLT_SCALE 11.1
|
|
define HAL_BATT_CURR_SCALE 64
|
|
|
|
PC2 RSSI_ADC ADC1
|
|
define BOARD_RSSI_ANA_PIN 12
|
|
|
|
PE5 LED0 OUTPUT LOW GPIO(90) # blue
|
|
PE4 LED1 OUTPUT LOW GPIO(91) # orange
|
|
define HAL_GPIO_A_LED_PIN 91
|
|
define HAL_GPIO_B_LED_PIN 90
|
|
define HAL_GPIO_LED_OFF 1
|
|
|
|
# USART1 (RX / SBUS)
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
# USART2
|
|
PD5 USART2_TX USART2 NODMA
|
|
PD6 USART2_RX USART2 NODMA
|
|
|
|
# USART3 (VTX)
|
|
PD8 USART3_TX USART3 NODMA
|
|
PD9 USART3_RX USART3 NODMA
|
|
|
|
# UART4 (GPS)
|
|
PD1 UART4_TX UART4
|
|
PD0 UART4_RX UART4
|
|
|
|
# UART5 (SPORT)
|
|
PC12 UART5_TX UART5 NODMA
|
|
PD2 UART5_RX UART5 NODMA
|
|
|
|
# USART6 (ESC Telemetry)
|
|
PC6 USART6_TX USART6 NODMA
|
|
PC7 USART6_RX USART6 NODMA
|
|
|
|
# UART7 (GPS)
|
|
PE8 UART7_TX UART7
|
|
PE7 UART7_RX UART7
|
|
|
|
PE1 UART8_TX UART8 NODMA
|
|
PE0 UART8_RX UART8 NODMA
|
|
|
|
define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
|
define HAL_SERIAL1_BAUD 115
|
|
define HAL_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry
|
|
define HAL_SERIAL6_BAUD 115
|
|
|
|
# Motors
|
|
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR
|
|
PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51)
|
|
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR
|
|
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53)
|
|
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) BIDIR
|
|
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
|
|
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR
|
|
PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57)
|
|
|
|
# VTX Power control - should be high at startup to ensure power
|
|
PC5 VTX_PWR OUTPUT HIGH GPIO(81)
|
|
define RELAY2_PIN_DEFAULT 81
|
|
|
|
# Motor order implies Betaflight/X for standard ESCs
|
|
define HAL_FRAME_TYPE_DEFAULT 12
|
|
|
|
# LED strip
|
|
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
|
|
|
DMA_NOSHARE SPI3* SPI1*
|
|
|
|
# spi devices
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
|
SPIDEV bmi270 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16
|
|
SPIDEV mpu6000_2 SPI4 DEVID4 MPU6000_2_CS MODE3 1*MHZ 4*MHZ
|
|
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ
|
|
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
|
# v2 board has dual ICM42688
|
|
SPIDEV icm42688 SPI1 DEVID1 MPU6000_CS MODE3 2*MHZ 16*MHZ
|
|
SPIDEV icm42688_2 SPI4 DEVID4 MPU6000_2_CS MODE3 2*MHZ 16*MHZ
|
|
|
|
# no built-in compass, but probe the i2c bus for all possible
|
|
# external compass types
|
|
define ALLOW_ARM_NO_COMPASS
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
|
|
|
# Two MPU6000s or one BMI270
|
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_90
|
|
IMU Invensense SPI:mpu6000_2 ROTATION_YAW_180
|
|
IMU BMI270 SPI:bmi270 ROTATION_PITCH_180
|
|
IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180
|
|
IMU Invensensev3 SPI:icm42688_2 ROTATION_ROLL_180_YAW_270
|
|
|
|
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
|
|
|
# one BARO
|
|
BARO DPS280 I2C:0:0x76
|
|
|
|
# setup for OSD
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
|
|
|
define STM32_PWM_USE_ADVANCED TRUE
|