Skip to content

MicoAir743-Lite

main (planned for: PX4 v1.17)

WARNING

PX4 does not manufacture this (or any) autopilot. Contact the manufacturer for hardware support or compliance issues.

MicoAir743-Lite is an ultra-high performance H743 flight controller with an unbeatable price, featuring the ICM45686 IMU sensor and integrated Bluetooth telemetry.

MicoAir743-Lite Front View

Equipped with a high-performance H7 processor, the MicoAir743-Lite features a compact form factor with SH1.0 connectors (which are more suitable than Pixhawk-standard GH1.25 for this board size). When paired with with Bluetooth telemetry, the board can be debugged with a phone or PC.

INFO

This flight controller is manufacturer supported.

MicoAir743-Lite (v1.1)

MicoAir743-Lite Back View

Quick Summary

Processors & Sensors

  • FMU Processor: STM32H743
    • 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
  • On-board sensors
    • Accel/Gyro: ICM-45686 (with BalancedGyro™ Technology)
    • Barometer: SPA06
  • On-board Bluetooth Telemetry
    • Connected to UART8 internally, baudrate 115200
    • Connecting to QGC (PC or Android phone) via Bluetooth
  • Other Characteristics:
    • Operating & storage temperature: -20 ~ 85°c

Interfaces

  • 8 UART (TELEM / GPS / RC)
  • 14 PWM outputs (10 supports DShot)
  • Support multiple RC inputs (SBUS / CRSF / DSM)
  • 1 GPS port
  • 1 I2C port
  • 2 ADC port2 (VBAT, Current)
  • 1 DJI O3/O4 VTX connector
  • 1 MicroSD Card Slot
  • 1 USB Type-C

Electrical data

  • VBAT Input:
    • 2~6S (6~27V)
  • USB Power Input:
    • 4.75~5.25V
  • BEC Output:
    • 5V 2A (for controller, receiver, GPS, optical flow or other devices)
    • 9V 2A (for video transmitter, camera)

Mechanical data

  • Mounting: 30.5 x 30.5mm, Φ4mm
  • Dimensions: 36 x 36 x 8 mm
  • Weight: 10g

MicoAir743-Lite Size

Where to Buy

Order from MicoAir Tech Store.

Pinouts

Pinouts definition can be found in the MicoAir743-Lite_pinout.xlsx file.

Serial Port Mapping

UARTDevicePort
USART1/dev/ttyS0TELEM1
USART2/dev/ttyS1GPS2
USART3/dev/ttyS2GPS1
UART4/dev/ttyS3TELEM2
UART5/dev/ttyS4TELEM3
USART6/dev/ttyS5RC
UART7/dev/ttyS6URT6
UART8/dev/ttyS7TELEM4

Interfaces Diagram

::: note All the connectors used on the board are SH1.0 :::

MicoAir743-Lite Interface Diagram

Sample Wiring Diagram

MicoAir743-Lite Wiring Diagram

Building Firmware

To build PX4 for this target:

sh
make micoair_h743-lite_default

Installing PX4 Firmware

The firmware can be installed in any of the normal ways:

  • Build and upload the source

    sh
    make micoair_h743-lite_default upload
  • Load the firmware using QGroundControl. You can use either pre-built firmware or your own custom firmware.

    INFO

    At time of writing the only pre-built software is PX4 main (see Installing PX4 Main, Beta or Custom Firmware). Release builds will be supported for PX4 v1.17 and later.

Radio Control

A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).

The RC port is connected to the FMU and you can attach a receiver that uses the protocols DSM, SBUS, CSRF, GHST, or other protocol listed in Radio Control modules. You will need to enable the protocol by setting the corresponding parameter RC_xxxx_PRT_CFG, such as RC_CRSF_PRT_CFG for a CRSF receiver.

Supported Platforms / Airframes

Any multicopter / airplane / rover or boat that can be controlled with normal RC servos or Futaba S-Bus servos. The complete set of supported configurations can be seen in the Airframes Reference.

Peripherals

Further info