• Home
    • Copter
    • Plane
    • Rover
    • Blimp
    • Sub
    • AntennaTracker
    • Mission Planner
    • APM Planner 2
    • MAVProxy
    • Companion Computers
    • Developer
  • Downloads
    • Mission Planner
    • APM Planner 2
    • Advanced User Tools
    • Developer Tools
    • Firmware
  • Community
    • Support Forums
    • Facebook
    • Developer Chat (Discord)
    • Developer Voice (Discord)
    • Contact us
    • Getting involved
    • Commercial Support
    • Development Team
    • UAS Training Centers
  • Stores
  • About
    • News
    • History
    • License
    • Trademark
    • Acknowledgments
    • Wiki Editing Guide
    • Partners Program
Plane Logo
  • Introduction
  • AutoPilot Hardware
    • Open hardware
    • Closed hardware
      • Aerotenna Ocpoc-Zynq
      • Airvolute DroneCore
      • AtomRC F405-NAVI
      • Emlid NAVIO2 (Linux)
      • Flywoo F745 AIO BL_32/ Nano
      • Foxeer Reaper F745-AIO V2
      • Furious FPV F-35 Lightning and Wing FC-10
      • Holybro Kakute F4*
      • Holybro Kakute F4 Mini*
      • Holybro Kakute F7 AIO*
      • Holybro Kakute F7 Mini* (only V1 and V2 are compatible)
      • Holybro Kakute H7 V2
      • Holybro Kakute H7 Mini v1.3
      • Holybro Pixhawk 4 Mini
      • Holybro Pixhawk5X
      • Horizon31 PixC4-Jetson
      • IFlight Beast F7 45A AIO
      • IFlight BeastH7 AIO
      • Mamba F405 MK2*
      • Mamba Basic F405 mk3
      • Mamba H743 v4
      • MakeFlyEasy PixSurveyA1
      • MakeFlyEasy PixPilot-V6
      • Mateksys F405 TE Family
      • Mateksys H743-Wing/MINI/SLIM/WLITE
      • ModalAI Flight core
      • mRo ControlZero F7
      • mRo Pixracer Pro (H7)
      • mRo Nexus
      • Omnibus F4 AIO/Pro*
      • OmnibusNanoV6
      • Omnibus F7V2*
      • Parrot C.H.U.C.K
      • RadioLink MiniPix
        • Specifications
        • Where to Buy
        • Peripheral Connections
        • Default UART order
        • Firmware handling
      • QioTek Zealot F427
      • QioTek Zealot H743
      • Sky-Drones AIRLink
      • SkystarsH7HD
      • SPRacing H7 Extreme
      • Swan-K1
      • SpeedyBee F4 (this board currently is non-verified)
      • SpeedyBee F4 V3
      • VR Brain 5
      • VR uBrain 5.1
    • Linux Based Autopilots
    • Firmware Limitations
    • Discontinued boards
    • Schematics
  • First Time Setup
  • First Flight and Tuning
  • QuadPlane Setup and Operation
  • If A Problem Arises
  • Flight Features
  • Advanced Configuration
  • Mission Planning
  • Logs
  • Peripheral Hardware
  • OEM Customization
  • Use-Cases and Applications
  • Antenna Tracking
  • Simulation
  • User Alerts
  • Upcoming Features
  • Appendix
  • Fixed Wing FAQ
  • Full Table of Contents


Individual Partners SWAG Shop
Plane
  • »
  • Autopilot Hardware Options »
  • RadioLink MiniPix
  • Edit on GitHub

RadioLink MiniPix¶

Warning

This autopilot is not recommended because some versions of the board are not compatible with the official ArduPilot software despite multiple efforts to work with the manufacturer to make them compatible. The manufacturer is also apparently not abiding by the GPLv3 license which requires releasing the modified source code to its customers. “V1.0” and “V1.2” probably work, “V1.0 II” and “V1.1” definitely do not work.

../_images/minipix1.jpg

above image and some content courtesy of the RadioLink website

Specifications¶

  • Processor and Sensors

    • STM32F405VGT6 ARM microcontroller

    • InvenSense MPU6500

    • Compass QMC5883L

    • Barometer LPS22HB

  • Interfaces

    • 6x PWM outputs

    • 1x RC input (PWM/PPM, SBUS)

    • 3 UARTS (flow-control on Telem 1 & 2, no flow-control on GPS port)

    • external I2C

    • 2 x ADC for voltage and current sensor

    • 1 x additional ADC for analog RSSI or analog airspeed

    • SDIO microSD card slot

    • micro USB connector

    • includes buzzer / safety-switch, power module, I2C expansion board and TS100 GPS / mag combo depending on kit features

    • size 39 x 39 x 12 mm

    • weight 12 g without wires

Where to Buy¶

  • RadioLink hardware is available from various warehouses like banggood.com

Peripheral Connections¶

../_images/minipix_periphs.jpg

Default UART order¶

  • SERIAL0 = console = USB

  • SERIAL1 = Telemetry1 = USART3

  • SERIAL2 = Telemetry2 = USART2 (see Notes for reversed plastic case labels!)

  • SERIAL3 = GPS1 = UART4

Serial protocols can be adjusted to personal preferences.

Firmware handling¶

This hardware comes preflashed with a RadioLink-branded version of ArduCopter and an ArduPilot-compatible bootloader. To use non-branded ChibiOS-based ArduPilot firmware versions, download the required vehicle firmware .apj file from https://firmware.ardupilot.org/ and flash your board using MissionPlanner’s “custom firmware” option.

In case a bootloader re-installation is required, you can boot your board to DFU-mode using the following solder-points:

../_images/minipix_dfu.jpg

Then follow the instructions on how to load firmware onto ChibiOS boards.

Warning

The flightcontroller’s plastic case shows the telemetry ports’ numbers reversed compared to the board’s PCB imprints and the firmware’s SERIALn assignments, this requires additional attention!

Note

MiniPix voltage and current sensing pins use Pixhawk standard ( BATT_VOLT_PIN = 2, BATT_CURR_PIN = 3). The additional ADC pin can be used for either RSSI or analog airspeed. Set required option to PIN = 11.

Previous Next

Questions, issues, and suggestions about this page can be raised on the forums. Issues and suggestions may be posted on the forums or the Github Issue Tracker.

Creative Commons License© Copyright 2023, ArduPilot Dev Team.