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
Binary file added Tools/bootloaders/DAKEFPVH743_SLIM_bl.bin
Binary file not shown.
1,168 changes: 1,168 additions & 0 deletions Tools/bootloaders/DAKEFPVH743_SLIM_bl.hex

Large diffs are not rendered by default.

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.
115 changes: 115 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/DAKEFPVH743_SLIM/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
# DAKEFPV H743 SLIM Flight Controller

The DAKEFPV H743 SLIM is a flight controller produced by [DAKEFPV](https://www.dakefpv.com/).

## Features

- MCU - STM32H743 32-bit processor running at 480 MHz
- IMU - Dual ICM42688
- Barometer - SPL06
- OSD - AT7456E
- 8x UARTs
- 1x CAN port
- 13x PWM Outputs (12 Motor Output, 1 LED)
- Battery input voltage: 4S-12S
- BEC 3.3V 0.5A
- BEC 5V 3A
- Dual switchable camera inputs

## Pinout

![DAKEFPV H743 SLIM Board Top](DAKEFPVH743_SLIM_Top.png "DAKEFPV H743 SLIM Top")
![DAKEFPV H743 SLIM Board Bottom](DAKEFPVH743_SLIM_Bottom.png "DAKEFPV H743 SLIM Bottom")
## 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 -> UART1 (GPS) DMA capable
- SERIAL2 -> UART2 (MAVLink2)
- SERIAL3 -> UART3 (ESC Telemetry)
- SERIAL4 -> UART4 (DisplayPort) DMA capable
- SERIAL5 -> UART5 (RCin) RX DMA capable
- SERIAL6 -> UART6 (User) DMA capable
- SERIAL7 -> UART7 (User) DMA Capable
- SERIAL8 -> UART8 (User)

## RC Input

RC input is configured by default via the USART5 RX input. It supports all unidirectional serial RC protocols except PPM . The SBUS pin is inverted and tied to R5 for SBUS support.

* FPort requires an external bi-directional inverter attached to T5 and :ref:`SERIAL5_OPTIONS<SERIAL5_OPTIONS>` set to 4 (half-duplex). See :ref:`common-FPort-receivers`.
* CRSF/ELRS uses RX5/TX5.
* SRXL2 requires a connection to T5 and automatically provides telemetry. Set :ref:`SERIAL5_OPTIONS<SERIAL5_OPTIONS>` to "4".

## FrSky Telemetry

FrSky Telemetry is supported using an unused UART, such as the TX2 pin (UART2 transmit).
You need to set the following parameters to enable support for FrSky S.PORT:

- :ref:`SERIAL2_PROTOCOL<SERIAL2_PROTOCOL>` 10
- :ref:`SERIAL2_OPTIONS<SERIAL2_OPTIONS>` 7

## PWM Output

The DAKEFPV H743 SLIM supports up to 14 outputs. Motor outputs M1 to M8 are available on separate pads, along with independent pads for S1-4 and LED for LED strips and other PWM outputs. M1-8, S1, and S4 support bidirectional DShot, and the LED outputs support serial LEDs or DShot.

The PWM is in 5 groups:

- PWM 1-4 in group1
- PWM 5-8 in group2
- PWM 9-12 in group3
- PWM 13 in group4 (CAMERA_CONTROL)
- PWM 14(LED) in group5 (set as Serial LED output function by default)

The outputs are in 5 groups:

- M 1-4 in group1
- M 5,8 in group2
- S 9,12 in group3
- OSD in group4
- LED in group5

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 built-in voltage sensor and external current sensor input. The current
sensor can read up to 130 Amps. The voltage sensor can handle up to 12S LiPo batteries.

The correct battery setting parameters are:

- :ref:`BATT_MONITOR<BATT_MONITOR>` 4
- :ref:`BATT_VOLT_PIN<BATT_VOLT_PIN__AP_BattMonitor_Analog>` 11
- :ref:`BATT_CURR_PIN<BATT_CURR_PIN__AP_BattMonitor_Analog>` 10
- :ref:`BATT_VOLT_MULT<BATT_VOLT_MULT__AP_BattMonitor_Analog>` 16.0
- :ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT__AP_BattMonitor_Analog>` 83.3

## RSSI

- ADC Pin 8 -> Analog RSSI voltage monitoring. Set :ref:`RSSI_TYPE<RSSI_TYPE>` = 1 and :ref:`RSSI_ANA_PIN<RSSI_ANA_PIN>` = 8. For RSSI embedded in digital RC protocols like CRSF, set :ref:`RSSI_TYPE<RSSI_TYPE>` = 3

## Compass

The DAKEFPV H743 SLIM does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.

## Camera control

GPIO 81 controls the camera output to the connectors marked "CAM1" and "CAM2". Setting this GPIO low switches the video output from CAM1 to CAM2. By default RELAY1 is configured to control this pin and sets the GPIO high.

## OSD Support
The DAKEFPVH743_SLIM has an onboard OSD using a MAX7456 chip and is enabled by default. The CAM1/2 and VTX pins provide connections for using the internal OSD. Simultaneous DisplayPort OSD is also possible and is configured by default.
The HD VTX connector can have RX4 replaced by the analog VTX signal if that connector is used for analog VTX connection by using the DJI/VTX jumper pads.

## Loading Firmware
Firmware for these boards can be found `here <https://firmware.ardupilot.org>`__ in sub-folders labeled "DAKEFPVH743_SLIM".
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.
5 changes: 5 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/DAKEFPVH743_SLIM/defaults.parm
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# setup for LEDs on chan14
SERVO14_FUNCTION 120

# enable displayport
OSD_TYPE2 5
44 changes: 44 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/DAKEFPVH743_SLIM/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@

# hw definition file for processing by chibios_hwdef.py
# for DAKEFPVH743_SLIM 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_DAKEFPVH743_SLIM

# 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
PA15 FLASH1_CS CS
PB12 OSD1_CS CS
PC9 GYRO1_CS CS
PB1 GYRO2_CS CS

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

# hw definition file for processing by chibios_hwdef.py
# for DAKEFPVH743 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_DAKEFPVH743_SLIM

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

MCU_CLOCKRATE_MHZ 480

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 (IMU1)
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2 (OSD)
PB13 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2

# SPI3 (External)
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3

# SPI4 (IMU2)
PE12 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4

# Chip select pins
PB12 OSD1_CS CS
PC9 GYRO1_CS CS
PB1 GYRO2_CS CS

# external CS pins
PA15 EXT_CS1 CS
PD3 EXT_CS2 CS

# Beeper
PE10 BUZZER OUTPUT GPIO(80) LOW PULLDOWN
define HAL_BUZZER_PIN 80

# SERIAL ports
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# USART1 (GPS1)
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_GPS

# USART2
PD5 USART2_TX USART2 NODMA
PD6 USART2_RX USART2 NODMA

# USART3
PD8 USART3_TX USART3 NODMA
PD9 USART3_RX USART3 NODMA
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_ESCTelemetry

# UART4
PB8 UART4_RX UART4
PB9 UART4_TX UART4
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MSP_DisplayPort

# UART5 (RX)
PB5 UART5_RX UART5
PB6 UART5_TX UART5
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_RCIN

# USART6
PC6 USART6_TX USART6
PC7 USART6_RX USART6

# UART7
PE7 UART7_RX UART7
PE8 UART7_TX UART7

# UART8
PE0 UART8_RX UART8 NODMA
PE1 UART8_TX UART8 NODMA

# CAN bus
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PD2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)

# I2C ports
I2C_ORDER I2C2
# I2C2
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2

BARO SPL06 I2C:0:0x76
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_SPL06_ENABLED 1

# ADC ports

# ADC1
PC0 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 10
define HAL_BATT_CURR_SCALE 83.3
PA4 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_VOLT_SCALE 16.0
PC5 RSSI_ADC ADC1
define BOARD_RSSI_ANA_PIN 8
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
PA0 TIM2_CH1 TIM2 PWM(5) GPIO(54) BIDIR # M5
PA1 TIM2_CH2 TIM2 PWM(6) GPIO(55) # M6
PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR # M7
PA3 TIM2_CH4 TIM2 PWM(8) GPIO(57) # M8
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) # S1
PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) # S2
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) NODMA # S3
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You are not saving anything here because you need a single DMA channel for the whole of timer 4, so I would just remove these two NODMA clauses

PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) NODMA # S4
PC8 TIM8_CH3 TIM8 PWM(13) GPIO(62) NODMA # labelled OSD
PB0 TIM3_CH3 TIM3 PWM(14) GPIO(63) # LED

# RELAYS
# Camera switch control - should be high at startup to ensure Camera 1 selected
PE2 CAMERA_SWITCH OUTPUT GPIO(81) LOW
define RELAY1_PIN_DEFAULT 81

# VTX power control
PE3 PINIO2 OUTPUT GPIO(82) LOW
define RELAY2_PIN_DEFAULT 82

# Bluetooth RF switch
PE4 PINIO3 OUTPUT GPIO(83) LOW

# LEDs

PD10 LED0 OUTPUT LOW GPIO(90)
define HAL_GPIO_A_LED_PIN 90

PD11 LED1 OUTPUT LOW GPIO(91)
define HAL_GPIO_B_LED_PIN 91

PA8 LED2 OUTPUT LOW GPIO(92)
define HAL_GPIO_C_LED_PIN 92

# microSD support
PC1 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2

# enable FAT filesystem support (needs a microSD defined via SDIO)
define HAL_OS_FATFS_IO 1

# External
SPIDEV EXT_SPI SPI3 DEVID1 EXT_CS1 MODE3 104*MHZ 104*MHZ

# OSD setup
SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ

define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

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

IMU Invensensev3 SPI:imu1 ROTATION_YAW_180
IMU Invensensev3 SPI:imu2 ROTATION_YAW_270

DMA_NOSHARE TIM1_UP TIM2_UP SPI1* SPI4*
DMA_PRIORITY TIM1_UP TIM2_UP SPI1* SPI4*

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
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
# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12
define DEFAULT_NTF_LED_TYPES 455
Loading