DAKEFPV H743/ H743 Pro

The DAKEFPV H743/H743 Pro are flight controllers produced by DAKEFPV.

Features

  • MCU - STM32H743 32-bit processor running at 480 MHz

  • IMU - Dual ICM42688

  • Barometer - SPL06

  • OSD - AT7456E

  • Onboard Flash: 16MByte

  • 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

  • BEC 12V 3A for video, gpio controlled

  • Dual switchable camera inputs

Pinout

../_images/DAKEFPVH743Pro_Top.png ../_images/DAKEFPVH743Pro_Bottom.png

DAKEFPV H743 Pro Wiring Diagram

../_images/DAKEFPVH743Pro_WiringDiagramTop.png ../_images/DAKEFPVH743Pro_WiringDiagramBottom.png

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.

PWM Output

The DAKEFPV H743/Pro supports up to 14 outputs. The pads for motor output M1 to M8 are provided on both the motor connectors and on separate pads, plus S1-4, LED on separate pads for LED strip and other PWM outputs. M1-8, S1, and S2 support B-Directional DShot. OSD, S3-4 support only PWM. The LED output supports serial LED or DShot.

For the H743 Pro the outputs are in 7 groups: * M 1-4 in group1 * M 5,6 in group2 * M 7,8 in group3 * S 1,2 in group4 * S 3,4 in group5 * OSD in group 6 * LED in group 7

For the H743 the outputs are in 6 groups: * M 1-4 in group1 * M 5-8 in group2 * S 1,2 in group3 * S 3,4 in group4 * OSD in group 5 * LED in group 6

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: * BATT_MONITOR 4 * BATT_VOLT_PIN 11 * BATT_CURR_PIN 10 * BATT_VOLT_MULT 16.0 * BATT_AMP_PERVLT 83.3

RSSI

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

Compass

The DAKEFPV H743/Pro does not have a built-in 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.

VTX Power Control

GPIO 82 controls the VTX power output to the connectors marked “12V”. Setting this GPIO low switches the video power off. By default RELAY2 is configured to control this pin and sets the GPIO high.

OSD Support

The DAKEFPVH743/Pro 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 the H743 PRO version can be found here in sub-folders labeled “DAKEFPVH743Pro”.

Firmware for the H743 version can be found here in sub-folders labeled “DAKEFPVH743”.

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.