# PX4 Vision Autonomy Development Kit

The PX4 Vision Autonomy Development Kit (opens new window) is a robust and inexpensive kit for enabling computer vision development on autonomous vehicles.

Overview

The kit contains a near-ready-to-fly carbon-fiber quadcopter equipped with a Pixhawk 4 flight controller, a UP Core companion computer (4GB memory & 64GB eMMC), and a Occipital Structure Core depth camera sensor.

Note

This vehicle comes with no pre-installed software. A pre-imaged USB stick that contains a reference implementation of the PX4/PX4-Avoidance local planner software is provided by Auterion. This software provides only a very basic example of what you can do with the PX4 Vision Autonomy Kit. Developers can use the kit to try out other features provided by the PX4 Avoidance (opens new window) project, modify the existing code, or experiment with completely new computer vision-based functionality.

The guide explains the minimal additional setup required to get the vehicle ready to fly (installing an RC system and battery). It also covers the first flight, and how to get started with modifying the computer vision code.

# Purchase

# Px4 Vision Guide Content

# Warnings and Notifications

  1. The kit is intended for computer vision projects that use a forward-facing camera (it does not have downward or rear-facing depth cameras). Consequently it can’t be used (without modification) for testing Safe Landing, or other features that require a downward-facing camera.
  2. Obstacle avoidance in missions can only be tested when GPS is available (missions use GPS coordinates). Collision prevention can be tested in position mode provided there is a good position lock from either GPS or optical flow.
  3. The port labeled USB1 may jam the GPS if used with a USB3 peripheral (disable GPS-dependent functionality including missions). This is why the boot image is supplied on a USB2.0 memory stick.
  4. PX4 Vision with ECN 010 or above (carrier board RC05 and up), the UP Core can be powered by either the DC plug or with battery. RC Number ECN Number

WARNING

For PX4 Vision with ECN below 010/carrier board below RC04, the UP Core should only be powered using the battery (do not remove the UP Core power socket safety cover).

Warning - do not connect power port

# What is Inside

What's inside

Whats inside

The PX4 Vision DevKit contains following components:

  • Core Components:

    • 1x Pixhawk 4 flight controller (with custom PX4 firmware)
    • 1x PMW3901 optical flow sensor
    • 1x TOF Infrared distance sensor (PSK‐CM8JL65‐CC5)
    • 1x Structure Core depth camera
      • 160 deg wide vision camera
      • Stereo infrared cameras
      • Onboard IMU
      • Powerful NU3000 Multi-core depth Processor
    • 1x UP Core computer (4GB memory & 64GB eMMC with Ubuntu and PX4 avoidance)
      • Intel® Atom™ x5-z8350 (up to 1.92 GHz)
      • Compatible OS: Microsoft Windows 10 full version, Linux (ubilinux, Ubuntu, Yocto), Android
      • FTDI UART connected to flight controller
      • USB1: USB3.0 A port used for booting PX4 avoidance environment from a USB2.0 stick (connecting a USB3.0 peripheral may jam GPS).
      • USB2: USB2.0 port on a JST-GH connector. Can be used for second camera, LTE, etc. (or keyboard/mouse during development).
      • USB3: USB2.0 JST-GH port connected to depth camera
      • HDMI: HDMI out
      • SD card slot
      • WiFi 802.11 b/g/n @ 2.4 GHz (attached to external antenna #1). Allows computer to access home WiFi network for Internet access/updates.
  • Mechanical Specification:

    • Frame: Full 5mm 3k carbon fiber twill
    • Motors: T-MOTOR F60 PROⅢ KV1750
    • ESC: BEHEli-S 20A ESC
    • Propellers: T6045
    • GPS: Pixhawk4 GPS module
    • Power module: Holybro PM07
    • Wheelbase: 286mm
    • Weight: 854 grams without battery or props
    • Telemetry: ESP8266 connected to flight controller (attached to external antenna #2). Enables wireless connection to the ground station.
  • A USB2.0 stick with pre-flashed software provided by Auterion that bundles:

  • Assorted cables, 8x propellers, 2x battery straps (installed) and other accessories (these can be used to attach additional peripherals).

# What Else Do You Need

The kit contains all the essential drone hardware except a battery and a radio control system, which must be purchased separately:

  • Battery:
    • 4S LiPo with XT60 female connector
    • Less than 115mm long (to fit between power connector and GPS mast)
  • Radio control system
    • Any PX4-compatible RC System can be used.
    • An FrSky Taranis transmitter with R-XSR receiver is one of the more popular setups.
  • An H2.0 Hex Key (to unscrew the top plate so that an RC receiver can be connected)

In addition, users will need ground station hardware/software:

# First-time Setup

  1. Attach a compatible RC receiver to the vehicle (not supplied with kit):

    • Remove/unscrew the top plate (where the battery goes) using an H2.0 hex key tool.
    • Connect the receiver to the flight controller.
    • Re-attach the top plate.
    • Mount the RC receiver on the UP Core carrier board plate at the back of the vehicle (use zipties or double-sided tape).
    • Ensure the antennas are clear of any obstructions and electrically isolated from the frame (e.g. secure them under the carrier board or to the vehicle arms or legs).
  2. Bind the RC ground and air units (if not already done). The binding procedure depends on the specific radio system used (read the receiver manual).

  3. Raise the GPS mast to the vertical position and screw the cover onto the holder on the base plate.

    Raise GPS mast

  4. Insert the pre-imaged USB2.0 stick from the kit into the UP Core port labeled USB1 (highlighted below).

    UP Core: USB1 Port

  5. Power the vehicle with a fully charged battery.

    Note

    Ensure propellers are removed before connecting the battery.

  6. Connect the ground station to the vehicle WiFi network (after a few seconds) using the following default credentials:

    • SSID: pixhawk4
    • Password: pixhawk4

    TIP

    WiFi network SSID, password, and other credentials may be changed after connecting (if desired), by using a web browser to open the URL: http://192.168.4.1. The baud rate must not be changed from 921600.

  7. Start QGroundControl on the ground station.

  8. Configure/calibrate the vehicle:

    Note

    The vehicle should arrive pre-calibrated (e.g. with firmware, airframe, battery, and sensors all setup). You will however need to calibrate the radio system (that you just connected) and it is often worth re-doing the compass calibration.

  9. (Optional) Configure a Flight Mode selector switch on the remote controller.

    Note

    Modes can also be changed using QGroundControl

    We recommend RC controller switches are define for:

    • Position Mode - a safe manual flight mode that can be used to test collision prevention.
    • Mission Mode - run missions and test obstacle avoidance.
    • Return Mode - return vehicle safely to its launch point and land.
  10. Attach the propellers with the rotations as shown:

    Motor Order Diagram

    • The propellers directions can be determined from the labels: 6045 (normal, counter-clockwise) and 6045R (reversed, clockwise).

      Propeller identification

    • Screw down firmly using the provided propellor nuts:

      Propeller nuts

# Fly the Drone with Avoidance

When the vehicle setup described above is complete:

  1. Connect the battery to power the vehicle.

  2. Wait until the boot sequence completes and the avoidance system has started (the vehicle will reject arming commands during boot).

    TIP

    The boot/startup process takes around 1 minute from the supplied USB stick (or 30 seconds from internal memory).

  3. Check that the avoidance system has started properly:

    • The QGroundControl notification log displays the message: Avoidance system connected.

      QGC Log showing avoidance system has started

    • A red laser is visible on the front of the Structure Core camera.

  4. Wait for the GPS LED to turn green. This means that the vehicle has a GPS fix and is ready to fly!

  5. Connect the ground station to the vehicle WiFi network.

  6. Find a safe outdoor location for flying, ideally with a tree or some other convenient obstacle for testing PX4 Vision.

  7. To test collision prevention, enable Position Mode and fly manually towards an obstacle. The vehicle should slow down and then stop within 6m of the obstacle (the distance can be changed using the CP_DIST parameter).

  8. To test obstacle avoidance, create a mission where the path is blocked by an obstacle. Then switch to Mission Mode to run the mission, and observe the vehicle moving around the obstacle and then returning to the planned course.

# Development using the Kit

The following sections explain how to use the kit as an environment for developing computer vision software.

# PX4 Avoidance Overview

The PX4 Avoidance system consists of computer vision software running on a companion computer (with attached depth camera) that provides obstacle and/or route information to the PX4 flight stack running on a flight controller.

Documentation about the companion computer vision/planning software can be found on github here: PX4/PX4-Avoidance (opens new window). The project provides a number of different planner implementations (packaged as ROS nodes):

  • The PX4 Vision Kit runs the localplanner by default and this is the recommended starting point for your own software.
  • The globalplanner has not been tested with this kit.
  • The landing planner requires a downward facing camera, and cannot used without first modifying the camera mounting.

PX4 and the companion computer exchange data over MAVLink (opens new window) using these interfaces:

# Installing the image on the Companion Computer

You can install the image on the UP Core and boot from internal memory (instead of the USB stick).

This is recommended because booting from internal memory is much faster, frees up a USB port, and may well provide more memory than your USB stick.

Note

Booting from internal memory takes around 30 seconds while booting from the supplied USB2 stick boots in about a minute (other cards may take several times longer).

To flash the USB image to the UP Core:

  1. Insert the pre-flashed USB drive into the UP Core port labeled USB1.

  2. Login to the companion computer (as described above).

  3. Open a terminal and run the following command to copy the image onto internal memory (eMMC). The terminal will prompt for a number of responses during the flashing process.

    cd ~/catkin_ws/src/px4vision_ros
    sudo ./flash_emmc.sh
    

    Note

    All information saved in the UP Core computer will be removed when executing this script.

  4. Pull out the USB stick.

  5. Restart the vehicle. The UP Core computer will now boot from internal memory (eMMC).

# Boot the Companion Computer

First insert the provided USB2.0 stick into the UP Core port labeled USB1, and then power the vehicle using a 4S battery. The avoidance system should start within about 1 minute (though this does depend on the USB stick supplied).

TIP

Fly the Drone with Avoidance additionally explains how to verify that the avoidance system is active.

If you've already installed the image on the companion computer you can just power the vehicle (i.e. no USB stick is needed). The avoidance system should be up and running within around 30 seconds.

Once started the companion computer can be used both as a computer vision development environment and for running the software.

# Login to the Companion Computer

To login to the companion computer:

  1. Connect a keyboard and mouse to the UP Core via port USB2:

    UP Core: USB2

    • Use the USB-JST cable from the kit to get a USB A connector

      USB to JST cable

    • A USB hub can be attached to the cable if the keyboard and mouse have separate connectors.

  2. Connect a monitor to the UP Core HDMI port.

    UP Core: HDMI port

    The Ubuntu login screen should then appear on the monitor.

  3. Login to the UP Core using the credentials:

    • Username: px4vision
    • Password: px4vision

# Developing/Extending PX4 Avoidance

The PX4 Vision’s UP Core computer provides a complete and fully configured environment for extending PX4 Avoidance software (and more generally, for developing new computer vision algorithms using ROS 2). You should develop and test your software on the vehicle, sync it to your own git repository, and share any fixes and improvements with the wider PX4 community on the github PX4/PX4-Avoidance (opens new window) repo.

The catkin workspace is at ~/catkin_ws, and is preconfigured for running the PX4 avoidance local planner. The launch-from-boot file (avoidance.launch) is in the px4vision_ros package (modify this file to change what planner is launched).

The avoidance package is started on boot. To integrate a different planner, this needs to be disabled.

  1. Disable the avoidance process using the following command:

    systemctl stop avoidance.service
    

    You can simply reboot the machine to restart the service.

    Other useful commands are:

    # restart service
    systemctl start avoidance.service
    
    # disable service (stop service and do not restart after boot)
    systemctl disable avoidance.service
    
    # enable service (start service and enable restart after boot)
    systemctl enable avoidance.service  
    
  2. The source code of the obstacle avoidance package can be found in https://github.com/PX4/PX4-Avoidance which is located in ~/catkin_ws/src/avoidance.

  3. Make changes to the code! To get the latest code of avoidance pull the code from the avoidance repo:

    git pull origin
    git checkout origin/master
    
  4. Build the package

    catkin build local_planner
    

The ROS workspace is placed in ~/catkin_ws. For reference on developing in ROS and using the catkin workspace, see the ROS catkin tutorials (opens new window).

# Developing PX4 Firmware

The kit is designed for creating computer vision software that runs on the companion computer, and which integrates with PX4’s flexible path planning and collision prevention interfaces.

You can also modify PX4 itself, and install it as custom firmware:

  • You will need to connect QGroundControl to the kit's Pixhawk 4 via USB in order to update firmware.
  • Select the PX4 Vision DevKit airframe after loading new firmware: Airframe Selection - PX4 Vision DevKit

Note

Modification of PX4 code is not needed to meet most computer vision use cases. To discuss the interfaces or how to integrate other features join the PX4 slack channel: #computer-vision.

# Px4 Vision Carrier Board Pinouts

The Carrier board pinouts can be download from Holybro's website (opens new window).

# Other Development Resources

# How to get Technical Support

For hardware issues, please contact Holybro at: productservice@holybro.com.

For software issues, use the following community support channels: