mirror of https://github.com/ArduPilot/ardupilot
hwdef: add AnyLeaf H7 board
This commit is contained in:
parent
5749bd5074
commit
078697c825
|
@ -0,0 +1,87 @@
|
|||
# AnyLeaf Mercury H7 Flight Controller
|
||||
|
||||
The Mercury H7 is a flight controller produced by [AnyLeaf](http://www.anyleaf.org/).
|
||||
|
||||
## Features
|
||||
Processor
|
||||
STM32H743 32-bit processor
|
||||
Sensors
|
||||
ICM42688 Acc/Gyro with dedicated 32.768kHz crystal
|
||||
DPS310 barometer
|
||||
Power
|
||||
2S - 6S Lipo input voltage with voltage monitoring
|
||||
9V, 3A supply for powering video transmitters
|
||||
5V, 2A supply for powering servos and electronics
|
||||
3.3V, 500mA supply for powering electronics
|
||||
Interfaces
|
||||
8x Bidirectional-DSHOT, or PWM-capable motor outputs
|
||||
1x CAN-FD port for external peripherals
|
||||
1x DJI-format Vtx connector
|
||||
4x UARTs/serial for external peripherals, 3 of which are available by default
|
||||
1x I2C bus for external peripherals
|
||||
USB-C port
|
||||
All UARTs support hardware inversion
|
||||
Onboard ExpressLRS radio tranceiver for control and/or telemetry data.
|
||||
Dimensions
|
||||
Size: 37.5 x 37.5mm
|
||||
Weight: 8g
|
||||
|
||||
## Pinout
|
||||
|
||||
![Anyleaf H7 pinout, bottom](anyleaf_h7_diagram_bottom.jpg)
|
||||
![Anyleaf H7 connectors, top](anyleaf_h7_diagram_top.jpg)
|
||||
|
||||
Pins and connector values are labeled on the flight controller PCB, with the following exceptions:
|
||||
- The onboard ELRS tranceiver is connected to pins PA2 (FC Tx) and PA3 (FC Rx), on UART2.
|
||||
- ESC telemetry is connected to UART3 Rx (PD9)
|
||||
- OSD HDL (DJI hand controller interop) is connected to UART1 Rx (PB7)
|
||||
|
||||
## UART Mapping
|
||||
All UARTs are DMA capable
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (External pads, and RX1 on DJI connector SBUS pin; defaulted to MAVLINK2)
|
||||
- SERIAL2 -> UART2 (DJI Connector telemetry; defaulted to DisplayPort)
|
||||
- SERIAL3 -> UART3 (ESC connector telemetry pin, or external pad; defaulted to ESC telemetry)
|
||||
- SERIAL4 -> USART4 (External pads; GPS protocol by default)
|
||||
- SERIAL5 -> UART7 (Onboard ELRS receiver only, RCIN protocol)
|
||||
- SERIAL6 -> UART8 (USER, External pads)
|
||||
|
||||
## Can FD port
|
||||
|
||||
This flight controller includes a 4-pin DroneCAN standard CAN port. It's capable of 64-byte frames,
|
||||
and up to 5Mbps data rates. It's useful for connecting GPS devices, compasses, power monitoring, sensors, motors, servos, and other CAN peripherals.
|
||||
|
||||
## RC Input
|
||||
|
||||
This flight controller includes a 2.4Ghz ExpressLRS transceiver, capable of receiving control input, and transmitting or receiving MavLink telemetry. To enable all ELRS features, either RC5 channel should be setup as an ARM switch (there are several RC5_OPTIONS that can do this) or by mapping the transmitter's Channel 5 to reflect ARM status from telemetry. See: https://youtu.be/YO2yA1fmZBs for an axample.
|
||||
|
||||
SBUS on the DJI connector may be used if SERIAL5_PROTOCOL is changed to 0 and SERIAL1_PROTOCOL is changed to 23 for RC input.
|
||||
|
||||
## OSD Support
|
||||
|
||||
This flight controller has an MSP-DisplayPort output on a 6-pin DJI-compatible JST SH port re-configured.
|
||||
|
||||
## Motor Output
|
||||
|
||||
Motor 1-8 is capable of bidirectional DSHOT and PWM.
|
||||
|
||||
All outputs in the motor groups below must be either PWM or DShot:
|
||||
Motors 1-4 Group1
|
||||
Motors 5-6 Group2
|
||||
Motors 7-8 Group3
|
||||
|
||||
## Magnetometer
|
||||
|
||||
This flight controller does not have a built-in magnetometer, but you can attach an external one using the CAN connector, or the I2C pads on the bottom.
|
||||
|
||||
## Loading Firmware
|
||||
Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “Anyleaf H7”.
|
||||
|
||||
Initial firmware load can be done with DFU by plugging in USB with the
|
||||
boot button pressed. Then you should load the "AnyleafH7_bl.hex"
|
||||
firmware, using your favourite DFU loading tool.
|
||||
|
||||
Subsequently, you can update firmware using Mission Planner or QGroundControl.
|
||||
|
||||
|
Binary file not shown.
After Width: | Height: | Size: 350 KiB |
Binary file not shown.
After Width: | Height: | Size: 307 KiB |
|
@ -0,0 +1,20 @@
|
|||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1146
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define AP_CAN_SCLAN_ENABLED 1
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN
|
|
@ -0,0 +1,23 @@
|
|||
# CAN
|
||||
CAN_P1_DRIVER 1 # Enables the use of CAN
|
||||
|
||||
# Onboard ELRS
|
||||
SERIAL5_PROTOCOL 23 # RCIN
|
||||
RC_OPTIONS 8192 # Set 420k baud for ELRS
|
||||
# RC2_REVERSED 1 # Prevent inverse pitch controls
|
||||
RSSI_TYPE 3 # RC provided RSSI
|
||||
# ARMING_RUDDER 0 # Disable rudder arming
|
||||
|
||||
|
||||
# Onboard OSD
|
||||
OSD_TYPE 5 # MSP
|
||||
SERIAL2_PROTOCOL 42 # DisplayPort
|
||||
OSD_CELL_COUNT 0 # auto based on voltage at start
|
||||
|
||||
|
||||
# ESC telemetry
|
||||
SERIAL3_PROTOCOL 16 # ESC telemetry
|
||||
|
||||
|
||||
# Remove default serial protocols; set to None.
|
||||
SERIAL6_PROTOCOL -1
|
|
@ -0,0 +1,16 @@
|
|||
include common.inc
|
||||
|
||||
|
||||
# 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
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PC4 IMU1_CS CS
|
||||
PE11 FLASH_SPI_CS CS
|
|
@ -0,0 +1,118 @@
|
|||
include common.inc
|
||||
|
||||
env OPTIMIZE -Os
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# use last 2 pages for flash storage
|
||||
# H743 has 16 pages of 128k each
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
STORAGE_FLASH_PAGE 14
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 12
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# SPI1 for IMU1 (ICM42688)
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
PC4 IMU1_CS CS
|
||||
|
||||
# SPI2 for flash (W25Q64JVZPIQ (64Mbit))
|
||||
PA9 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
PE11 FLASH_CS CS
|
||||
|
||||
# two I2C buses
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# I2C1
|
||||
PB8 I2C1_SCL I2C1 PULLUP
|
||||
PB9 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
# I2C2
|
||||
PB10 I2C2_SCL I2C2 PULLUP
|
||||
PB11 I2C2_SDA I2C2 PULLUP
|
||||
|
||||
# ADC
|
||||
PA4 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA0 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
define HAL_BATT_MONITOR_DEFAULT 4 # Analog voltage and current
|
||||
define HAL_BATT_VOLT_PIN 18 # ADC channel
|
||||
define HAL_BATT_CURR_PIN 16
|
||||
define HAL_BATT_VOLT_SCALE 11.44 # Nominally a 11x divider. 11.44 is based on experimenting.
|
||||
define HAL_BATT_CURR_SCALE 40.0 # This depends on the ESC's V/mA output ratio.
|
||||
|
||||
# LED
|
||||
PC13 LED0 OUTPUT LOW GPIO(90) # Amber; System status.
|
||||
PC0 LED1 OUTPUT LOW GPIO(91) # Not connected; GPS Status. (Required, or the system status LED won't work.)
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 91
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# order of UARTs (and USB) OTG2 may be required for SLCAN.
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 UART8 #OTG2
|
||||
|
||||
# USART1
|
||||
PB6 USART1_TX USART1
|
||||
PB7 USART1_RX USART1
|
||||
|
||||
# USART2 (MSP Displayport OSD)
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
|
||||
# USART3
|
||||
PD8 USART3_TX USART3
|
||||
PD9 USART3_RX USART3
|
||||
|
||||
# UART4
|
||||
PC10 UART4_TX UART4
|
||||
PC11 UART4_RX UART4
|
||||
|
||||
# UART7 (ELRS receiver)
|
||||
PB4 UART7_TX UART7
|
||||
PB3 UART7_RX UART7
|
||||
|
||||
PE1 UART8_TX UART8
|
||||
PE0 UART8_RX UART8
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
# Motors
|
||||
PC6 TIM3_CH1 TIM3 PWM(1) GPIO(50) BIDIR
|
||||
PC7 TIM3_CH2 TIM3 PWM(2) GPIO(51)
|
||||
PC8 TIM3_CH3 TIM3 PWM(3) GPIO(52) BIDIR
|
||||
PC9 TIM3_CH4 TIM3 PWM(4) GPIO(53)
|
||||
PE5 TIM15_CH1 TIM15 PWM(5) GPIO(54) BIDIR
|
||||
PE6 TIM15_CH2 TIM15 PWM(6) GPIO(55)
|
||||
PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR
|
||||
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
||||
|
||||
# Beeper
|
||||
PE9 TIM1_CH1 TIM1 GPIO(58) ALARM
|
||||
|
||||
DMA_PRIORITY S*
|
||||
|
||||
DMA_NOSHARE SPI1* TIM3* TIM15* TIM1*
|
||||
|
||||
# SPI devices
|
||||
SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ
|
||||
SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ
|
||||
|
||||
# IMU
|
||||
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# DPS310 integrated on I2C2 bus, multiple possible choices for external barometer
|
||||
BARO DPS310 I2C:0:0x77
|
||||
|
||||
# setup for OSD
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 5 # MSP Displayport
|
Loading…
Reference in New Issue