Keyboard shortcuts

Press or to navigate between chapters

Press S or / to search in the book

Press ? to show this help

Press Esc to hide this help

KiwiH743 12S Flight Controller

KiwiH743.jpg

Buy Online Buy Online

Overview

The KiwiH743 is a high-performance flight controller based on the STM32H743 MCU, designed for advanced UAV applications. It combines powerful processing, flexible connectivity, and rich sensor support, optimized for ArduPilot firmware.

It is the next generation of the KiwiF405 family, offering 2MB flash, 480 MHz CPU clock, extended UART/SPI/I2C buses, and support for dual IMUs, barometer, and OSD integration.

Premium features: GPS-less takeoff, IRC Tramp VTX control, VRX integration (TBS Fusion, Skyzone Steadyview).


Firmware

Features

  • Dual IMUs: ICM-42688P + ICM-45686 with EKF3 dual-source fusion
  • BMP388 barometer, external compass support (I²C probing)
  • Integrated OSD (MAX7456-compatible via SPI4)
  • 14 PWM outputs (8 motors + 6 servos), DShot bidirectional on M1–M4
  • 7 hardware UARTs + 2 USB ports (OTG1 MAVLink, OTG2 HiSpeed serial)
  • 16 MB DataFlash + external SD card slot
  • Visual odometry, external AHRS, GPS moving baseline support
  • Gyro FFT for vibration analysis
  • INS temperature calibration
  • Guided (NoGPS), FlowHold, OpticalFlow modes

Technical Specifications

  • MCU: STM32H743VIT6 (ARM Cortex-M7, 480 MHz, 2048 KB flash)
  • Crystal: 16 MHz external oscillator
  • IMU1: ICM-42688P (SPI6, rotation YAW_180)
  • IMU2: ICM-45686 (SPI2, rotation YAW_270)
  • Barometer: BMP388 (I2C2, address 0x76)
  • OSD: MAX7456-compatible (SPI4)
  • DataFlash: 16 MB (SPI3)
  • LED: PE4 (active low)
  • Dimensions: 36×36 mm, mounting 30.5×30.5 mm

Serial Ports

PortArduPilotDefault ProtocolPinsNotes
USBSERIAL0MAVLinkPA11, PA12OTG1 Full Speed
USART1SERIAL1ESC Telemetry (115200)PA10RX only
USART2SERIAL2SmartAudio (115200)PD5, PD6NODMA
USART3SERIAL3PD8, PD9
UART4SERIAL4PD1, PD0
UART5SERIAL5MAVLink1 (57600)PB6, PD2NODMA
UART7SERIAL7MAVLink2PE8, PE7RTS: PE9, CTS: PE10
UART8SERIAL8RC InputPE1, PE0SBUS/DSM
USB HSSERIAL9OTG2 HiSpeed

RC input: SBUS/DSM on PE11.


GPIOs, Relays, and AUX

Dedicated GPIO Pads

PadPinGPIODefaultArduPilot Relay Config
CAM SWPA8100RELAY1RELAY1_PIN=100 (hwdef default)
RELAY1PD4101Output LOWRELAY2_PIN=101, RELAY2_FUNC=1
RELAY2PB7102Output LOWRELAY3_PIN=102, RELAY3_FUNC=1
LEDPE490Status LED

Note: RELAY1_PIN defaults to GPIO 100 (Camera Switch pad, PA8), not the pad labeled “RELAY1” (PD4, GPIO 101). This is set in the hwdef. Adjust if your wiring differs.

PWM Outputs

OutputPinGPIOTimerFunctionDShot Bidir
PWM1PC650TIM3_CH1Motor 1Yes
PWM2PC751TIM3_CH2Motor 2Yes
PWM3PC852TIM3_CH3Motor 3Yes
PWM4PC953TIM3_CH4Motor 4Yes
PWM5PD1254TIM4_CH1Motor 5No
PWM6PD1355TIM4_CH2Motor 6No
PWM7PD1456TIM4_CH3Motor 7No
PWM8PD1557TIM4_CH4Motor 8No
PWM9PA058TIM5_CH1Servo 1No
PWM10PA159TIM5_CH2Servo 2No
PWM11PA260TIM5_CH3Servo 3No
PWM12PA361TIM5_CH4Servo 4No
PWM13PE1362TIM1_CH3Servo 5No
PWM14PB863TIM16_CH1Servo 6No

PWM pins can be reassigned to GPIO via SERVOn_FUNCTION=0 + RELAYn_PIN=<gpio>.

Spare ADC

PinFunction
PC1SPARE2_ADC1 (analog input only)

Relay Usage

MAVProxy:

param set RELAY2_PIN 101
param set RELAY2_FUNC 1
relay set 0 1    # RELAY1 ON (CAM SW pad HIGH)
relay set 0 0    # RELAY1 OFF
relay set 1 1    # RELAY2 ON (RELAY1 pad HIGH)

Mission waypoint: DO_SET_RELAY — relay number 0-based (0=RELAY1), setting 1=ON / 0=OFF.

Lua:

relay:toggle(0)  -- toggle RELAY1 (CAM SW)
relay:on(1)      -- RELAY2 ON (RELAY1 pad)
relay:off(1)     -- RELAY2 OFF

All GPIO pads default LOW on boot. Use RELAY_DEFAULT params to set initial state.


Power Monitoring

  • Battery Voltage: PC5 (ADC1 IN8)
  • Battery Current: PB1 (ADC1 IN5)
  • Default monitor type: Analog

Sensor Calibration

ParameterArduPilotBetaflight
Voltage scaleBATT_VOLT_MULT = 21.0voltage_meter_scale = 210
Current scaleBATT_AMP_PERVLT = 142.9current_meter_scale = 100

Battery Voltage Thresholds (ArduPilot)

Parameter6S8S12S
Full charge25.2 V33.6 V50.4 V
BATT_ARM_VOLT22.229.644.4
BATT_LOW_VOLT21.028.042.0
BATT_CRT_VOLT19.826.439.6

Buses

SPI

BusCLKMISOMOSIUsage
SPI1PA5PA6PA7SD Card (CS: PA4)
SPI2PB13PB14PB15IMU2 ICM-45686 (CS: PD10)
SPI3PC10PC11PC12DataFlash (CS: PD3)
SPI4PE2PE5PE6OSD MAX7456 (CS: PE3)
SPI6PB3PB4PB5IMU1 ICM-42688P (CS: PC13)

I2C

BusSCLSDADevices
I2C2PB10PB11BMP388 (0x76), external compass

Default Frame and Modes

  • Default frame: Quadcopter X (FRAME_TYPE=3, BetaFlight-X motor order)
  • Motor protocol: DShot (MOT_PWM_TYPE=5)
  • BLHeli passthrough: enabled (SERVO_BLH_AUTO=1, mask=15)
  • Flight mode channel: CH8
  • VTX: enabled, band 6, channel 4

Camera Gimbal Support

KiwiH743 supports camera gimbals out of the box — both servo-based and MAVLink protocol gimbals (CADDX GM3 V2 and compatible).

Wire gimbal UART to any free serial port (gimbal TX → FC RX, gimbal RX → FC TX, GND).

ParamValueNotes
SERIALx_PROTOCOL2MAVLink2
SERIALx_BAUD115115200 bps
MNT1_TYPE6Gremsy (reboot after setting)
MNT1_PITCH_MIN-120GM3 V2 spec: ±120°
MNT1_PITCH_MAX120
MNT1_YAW_MIN-160GM3 V2 spec: ±160°
MNT1_YAW_MAX160
MNT1_RC_RATE60deg/s for rate control, 0 for angle
RC Control

Assign RC channels to control gimbal axes:

ParamValueNotes
RC6_OPTION213Mount1 Pitch
RC7_OPTION214Mount1 Yaw
RC8_OPTION212Mount1 Roll (3-axis gimbals only)

Example: with MNT1_RC_RATE=60, moving the RC6 stick deflects pitch at 60°/s. Set MNT1_RC_RATE=0 for direct angle control (stick position = gimbal angle).

Gimbal firmware must be V2.0 or higher.

Servo Gimbal

Connect pitch/yaw servos to any Servo PWM outputs (PWM9–PWM14).

ParamValueNotes
MNT1_TYPE1Servo
SERVOx_FUNCTION6Mount1 Pitch (assign to desired output)
SERVOx_FUNCTION8Mount1 Yaw (assign to desired output)
MNT1_PITCH_MIN-90
MNT1_PITCH_MAX90
MNT1_YAW_MIN-170
MNT1_YAW_MAX170
MNT1_RC_RATE60deg/s for rate control, 0 for angle

Pinout Reference

ESC Pins

1 - ESC Telemetry
2 - ESC Current
3 - Motor4
4 - Motor3
5 - Motor2
6 - Motor1
7 - VBAT
8 - GND