Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -324,6 +324,7 @@ AP_HW_X-MAV-AP-H743R1 1203
AP_HW_ORQAH7QUADCORE 1204
AP_HW_ESP32_PERIPH 1205
AP_HW_ESP32S3_PERIPH 1206
AP_HW_AIRBRAIN_H743 1207

AP_HW_CSKY-PMU 1212

Expand Down
Binary file added Tools/bootloaders/AIRBRAINH743_bl.bin
Binary file not shown.
1,156 changes: 1,156 additions & 0 deletions Tools/bootloaders/AIRBRAINH743_bl.hex

Large diffs are not rendered by default.

95 changes: 95 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/AIRBRAINH743/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,95 @@

# AIRBRAINH743 Flight Controller

The AIRBRAINH743 is a flight controller designed and produced by [Gear Up](https://takeyourgear.com/).

## Features

- MCU - STM32H743xx 32-bit processor running at 480 MHz
- IMU - Invensense ICM-42688-P
- Barometer - DPS368
- Magnetometer - LIS2MDL
- 128 Mbytes flash-based logging
- Battery input voltage: 3S-10S
- BEC 5V 2A
- BEC 10V 2.5A
- 7x UARTs
- 9x PWM Outputs (8 Motor Output, 1 LED)

## Pinout

![AIRBRAINH743 Board Top](pinoutTop.png "AIRBRAINH743 Top")
![AIRBRAINH743 Board Bottom](pinoutBottom.png "AIRBRAINH743 Bottom")

## UART Mapping

The UARTs are marked RX and TX in the above pinouts. The RX pin is the
receive pin. The TX pin is the transmit pin .

- SERIAL0 -> USB (MAVLink2)
- SERIAL1 -> USART1 (None)
- SERIAL2 -> USART2 (RCIN, DMA-enabled)
- SERIAL3 -> USART3 (MSP DisplayPort, DMA-enabled)
- SERIAL4 -> UART4 (GPS, DMA-enabled)
- SERIAL5 -> UART5 (None, DMA-enabled)
- SERIAL7 -> UART7 (ESCTelemetry)
- SERIAL8 -> UART8 (GPS2, DMA-enabled)

## RC Input

The default RC input is configured on USART2. RC could be applied instead to a different UART port, and set
the protocol to receive RC data ``SERIALn_PROTOCOL`` = 23 and change :ref:`SERIAL2 _PROTOCOL <SERIAL2 _PROTOCOL>`
to something other than '23'. For rc protocols other than unidirectional, the USART2_TX pin will need to be used:

- FPort would require :ref:`SERIAL2_OPTIONS<SERIAL2_OPTIONS>` be set to "15".
- CRSF would require :ref:`SERIAL2_OPTIONS<SERIAL2_OPTIONS>` be set to "0".
- SRXL2 would require :ref:`SERIAL2_OPTIONS<SERIAL2_OPTIONS>` be set to "4" and connects only the TX pin.

The HD VTX connector contains UART5 RX for SBUS. To use this connector for SBUS set :ref:`SERIAL2 _PROTOCOL <SERIAL2 _PROTOCOL>`
to something other than '23' and set :ref:`SERIAL5 _PROTOCOL <SERIAL5 _PROTOCOL>` to '23'

## PWM Output

The AIRBRAINH743 supports up to 9 PWM or DShot outputs. The pads for motor output
M1 to M9 are provided on both the motor connectors and on separate pads, plus
separate pads for LED strip and other PWM outputs.

The PWM is in 4 groups:

- PWM 1-4 in group1
- PWM 5-6 in group2
- PWM 7-8 in group3
- PWM 9 in group4 (defaulted to Serial LED protocol)

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. Channels 1-8 support bi-directional dshot.

## Battery Monitoring

The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input.
The voltage sensor can handle up to 6S LiPo batteries.

The default battery parameters are:

- :ref:`BATT_MONITOR<BATT_MONITOR>` = 4
- :ref:`BATT_VOLT_PIN<BATT_VOLT_PIN__AP_BattMonitor_Analog>` = 4
- :ref:`BATT_CURR_PIN<BATT_CURR_PIN__AP_BattMonitor_Analog>` = 8 (CURRENT pin)
- :ref:`BATT_VOLT_MULT<BATT_VOLT_MULT__AP_BattMonitor_Analog>` = 15.0
- :ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT__AP_BattMonitor_Analog>` = 101.0

## Compass

The AIRBRAINH743 has builtin compass. You can also attach an external compass using I2C on the SDA and SCL pads.

## Loading Firmware

Firmware for these boards can be found `here <https://firmware.ardupilot.org>`__ in sub-folders labeled "AIRBRAINH743".

Initial firmware load can be done with DFU by plugging in USB with the
bootloader button pressed. Then you should load the "with_bl.hex"
firmware, using your favourite DFU loading tool.

Once the initial firmware is loaded you can update the firmware using
any ArduPilot ground station software. Updates should be done with the
*.apj firmware files.
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/AIRBRAINH743/defaults.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
SERVO9_FUNCTION 120

OSD_TYPE1 5
42 changes: 42 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/AIRBRAINH743/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@

# hw definition file for processing by chibios_hwdef.py
# for AIRBRAINH743 hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32H7xx STM32H743xx

# board ID for firmware load
APJ_BOARD_ID AP_HW_AIRBRAIN_H743

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 2048

# bootloader starts at zero offset
FLASH_RESERVE_START_KB 0

# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 384

# order of UARTs (and USB)
SERIAL_ORDER OTG1

# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN


# Chip select pins
PD4 FLASH1_CS CS
PA3 GYRO1_CS CS

PD11 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
162 changes: 162 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/AIRBRAINH743/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,162 @@

# hw definition file for processing by chibios_hwdef.py
# for AIRBRAINH743 hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32H7xx STM32H743xx

# board ID for firmware load
APJ_BOARD_ID AP_HW_AIRBRAIN_H743

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 2048

# bootloader takes first sector
FLASH_RESERVE_START_KB 384

define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

# ChibiOS system timer
STM32_ST_USE_TIMER 12
define CH_CFG_ST_RESOLUTION 16

# SPI devices

# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2
PB14 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
PD3 SPI2_SCK SPI2

# SPI4 AUX
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PE12 SPI4_SCK SPI4

# Chip select pins
PD4 FLASH1_CS CS
PA3 GYRO1_CS CS

# Beeper
PA15 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80

# SERIAL ports
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 EMPTY UART7 UART8

PD0 VBUS INPUT OPENDRAIN

PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# USART1 - Debug
PA10 USART1_RX USART1 NODMA
PA9 USART1_TX USART1 NODMA
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None

# USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN

# USART3 - DJI
PD8 USART3_TX USART3
PD9 USART3_RX USART3
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort

# UART4
PB8 UART4_RX UART4
PB9 UART4_TX UART4

# UART5 - PX4 companion
PB12 UART5_RX UART5
PB13 UART5_TX UART5

# UART7 - ESC
PE7 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry

# UART8 - GPS
PE0 UART8_RX UART8
PE1 UART8_TX UART8
define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_GPS

# I2C ports
I2C_ORDER I2C1
# I2C1
PB6 I2C1_SCL I2C1 PULLUP
PB7 I2C1_SDA I2C1 PULLUP

# I2C2
#PD12 I2C2_SCL I2C2
#PD13 I2C2_SDA I2C2

# ADC1
PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 4
define HAL_BATT_VOLT_SCALE 15.0
PC5 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 8
define HAL_BATT_CURR_SCALE 101.0
define HAL_BATT_MONITOR_DEFAULT 4

# MOTORS
PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR # M1
PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) # M2
PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR # M3
PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) # M4
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) BIDIR # M5
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55) # M6
PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR # M7
PB11 TIM2_CH4 TIM2 PWM(8) GPIO(57) # M8

# LEDs
define DEFAULT_NTF_LED_TYPES 455
PA2 TIM5_CH3 TIM5 PWM(9) GPIO(58) # M9

PB15 LED0 OUTPUT LOW GPIO(90)
define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90

PD11 LED1 OUTPUT LOW GPIO(91)
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91

PD15 LED2 OUTPUT LOW GPIO(92)
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1

# Dataflash setup
SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ

DATAFLASH littlefs:w25nxx

# Baro
BARO DPS310 I2C:0:0x76

# Compass
COMPASS LIS2MDL I2C:0:0x1E false ROTATION_YAW_270

# IMU setup
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ

IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_90
DMA_NOSHARE TIM1_UP TIM3_UP TIM2_UP SPI1*
DMA_PRIORITY TIM1_UP TIM3_UP TIM2_UP SPI1*

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define AP_COMPASS_PROBING_ENABLED 1
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 3
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading