Basic Concepts

This topic provides a basic introduction to drones and using PX4 (it is meant mostly for novice users but is also a good introduction for experienced users).

If you are already familiar with the basic concepts, you can move on to Basic Assembly to learn how to wire your specific autopilot hardware. To load firmware and set up the vehicle with QGroundControl, see Basic Configuration.

What is a Drone?

A drone is an unmanned "robotic" vehicle that can be remotely or autonomously controlled.

Drones are used for many consumer, industrial, government and military applications. These include (non exhaustively): aerial photography/video, carrying cargo, racing, search and surveying etc.

Different types of drones are used for air, ground, sea, and underwater. These are (more formally) referred to as Unmanned Aerial Vehicles (UAV), Unmanned Aerial Systems (UAS), Unmanned Ground Vehicles (UGV), Unmanned Surface Vehicles (USV), Unmanned Underwater Vehicles (UUV).

The "brain" of the drone is called an autopilot. It consists of flight stack software running on vehicle controller ("flight controller") hardware.

Some drones also have a separate on-vehicle companion computer. These provide powerful general-purpose computing platform for networking, computer vision, and many other tasks.

PX4 Autopilot

PX4 is powerful open source autopilot flight stack.

Some of PX4's key features are:

PX4 is a core part of a broader drone platform that includes the QGroundControl ground station, Pixhawk hardware, and MAVSDK for integration with companion computers, cameras and other hardware using the MAVLink protocol. PX4 is supported by the Dronecode Project.

QGroundControl

The Dronecode ground control station is called QGroundControl. You can use QGroundControl to load (flash) PX4 onto the vehicle control hardware, you can setup the vehicle, change different parameters, get real-time flight information and create and execute fully autonomous missions.

QGroundControl runs on Windows, Android, MacOS or Linux. Download and install it from here.

Vehicle/Flight Controller Board

PX4 was initially designed to run on Pixhawk Series controllers, but can now run on Linux computers and other hardware. You should select a board that suits the physical constraints of your vehicle, the activities you wish to perform, and of course cost.

For more information see: Flight Controller Selection.

Sensors

PX4 uses sensors to determine vehicle state (needed for stabilization and to enable autonomous control). The system minimally requires a gyroscope, accelerometer, magnetometer (compass) and barometer. A GPS or other positioning system is needed to enable all automatic modes, and some assisted modes. Fixed wing and VTOL-vehicles should additionally include an airspeed sensor (very highly recommended).

For more information see:

Outputs: Motors, Servos, Actuators

PX4 uses outputs to control: motor speed (e.g. via ESC), flight surfaces like ailerons and flaps, camera triggers, parachutes, grippers, and many other types of payloads.

The outputs may be PWM ports or DroneCAN nodes (e.g. DroneCAN motor controllers). The images below show the PWM output ports for Pixhawk 4 and Pixhawk 4 mini.

The outputs are divided into MAIN and AUX outputs, and individually numbered (i.e. MAINn and AUXn, where n is 1 to usually 6 or 8). They might also be marked as IO PWM Out and FMU PWM OUT (or similar).

:::warning A flight controller may only have MAIN PWM outputs (like the Pixhawk 4 Mini), or may have only 6 outputs on either MAIN or AUX. Ensure that you select a controller that has enough ports/outputs for your airframe. :::

You can connect almost any output to any motor or other actuator, by assigning the associated function ("Motor 1") to the desired output ("AUX1") in QGroundControl: Actuator Configuration and Testing. Note that the functions (motor and control surface actuator positions) for each frame are given in the Airframe Reference.

Notes:

  • Pixhawk controllers have an FMU board and may have a separate IO board. If there is an IO board, the AUX ports are connected directly to the FMU and the MAIN ports are connected to the IO board. Otherwise the MAIN ports are connected to the FMU, and there are no AUX ports.

  • The FMU output ports can use D-shot or One-shot protocols (as well as PWM), which provide much lower-latency behaviour. This can be useful for racers and other airframes that require better performance.

  • There are only 6-8 outputs in MAIN and AUX because most flight controllers only have this many PWM/Dshot/Oneshot outputs. In theory there can be many more outputs if the bus supports it (i.e. a UAVCAN bus is not limited to this few nodes).

ESCs & Motors

Many PX4 drones use brushless motors that are driven by the flight controller via an Electronic Speed Controller (ESC) (the ESC converts a signal from the flight controller to an appropriate level of power delivered to the motor).

For information about what ESC/Motors are supported by PX4 see:

Battery/Power

PX4 drones are mostly commonly powered from Lithium-Polymer (LiPo) batteries. The battery is typically connected to the system using a Power Module or Power Management Board, which provide separate power for the flight controller and to the ESCs (for the motors).

Information about batteries and battery configuration can be found in Battery Configuration and the guides in Basic Assembly (e.g. Pixhawk 4 Wiring Quick Start > Power).

Manual Control

Pilots can control a vehicle manually using either a Radio Control (RC) System or a Joystick/Gamepad controller connected via QGroundControl.

:::note PX4 does not require a manual control system for autonomous flight modes. :::

:::note Both methods can be used for most manual control use cases, such as surveys. RC systems are recommended when first tuning/testing a new frame design or when flying racers/acrobatically (and in other cases where low latency is important). :::

Radio Control (RC)

Radio Control (RC) systems can be used to manually control PX4.

They consist of a ground based RC controller that uses a radio transmitter to communicate stick/control positions to a receiver on the vehicle. Some RC systems can additionally receive telemetry information back from the autopilot.

RC System Selection explains how to choose an RC system. Other related topics include:

GCS Joystick Controller

A Joystick/Gamepad connected through QGroundControl can also be used to manually control PX4.

With this approach, QGroundControl translates stick/button information from a connected Joystick into MAVLink-protocol messages, which are then sent to PX4 using the shared telemetry radio link. The telemetry radio must have sufficient bandwidth for both manual control and other telemetry messages, and of course this approach means that you must have a ground station running QGroundControl.

Joysticks are also used to manually fly PX4 in a simulator.

:::note Controllers like the Auterion Skynav and UAVComponents MicroNav integrate QGC and a Joystick, and connect the vehicle via a high bandwidth telemetry radio link.

Safety Switch

Some vehicles have a safety switch that must be engaged before the vehicle can be armed (when armed, motors are powered and propellers can turn).

Commonly the safety switch is integrated into a GPS unit, but it may also be a separate physical component.

Data/Telemetry Radios

Data/Telemetry Radios can provide a wireless MAVLink connection between a ground control station like QGroundControl and a vehicle running PX4. This makes it possible to tune parameters while a vehicle is in flight, inspect telemetry in real-time, change a mission on the fly, etc.

Offboard/Companion Computer

A Companion Computer (also referred to as "mission computer" or "offboard computer"), is a separate on-vehicle computer that communicates with PX4 to provide higher level command and control.

The companion computer usually runs Linux, as this is a much better platform for "general" software development, and allows drones to leverage pre-existing software for computer vision, networking, and so on.

The flight controller and companion computer may be pre-integrated into a single baseboard, simplifying hardware development, or may be separate, and are connected via a serial cable, Ethernet cable, or wifi. The companion computer typically communicates with PX4 using a high level Robotics API such as MAVSDK or ROS 2.

Relevant topics include:

SD Cards (Removable Memory)

PX4 uses SD memory cards for storing flight logs, and they are also required in order to use UAVCAN peripherals and fly missions.

By default, if no SD card is present PX4 will play the format failed (2-beep) tune twice during boot (and none of the above features will be available).

:::tip The maximum supported SD card size on Pixhawk boards is 32GB. The SanDisk Extreme U3 32GB is highly recommended. :::

SD cards are never-the-less optional. Flight controllers that do not include an SD Card slot may:

  • Disable notification beeps are disabled using the parameter CBRK_BUZZER.

  • Stream logs to another component (companion).

  • Store missions in RAM/FLASH.

Arming and Disarming

A vehicle is said to be armed when all motors and actuators are powered, and disarmed when nothing is powered. There is also a prearmed state when only actuators are powered.

:::warning Armed vehicles can be dangerous as propellors will be spinning. :::

Arming is triggered by default (on Mode 2 transmitters) by holding the RC throttle/yaw stick on the bottom right for one second (to disarm, hold stick on bottom left). It is alternatively possible to configure PX4 to arm using an RC switch or button (and arming MAVLink commands can also be sent from a ground station).

To reduce accidents, vehicles should be armed as little as possible when the vehicle is on the ground. By default, vehicles are:

  • Disarmed or Prearmed (motors unpowered) when not in use, and must be explicitly armed before taking off.

  • Automatically disarm/prearm if the vehicle does not take off quickly enough after arming (the disarm time is configurable).

  • Automatically disarm/prearm shortly after landing (the time is configurable).

  • Arming is prevented if the vehicle is not in a "healthy" state.

  • Arming is prevented if the vehicle has a safety switch that has not been engaged.

  • Arming is prevented if a VTOL vehicle is in fixed-wing mode (by default).

When prearmed you can still use actuators, while disarming unpowers everything. Prearmed and disarmed should both safe, and a particular vehicle may support either or both.

:::tip Sometimes a vehicle will not arm for reasons that are not obvious. QGC v4.2.0 (Daily build at time of writing) and later provide an arming check report in Fly View > Arming and Preflight Checks. From PX4 v1.14 this provides comprehensive information about arming problems along with possible solutions. :::

A detailed overview of arming and disarming configuration can be found here: Prearm, Arm, Disarm Configuration.

Flight Modes

Flight modes provide different types/levels of vehicle automation and autopilot assistance to the user (pilot). Autonomous modes are fully controlled by the autopilot, and require no pilot/remote control input. These are used, for example, to automate common tasks like takeoff, returning to the home position, and landing. Other autonomous modes execute pre-programmed missions, follow a GPS beacon, or accept commands from an offboard computer or ground station.

Manual modes are controlled by the user (via the RC control sticks/joystick) with assistance from the autopilot. Different manual modes enable different flight characteristics - for example, some modes enable acrobatic tricks, while others are impossible to flip and will hold position/course against wind.

:::tip Not all flight modes are available on all vehicle types, and some modes can only be used when specific conditions have been met (e.g. many modes require a global position estimate). :::

An overview of the available flight modes can be found here. Instructions for how to set up your remote control switches to turn on different flight modes is provided in Flight Mode Configuration.

Safety Settings (Failsafe)

PX4 has configurable failsafe systems to protect and recover your vehicle if something goes wrong! These allow you to specify areas and conditions under which you can safely fly, and the action that will be performed if a failsafe is triggered (for example, landing, holding position, or returning to a specified point).

:::note You can only specify the action for the first failsafe event. Once a failsafe occurs the system will enter special handling code, such that subsequent failsafe triggers are managed by separate system level and vehicle specific code. :::

The main failsafe areas are listed below:

  • Low Battery

  • Remote Control (RC) Loss

  • Position Loss (global position estimate quality is too low).

  • Offboard Loss (e.g. lose connection to companion computer)

  • Data Link Loss (e.g. lose telemetry connection to GCS).

  • Geofence Breach (restrict vehicle to flight within a virtual cylinder).

  • Mission Failsafe (prevent a previous mission being run at a new takeoff location).

  • Traffic avoidance (triggered by transponder data from e.g. ADSB transponders).

For more information see: Safety (Basic Configuration).

Heading and Directions

All the vehicles, boats and aircraft have a heading direction or an orientation based on their forward motion.

:::note For a VTOL Tailsitter the heading is relative to the multirotor configuration (i.e. vehicle pose during takeoff, hovering, landing). :::

It is important to know the vehicle heading direction in order to align the autopilot with the vehicle vector of movement. Multicopters have a heading even when they are symmetrical from all sides! Usually manufacturers use a colored props or colored arms to indicate the heading.

In our illustrations we will use red coloring for the front propellers of multicopter to show heading.

You can read in depth about heading in Flight Controller Orientation

Last updated