AP_HAL_ChibiOS: add Holybro KakuteH7-Wing

This commit is contained in:
Henry Wurzburg 2023-06-19 07:02:55 -05:00 committed by Randy Mackay
parent abb3bcfb1d
commit 22d3146f38
4 changed files with 375 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 111 KiB

View File

@ -0,0 +1,108 @@
# KakuteH7-Wing Flight Controller
The KakuteH7-Wing is a flight controller produced by [Holybro](http://www.holybro.com/).
## Features
Processor
STM32H743 32-bit processor
AT7456E OSD
Sensors
ICM42688 Acc/Gyro
BMP280 barometer
Power
2S - 8S Lipo input voltage with voltage monitoring
9V/12V, 1.5A BEC for powering Video Transmitter
6V/7.2V, ?A BEC for servos
3.3V, 1A BEC
Interfaces
14x PWM outputs DShot capable, 4 outputs BiDirDShot capable
1x RC input
6x UARTs/serial for GPS and other peripherals
2x I2C ports for external compass, airspeed, etc.
USB-C port
Switchable 9V/12V VTX power
2 Switchable Camera inputs
All UARTS support hardware inversion. SBUS, SmartPort, and other inverted protocols work on any UART without “uninvert hack”
Input for second battery monitor
## Pinout
![KakuteH7-Wing Board](KakuteH7-Wing-pinout.jpg "KakuteH7-Wing)
## UART Mapping
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
- SERIAL0 -> USB
- SERIAL1 -> UART7 (TELEM1) with CTS/RTS DMA Enabled
- SERIAL2 -> UART2 (Telem2) DMA Enabled
- SERIAL3 -> UART1 (GPS) DMA Enabled
- SERIAL4 -> USART3 (GPS2)
- SERIAL5 -> UART5 (User) DMA Enabled
- SERIAL6 -> USART6 (RX normally RCIN, BRD_ALT_CONFIG =1 for normal UART RX)
- SERIAL7 -> UART8 (User) DMA Enabled
## RC Input
RC input is configured on the R6 (UART6_RX) pin. It supports all RC
protocols. For protocols requiring half-duplex serial to transmit
telemetry (such as FPort) you should set BRD_ALT_CONFIG=1 and setup
SERIAL6 as an RC input serial port, with half-duplex, pin-swap
and inversion enabled.
## OSD Support
The KakuteH7 supports OSD using OSD_TYPE 1 (MAX7456 driver).
## PWM Output
The KakuteH7 supports up to 14 PWM outputs. Outputs 1-10 support DShot. Outputs 5-8 support BiDirDshot.
The PWM is in 5 groups:
- PWM 1-4 in group1
- PWM 5,6 in group2
- PWM 7,8 in group3
- PWM 9,10 in group4
- PWM 11-13 in group5
- PWM 14 in group6
Channels within the same group need to use the same output rate. If
any channel in a group uses DShot then all channels in the group need
to use DShot.
## Battery Monitoring
The board has a builting voltage and current sensor. The current
sensor can read up to ?? Amps. The voltage sensor can handle up to 6S
LiPo batteries.
The correct battery setting parameters are:
- BATT_MONITOR 4
- BATT_VOLT_PIN 8
- BATT_CURR_PIN 4
- BATT_VOLT_MULT 18.18
- BATT_AMP_PERVLT 36.6
## Switchable Vidoe Supply and Camera Inputs
The camera input defaults to CAM1 but can be switched to CAM2 by setting a relay set to pin 81. Both cameras should be the same video format.
The 9V/12V video supply can be switched off (default is on) using a relay set topin 82.
## Compass
The KakuteH7-Wing does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads.
## Loading Firmware
Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “KakuteH7-Wing”.
Initial firmware load can be done with DFU by plugging in USB with the
boot button pressed. Then you should load the "KakuteH7-Wing_bl.hex"
firmware, using your favourite DFU loading tool.
Subsequently, you can update firmware with Mission Planner.

View File

@ -0,0 +1,49 @@
# hw definition file for processing by chibios_pins.py
# for Holybro KakuteH7-WING bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# board ID for firmware load
APJ_BOARD_ID 1105
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 16000000
FLASH_SIZE_KB 2048
# bootloader starts at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 128
# order of UARTs (and USB). Allow bootloading on USB and telem1
SERIAL_ORDER OTG1 UART7
# UART7 (telem1)
PE7 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# make sure Vsw is on during bootloader
PE3 PINIO2 OUTPUT LOW
PC15 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
# Add CS pins to ensure they are high in bootloader
PE12 ICM42688_CS CS
PB12 MAX7456_CS CS
PC8 BMI088_A_CS CS
PC9 BMI088_G_CS CS
#silence buzzer during boot
PB9 BUZZER OUTPUT GPIO(80) LOW

View File

@ -0,0 +1,218 @@
# hw definition file for processing by chibios_pins.py
# for Holybro KakuteH7-WING
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# board ID for firmware load
APJ_BOARD_ID 1105
# crystal frequency, setup to use external oscillator (16Mhz)
OSCILLATOR_HZ 16000000
FLASH_SIZE_KB 2048
env OPTIMIZE -Os
# bootloader takes first sector
FLASH_RESERVE_START_KB 128
# ChibiOS system timer
STM32_ST_USE_TIMER 12
define CH_CFG_ST_RESOLUTION 16
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# SPI1 for IMU1 (BMI088)
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PC8 BMI088_A_CS CS
PC9 BMI088_G_CS CS
PD11 DRDY1_BMI088_ACC INPUT
PD10 DRDY2_BMI088_GYRO INPUT
# SPI2 for MAX7456 OSD
PB12 MAX7456_CS CS
PD3 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
#SPI3 for IMU1 (ICM42688)
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
PE12 ICM42688_CS CS
PE15 DRDY1_ICM42688 INPUT
# three I2C bus
I2C_ORDER I2C4 I2C1 I2C2
# I2C4 (BMP280 BARO)
PD12 I2C4_SCL I2C4
PD13 I2C4_SDA I2C4
# I2C1
PB8 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
# I2C2
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# ADC
PC5 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC4 BATT_CURRENT_SENS ADC1 SCALE(1)
PA3 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
PA2 BATT2_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 8
define HAL_BATT_CURR_PIN 4
define HAL_BATT2_VOLT_PIN 15
define HAL_BATT2_CURR_PIN 14
define HAL_BATT_VOLT_SCALE 18.18
define HAL_BATT_CURR_SCALE 36.6
define HAL_BATT2_VOLT_SCALE 11.0
PC0 RSSI_ADC ADC1
define BOARD_RSSI_ANA_PIN 10
# LED
# green LED1 marked as B/E
# blue LED0 marked as ACT
PC15 LED0 OUTPUT LOW GPIO(90) # blue
PC14 LED1 OUTPUT LOW GPIO(91) # red
define HAL_GPIO_A_LED_PIN 91
define HAL_GPIO_B_LED_PIN 90
define HAL_GPIO_LED_OFF 1
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 USART2 USART1 USART3 UART5 USART6 UART8 OTG2
# USART1 (GPS1, SERIAL3)
PA10 USART1_RX USART1
PB6 USART1_TX USART1
# USART2 (TELEM2, SERIAL2)
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# USART3 (GPS2, SERIAL4)
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART5 (USER, SERIAL5)
PB13 UART5_TX UART5
PD2 UART5_RX UART5
# USART6 (RC input), SERIAL6
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN LOW
PC6 USART6_TX USART6 NODMA
# as an alternative config setup the RX6 pin as a uart. This allows
# for bi-directional UART based receiver protocols such as FPort
# without any extra hardware
PC7 USART6_RX USART6 NODMA ALT(1)
# UART7 (TELEM1, SERIAL1)
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE10 UART7_CTS UART7
PE9 UART7_RTS UART7
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MAVLink2
# UART8 (USER, SERIAL7)
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# CAN bus
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# Motors
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50)
PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51)
PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52)
PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53)
PD14 TIM4_CH3 TIM4 PWM(5) GPIO(54) BIDIR
PD15 TIM4_CH4 TIM4 PWM(6) GPIO(55)
PA0 TIM5_CH1 TIM5 PWM(7) GPIO(56) BIDIR
PA1 TIM5_CH2 TIM5 PWM(8) GPIO(57)
PE5 TIM15_CH1 TIM15 PWM(9) GPIO(58)
PE6 TIM15_CH2 TIM15 PWM(10) GPIO(59)
PB5 TIM3_CH2 TIM3 PWM(11) GPIO(60) NODMA
PB0 TIM3_CH3 TIM3 PWM(12) GPIO(61) NODMA
PB1 TIM3_CH4 TIM3 PWM(13) GPIO(62) NODMA
PA15 TIM2_CH1 TIM2 PWM(14) GPIO(63) NODMA
# Beeper
#PB9 TIM17_CH1 TIM17 GPIO(77) ALARM
PB9 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
# microSD support
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
PC1 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
define FATFS_HAL_DEVICE SDCD2
# GPIOs 81:CAM SELECT,82:9V SWITCH,83: USER1,84:USER2
PC13 PINIO1 OUTPUT GPIO(81) LOW
PE3 PINIO2 OUTPUT GPIO(82) HIGH
PD4 PINIO3 OUTPUT GPIO(83) LOW
PE4 PINIO4 OUTPUT GPIO(84) LOW
#Power Control and Status
PA9 VBUS_VALID INPUT
PB2 VDD_3V3_SENSORS_EN OUTPUT HIGH
PA4 VDD_5V_SENS ADC1 SCALE(2)
PE2 VDD_BRICK_nVALID INPUT FLOAT
define HAL_STORAGE_SIZE 32768
# use last 2 pages for flash storage
# H743 has 16 pages of 128k each
STORAGE_FLASH_PAGE 14
# spi devices
SPIDEV bmi088_a SPI1 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ
SPIDEV bmi088_g SPI1 DEVID2 BMI088_G_CS MODE3 10*MHZ 10*MHZ
SPIDEV icm42688 SPI3 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ
SPIDEV osd SPI2 DEVID3 MAX7456_CS MODE0 10*MHZ 10*MHZ
DMA_NOSHARE SPI1* SPI3* TIM4* TIM5*
# 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 1
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# One IMU (orientation needs to be determined)
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180_YAW_270
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
# BMP280 integrated on I2C4 bus
BARO BMP280 I2C:0:0x76
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
NODMA I2C*
define STM32_I2C_USE_DMA FALSE