Skip to content

基本概念

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 more experienced users).

如果你已经熟悉了基本概念,你可以转到 基本组装 以了解如何连接特定的自驾仪硬件。 To load firmware and set up the vehicle with QGroundControl, see Basic Configuration.

无人机是什么?

A drone, or Unmanned Vehicles (UV), is an unmanned "robotic" vehicle that can be manually or autonomously controlled. They can travel in air, on the ground, on/under the water, and are used for many consumer, industrial, government and military applications, including aerial photography/video, carrying cargo, racing, search and surveying, and so on.

Drones are more formally referred to as Unmanned Aerial Vehicles (UAV), Unmanned Ground Vehicles (UGV), Unmanned Surface Vehicles (USV), Unmanned Underwater Vehicles (UUV).

INFO

The term Unmanned Aerial System (UAS) typically refers to a UAV and all of the other components of a complete system, including a ground control station and/or radio controller, and any other systems used to control the drone, capture, and process data.

Drone Types

There are many different vehicle frames (types), and within the types there are many variations. Some of the types, along with the use cases for which they are most suited are listed below.

  • Multicopters — Multi-rotors offer precision hovering and vertical takeoff, at the cost of shorter and generally slower flight. They are the most popular type of flying vehicle, in part because they are easy to assemble, and PX4 has modes that make them easy to fly and very suitable as a camera platform.
  • Helicopters — Helicopters similar benefits to Multicopters but are mechanically more complex and more efficient. They are also much harder to fly.
  • Planes (Fixed-wing) — Fixed-wing vehicles offer longer and faster flight than multicopters, and hence better coverage for ground surveys etc. However they are harder to fly and land than multicopters, and aren't suitable if you need to hover or fly very slowly (e.g. when surveying vertical structures).
  • VTOL (Vertical Takeoff and Landing) - Hybrid Fixed-wing/Multicopter vehicles offer the best of both worlds: take off in vertical mode and hover like a multicopter but transition to forward flight like an airplane to cover more ground. VTOL are often more expensive than either multicopters and fixed-wing aircraft, and harder to build and tune. They come in a number of types: tiltrotors, tailsitters, quadplanes etc.
  • Airships/Balloons — Lighter-than-air vehicles that typically offer high altitude long duration flight, often at the cost of having limited (or no) control over speed and direction of flight.
  • Rovers — Car-like ground vehicles. They are simple to control and often fun to use. They can't travel as fast as most aircraft, but can carry heavier payloads, and don't use much power when still.
  • Boats — Water-surface vehicles.
  • Submersibles — Underwater vehicles.

更多信息请参阅:

Autopilots

无人机的“大脑”被称为自动驾驶仪。

It minimally consists of flight stack software running on a real time OS ("RTOS") on flight controller (FC) hardware. The flight stack provides essential stabilisation and safety features, and usually also some level of pilot assistance for manual flight and automating common tasks, such as taking off, landing, and executing predefined missions.

Some autopilots also include a general-purpose computing system that can provide "higher level" command and control, and that can support more advanced networking, computer vision, and other features. This might be implemented as a separate companion computer, but in future it is increasingly likely to be a fully integrated component.

PX4 自动驾驶仪

PX4 is powerful open source autopilot flight stack running on the NuttX RTOS.

PX4的一些主要功能包括:

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 由 Dronecode 项目 支持。

Ground Control Stations

Ground Control Stations (GCS) are ground based systems that allow UV operators to monitor and control a drone and its payloads. A subset of the products that are known to work with PX4 are listed below.

QGroundControl

The Dronecode GCS software is called QGroundControl ("QGC"). It runs on Windows, Android, MacOS or Linux hardware, and supports a wide range of screen form factors. You can download it (for free) from here.

QGC Main Screen

QGroundControl communicates with the drone using a telmetry radio (a bidirectional data link), which allows you to get real-time flight and safety information, and to control the vehicle, camera, and other payloads using a point-and-click interface. On hardware that supports them, you can also manually fly the vehicle using joystick controllers. QGC can also be used to visually plan, execute, and monitor autonomous missions, set geofences, and much more.

QGroundControl desktop versions are also used to install (flash) PX4 firmware and configure PX4 on the drone's autopilot/flight controller hardware.

Auterion Mission Control (AMC)

Auterion Mission Control is a powerful and fully featured ground control station application that is optimized for pilots rather than vehicle configuration. While designed to work with Auterion products, it can be used with "vanilla" PX4.

For more information see:

Drone Components & Parts

Flight Controller

Flight controllers (FC) are the hardware onto which the PX4 flight stack firmware is loaded and run. They are connected to sensors from which PX4 determines its state, and to the actuators/motors that it uses to stabilise and move the vehicle.

PX4 can run on many different types of Flight Controller Hardware, ranging from Pixhawk Series controllers to Linux computers. These include Pixhawk Standard and manufacturer-supported boards. You should select a board that suits the physical constraints of your vehicle, the activities you wish to perform, and cost.

For more information see: Flight Controller Selection

传感器

PX4 uses sensors to determine vehicle state, which it needs in order to stablise the vehicle and enable autonomous control. The vehicle states include: position/altitude, heading, speed, airspeed, orientation (attitude), rates of rotation in different axes, battery level, and so on.

PX4 minimally requires a gyroscope, accelerometer, magnetometer (compass) and barometer. A GNSS/GPS or other source of global position is needed to enable all automatic modes, and some manual/assisted modes. Fixed-wing and VTOL-vehicles should additionally include an airspeed sensor (highly recommended).

The minimal set of sensors is incorporated into Pixhawk Series flight controllers (and may also be in other controller platforms). Additional/external sensors can be attached to the controller.

For more information see: Sensor Hardware & Setup

输出:电机,舵机,执行器

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). 下面的图片显示了Pixhawk 4Pixhawk 4 Mini的PWM输出端口。

Pixhawk 4 output ports Pixhawk4 mini MAIN ports

输出分为 MAINAUX,并单独编号(MAINnAUXn, n 通常是从1到6或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.

备注:

  • Pixhawk controllers have an FMU board and may have a separate IO board. 如果有IO 板, AUX 端口直接连接到 FMU 和 MIAN 端口连接到IO板。 否则, MAIN 端口连接到FMU,没有 AUX 端口。
  • The FMU output ports can use D-shot or One-shot protocols (as well as PWM), which provide much lower-latency behaviour. 这对于竞速机和其他需要更好性能的机体来说是有用的。
  • MAINAUX 中仅有6-8个输出,因为大多数飞行控制器只有这么多的 PWM/Dshot/Oneshot 输出。 理论上来说,如果总线支持,可以有更多的输出(比如UAVCAN总线就不限于这几个节点)。

电调 & 电机

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).

有关 PX4 支持的电调和电机的信息,请参阅:

电池/电源

PX4无人机最常使用的是锂聚合物(LiPo)电池。 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 Estimation Tuning 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.

Taranis X9D Transmitter Photo of MicroNav, a ground controller with integrated joysticks

RC systems use a dedicated ground-based radio transmitter and vehicle-based receiver for sending control information. They should always be used when first tuning/testing a new frame design, or when flying racers/acrobatically (and in other cases where low latency is important).

Joystick systems use QGroundControl to encode the control information from a "standard" computer gaming joystick into MAVLink messages, and sent it to the vehicle using the (shared) telemetry radio channel. They can be used for most manual flight use cases such as taking off, surveys, and so on, provided your telemetry channel has a high enough bandwidth/low latency.

Joysticks are often used in integrated GCS/manual control systems because it is cheaper and easier to integrate a joystick than a separate radio system, and for the majority of use cases, the lower latency does not matter. 一些遥控系统还可以额外接收自动驾驶仪传回的数传信息。

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

安全开关

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).

通常,安全开关被整合到GPS设备中,但也可能是一个单独的物理组件。

数传电台

Data/Telemetry Radios can provide a wireless MAVLink connection between a ground control station like QGroundControl and a vehicle running PX4. 这使得在飞行过程中调整参数,实时监视遥测信息,更改任务等成为可能。

机载计算机

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卡(可移除储存器)

PX4 使用 SD 储存卡存储 飞行日志,而且还需要内存卡才能使用 UAVCAN 外围设备,运行 飞行任务

默认情况下,如果没有 SD 卡,PX4 将在启动时播放 格式化失败(2-声短响) 两次(且上述需要储存卡的功能都不可用)。

TIP

Pixhawk 飞控板支持的最大 SD 卡大小为 32 GB 。 The SanDisk Extreme U3 32GB and Samsung EVO Plus 32 are highly recommended.

尽管如此,SD卡也只是可选的。 不包含 SD 卡槽的飞行控制器可以:

  • 使用参数 CBRK_BUZZER 禁用通知蜂鸣器。
  • 推流日志 到另一个组件(机载计算机)。
  • Store missions in RAM/FLASH.

Payloads

Payloads are equipment carried by the vehicle to meet user or mission objectives, such as cameras in surveying missions, instruments used in for inspections such as radiation detectors, and cargo that needs to be delivered. PX4 supports many cameras and a wide range of payloads.

Payloads are connected to Fight Controller outputs, and can be triggered automatically in missions, or manually from an RC Controller or Joystick, or from a Ground Station (via MAVLink/MAVSDK commands).

For more information see: Payloads & Cameras

解锁和加锁

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). 还可以使用遥控上的按钮来配置 PX4 解锁(也可以从地面站发送MAVLink解锁命令)。

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 has a safety switch that has not been engaged.
  • 如果VTOL飞行器处于固定翼飞机模式,则阻止解锁(默认情况下)。

When prearmed you can still use actuators, while disarming unpowers everything. Prearmed and disarmed should both be 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.

更详细的解锁和加锁的配置的解读可以在这里找到:预解锁,解锁,加锁配置

飞行模式

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 for each vehicle can be found below:

Instructions for how to set up your remote control switches to enable different flight modes is provided in Flight Mode Configuration.

安全设置(故障保护)

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).

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).

航向和运动方向

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

Frame Heading

INFO

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.

Frame Heading TOP

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