Drone Autopilot Solutions
The Ardupilot and PX4 open-source autopilot platforms are two of the most popular flight controller platforms for drones. In Part 1 of this article series, Raul begins by discussing the general architecture of a do-it-yourself, multirotor drone and its main software and hardware components.
— ADVERTISMENT—
—Advertise Here—
— ADVERTISMENT—
—Advertise Here—
Ardupilot and PX4 are two open-source autopilot platforms regarded as the leading flight controller platforms for small unmanned vehicles in a wide variety of applications, including hobby and amateur, commercial, industrial and academic research.
In Part 1 of this article series, I will begin by discussing the general architecture of a do-it-yourself multirotor drone and its main software and hardware components. Then, I will provide a general introduction to both the Ardupilot and PX4 platforms, and discuss some examples of supported flight controller hardware, vehicle types and available ground control software. I will also give a general introduction to the MAVLink protocol used in both platforms for communication of vehicles with ground control stations.
In Part 2 of this series, I’ll discuss how to build a quadrotor for aerial photography, based on one of the aforementioned platforms. I will also present a setup that, with minor modifications, could also be used as a starting point for future experimentation with autonomous navigation and computer-vision-based object tracking.
The information presented here is aimed mainly at students and hobbyists who want to start building multirotor drones with open-source Ardupilot and PX4 software and hardware, but don’t have a general background in multirotors and the aforementioned platforms. By the end of the article series, the necessary information will be presented to understand the general architecture of a multirotor and choose one of the two platforms for building a drone for aerial photography.
Figure 1 is a block diagram depicting the general architecture of a multirotor drone system for aerial photography. It comprises the following main components: a frame, a flight controller with onboard and offboard sensors, a propulsion system, a power system, a radio control (RC) transmitter/receiver pair, telemetry transceivers, a video camera with a gimbal, a First Person View (FPV) system with a video transmitter, receiver and monitor and ground control software, typically running on a personal computer or mobile device. Let’s look at each component in more detail.
— ADVERTISMENT—
—Advertise Here—
THE FLIGHT CONTROLLER
The flight controller is generally a microcontroller (MCU)-based board with firmware specially written for stabilizing and controlling the flight of the aircraft. It has attached onboard and offboard sensors, from which it takes readings and uses that data to try to infer the aircraft’s pose (position and orientation). Then, with the help of a sophisticated control algorithm, it tries to stabilize the aircraft and make it maintain its actual pose, or drive it to a new desired one. It achieves stabilization by constantly comparing its actual pose (inferred from its sensors) and the desired pose (where it wants to be). Based on that information, it decides how much thrust it must apply to all its rotors to correct its pose.
Sensors frequently found in typical flight controllers are: 3D accelerometers and gyroscopes, altimeter (pressure sensor), digital compass (magnetometer) and a GPS receiver. Although in practice, only a 3D gyroscope is needed to keep a multirotor aerodynamically stable (hovering in the air), the other sensors are required to make possible more advanced functionality, such as maintaining a given position, orientation or velocity, flying GPS waypoints and so on.
STABILIZATION
Multirotors are inherently aerodynamically unstable, and it is very difficult to stabilize them by manually controlling the thrust of their rotors. For that reason, an electronic flight controller is required to stabilize a multirotor aerodynamically. The flight controller can execute a control loop (that is, read its sensors, compute errors and take the necessary correction measures) at a high frequency. In contrast, fixed-wing drones (“planes”) are inherently aerodynamically stable, and can be flown by controlling manually their motor thrust and control surfaces. Therefore, flight controllers are optional for stabilizing fixed wings, but they are still required for more advanced functions, such as maintaining a given trajectory or flying automated GPS waypoint missions.
The embedded software for a flight controller is not trivial. Usually it contains, at its core, sophisticated algorithms used in autopilots, such as nested PID control loops for controlling 3D attitude, and velocity and Kalman filters for sensor fusion. However, the firmware, which is a precompiled binary of the autopilot software, is generally available directly to be loaded to the flight controller board.
Figure 2 shows the Pixhawk 1 flight controller board, along with a GPS receiver and digital compass sensor module. (Both the GPS receiver and compass come inside the round case.) The Pixhawk 1 is very affordable (around $75) and is compatible with Ardupilot and PX4. It is based on the STMicroelectronics STM32F427 Cortex-M4F 32-bit MCU, and comes with several onboard sensors.
They are an L3GD20H 16-bit gyroscope and a LSM303D 14-bit accelerometer/magnetometer (both also made by STMicroelectronics), one Invensense MPU-6000 3-axis accelerometer/gyroscope and one MEAS MS5611 barometer from TE Connectivity. The external GPS/compass module has a Ublox M8N GPS receiver and a Honeywell HMC5883L digital compass.
FRAME AND PROPULSION SYSTEM
Figure 3 shows two example frames for a hexarotor (frame model S550) and a quadrotor (frame model S500). The main purpose of a frame is to hold all hardware parts that fly with the aerial vehicle. The propulsion system, in contrast, comprises all parts directly in charge of generating lift for the aerial vehicle. They are a set of brushless motors, propellers and Electronic Speed Controller (ESC) units in the required number for the selected configuration (four for a quadrotor, six for a hexarotor, and so on). Figure 4 shows, from left to right, an ESC, a brushless motor and a propeller.
A brushless motor, known also as electronically commutated or synchronous DC motor, is controlled by a current pulse signal from the ESC. It is characterized mainly by four specifications: size, rotation velocity, maximum working voltage and power. For example, a “2212, 920KV, 4S, 150W” brushless motor has a diameter of 22mm and a height of 12mm (hence, 2212). It spins at 920KV (which is really 920rpm/V), and can be powered with Lithium-ion polymer (LiPo) batteries up to 4 cells (or any equivalent power supply). A LiPo battery has a nominal voltage of 3.7V per cell, so a 4S battery has a total nominal voltage of 3.7V × 4 = 14.8V. This means that this particular motor can be powered with any voltage up to 14.8V, nominally. Last, the power specification gives us the maximum current the motor can handle safely.
Propellers are characterized mainly by diameter and pitch. For example, a “1045” propeller has a diameter of 10” and a pitch of 4.5”. For two-blade propellers, the diameter is the size between the tips of the two blades. The pitch, however, has a meaning seemingly more “obscure” at first, especially for newcomers. It is the longitudinal distance a propeller would move forward in one revolution, as if it were a screw going into wood [1].
Both diameter and pitch must be appropriately combined, according to velocity and power specifications for a given motor. As a rule of thumb, large-diameter and low-pitch propellers are required for low-velocity motors, which, in turn, provide more torque—characteristics typically desired for drones that lift high payloads. In contrast, low-diameter and high-pitch propellers are required for high velocity motors, which make the aircraft faster and more maneuverable, but with lower motor torque and less payload capacity. The latter characteristics typically are required for racing drones.
In general, however, we don’t have to worry much about these specific details, because for building our first multirotor, we generally take one of a few “reference design” kits widely available for purchase. They have all the right parts with the right specifications for a given application, whether for racing, photography or carrying high payloads. Propellers come in a variety of materials, most commonly plastic, reinforced fiberglass, carbon fiber and wood. The plastic ones are cheaper and low quality, and the wood ones generally are more expensive but with better quality. A good mix of low price and reasonable quality would be the reinforced fiberglass or carbon fiber propellers.
The ESC, as its name implies, controls the motor speed. An ESC receives a PWM signal (identical to a servo motor control signal) at its input, and provides in response a tri-phase voltage signal to drive the brushless motor. It uses field-effect transistors (FETs) to produce high-current switching signals with a duty cycle proportional to the required velocity. ESCs are characterized mainly by the maximum current they can source and the maximum battery voltage they can work with. A “30A, 5S” ESC for example, will handle up to 30A of current and work with batteries up to 5 cells in series (18.5V, nominal voltage).
Most ESCs include a Battery Elimination Circuit (BEC) unit, which is just a fancy name for a voltage regulator that provides a 5V output to power some other electronic devices in a drone, such as servo motors and small video cameras. There are also opto-isolated ESCs (OPTO ESCs), which have the input-signal-receiving circuitry optically isolated from the higher output voltage circuit that powers the motor. This type of ESC typically doesn’t have BEC units included, but if needed, BECs can be purchased separately as stand-alone units.
POWER, RC AND TELEMETRY
The power system comprises a LiPo battery pack, a power module and optionally a battery alarm. Figure 5 shows them from left to right, in that order. LiPo batteries are usually characterized by three main specifications—capacity, voltage and discharge rate. For example, for a typical quadrotor for aerial photography a “5000mA-hour, 3S, 8C” LiPo battery can be used. 5000mA-hour capacity means that the battery can provide a sustained current of 5,000mA (or 5A) for 1 hour, or alternately 10A for half an hour, or 20A for 15 minutes. 3S means that the battery has 3 LiPo cells connected serially, for a total nominal voltage of 11.1V (3.7V x 3 = 11.1V). The discharge rate 8C, if multiplied by the capacity, specifies the battery’s continuous discharge rating. Multiplying 5,000 times 8, gives 40,000mA, or 40A of continuous discharge current rating. This means the battery can give continuously up to 40A of current safely, without suffering any damage.
The power module is basically a 5V regulated power supply with included voltage and current sensors. It takes the battery voltage (for example 11.1V for a 3S battery) as input, and provides a regulated 5V output to power the flight controller and onboard sensors, along with any other external device connected to the flight controller. Examples of such external devices include offboard sensor modules, the RC receiver, and the telemetry transceiver. The flight controller can read from the included voltage and current sensors the drone’s actual voltage and current consumption, and use this data to estimate the remaining battery power and also the available flight time.
As for the LiPo alarm, it is basically a voltmeter with a buzzer. It constantly measures the voltage in each cell of the battery, and provides an audible alarm beep when the cells reach the minimum allowed voltage (about 3V) per cell. So, the main task of the LiPo alarm is to warn us when the battery has reached the minimum permissible voltage before over-discharge—which can irreversibly damage the battery–occurs. The voltage and current sensors present in the power module basically fulfill this same task, if appropriately configured with in the flight controller. In this case, the external LiPo alarm would become redundant. LiPo battery cells have a maximum cell voltage specification too, which is 4.2V for a fully charged cell. This means a fully charged 3S battery really has 12.4V, higher than the nominal 11.4V [2].
Let’s talk now about the telemetry modules and RC system shown in Figure 6. The RC system (the large and small objects on the right in Figure 6) comprises a transmitter and receiver pair working in the 2.4 GHz bandwidth (the most popular working frequency for RCs). A system with at least four channels is required for basic flying of a multirotor, and a minimum of six channels is needed to include some advanced functions, such as multiple flying modes and some GPS based flying functions. If you can afford them, nine or 10 channels are recommended for maximum versatility.
Telemetry modules (the two objects on the left in Figure 6), as the name implies, help us receive from the drone radio telemetry data in a personal computer or mobile device. They also allow us to remotely change some configuration parameters in the flight controller, and to perform advanced functions, such as sending and triggering GPS waypoint navigation missions. Common telemetry modules are available for working in the 433MHz and 915MHz bandwidths. You must choose the legally permitted one in your country, in compliance with local regulations.
AERIAL PHOTOGRAPHY HARDWARE
A typical aerial photography quadcopter, such as the one we will build in Part 2 of this article series, has a payload capacity of around 500g on average. Cameras designed for recording sports action, and cameras specifically designed for drone photography are commonly used, because they are small and low-weight (around 130g). These cameras can store video images and photos locally in a micro SD card, but also provide a live output video feed, which can be wirelessly transmitted and monitored in real time using an FPV system.
Some cameras have internal rechargeable batteries, so they don’t need external power, and some can be powered directly from the LiPo pack. Figure 7 shows a GoPro Hero camera mounted in a Tarot TL68A00 compatible gimbal. The gimbal is an auto-leveling mechanism that helps the camera stay horizontally and vertically level, even if the drone is not. It has sensors, such as accelerometers and gyroscopes, which, in conjunction with an MCU, stabilize the camera, in a way similar to how the flight controller stabilizes the drone, itself. The gimbal can be powered directly from the LiPo battery pack that powers the drone’s propulsion system.
Finally, the FPV system (Figure 8) is a wireless video transmission, reception and monitoring system that works commonly in the 5.8GHz bandwidth. It comprises a video transmitter (upper left in Figure 8) connected to the video output feed of the camera, and a receiver (lower left) connected to a video monitor (to the right). The monitor is located near the pilot at the ground control station. The transmitter can be powered from the main battery pack, whereas the receiver and video monitor generally have their own LiPo battery for portability.
Ground Control Station (GCS) software is a software application that runs on a personal computer or mobile device and performs a variety of functions: It allows a user to program the firmware in the flight controller board, configure its parameters, calibrate the sensors and configure the RC system, among other things. It also displays the drone’s telemetry data in real time (for example, position and velocity), and makes it possible to control the drone remotely, modify its parameters and trigger some special functions—such as autonomous GPS waypoint navigation and automatic return to home. It also allows monitoring of the drone’s global position in a map and sometimes monitoring live video streams from the drone’s camera.
Figure 9 shows a screen capture of QGroundControl, a well-known GCS software that can run on both personal computers and mobile devices. The screen capture shows the drone’s position and orientation in a map, its followed path, some telemetry data, and a navigation instrumentation panel in the manner of a “virtual cockpit”.
ARDUPILOT AND PX4 PLATFORMS
Ardupilot [3] and PX4 [4] are two of the most commonly used open-source drone platforms for diverse applications, such as hobby and entertainment, professional photography, aero photogrammetry, multi-spectral remote sensing, cargo delivery, and research and development. Both platforms have a complete ecosystem of tools that includes flight controller boards with a variety of supported sensors, autopilot firmware for different types of vehicles and configurations, ground control software and SDKs/APIs for controlling drones programmatically and developing drone applications. In the remaining paragraphs, I will talk about some of the supported flight controller boards and ground control software in both ecosystems. Then I will briefly explain about the MAVLink protocol used in both platforms for telemetry and control.
Flight Controllers: The Ardupilot platform supports a wide variety of open-source and closed-source flight controller hardware. Some of the open-source ones are: Pixhawk 1, Pixhawk 3, Pixracer, CUAV V5, Cube, Beaglebone Black and PocketBeagle. The last couple require sensor add-on boards or “capes.” Some of the closed-source options are: Pixhawk 4, Kakute F4/F7, NAVIO2, VR Brain, VR uBrain, Parrot C.H.U.C.K, and Parrot Bebop Autopilot [5]. Although there are some others, I’m mentioning only those I know most.
There’s available firmware that runs on these hardware platforms to support multiple types of vehicles, such as multirotors, fixed-wing and VTOL (Vertical Take Off and Landing) aircraft, helicopters, ground rovers, boats, submarines and even antenna trackers. Precompiled firmware for all these types of vehicles is generally available directly from ground control software to be easily uploaded to the flight controller board. The firmware is highly configurable via a plethora of parameters that control many things—from low-level configuration of sensors and actuators to the tuning constants of stabilization PID control loops.
Depending on the type of vehicle, the Ardupilot firmware supports a variety of sensors from the most common ones used for basic flight control and stabilization (gyroscopes, accelerometers, compass, altimeter and GPS), to some complementary sensors that allow enhanced functionality (sonar, laser, optical flow and airspeed sensors). Some sensors are included in the flight controller board along the MCU (onboard sensors), and some are attached externally (offboard sensors).
Some functions commonly available to all vehicles in both platforms include: manual, semi-autonomous and fully autonomous flight modes; programmable 3D waypoint navigation missions; fail safes for loss of RC communication; GPS glitches and low battery power level; support for camera gimbal; radio telemetry; companion computer integration and software simulation.
PX4 also has various kinds of supported flight controller hardware [6], and supports vehicles, such as multicopters, helicopters, airplanes, VTOL aircraft and ground rovers. Almost all functionality and characteristics mentioned for Ardupilot apply also to PX4. A list of open- and closed-hardware flight controllers officially supported by both Ardupilot and PX4 at the same time is given in Table 1.
Ground Station Software: Several ground control applications are available for the most common operating systems (Windows, Linux, Mac OS X, Android and iOS). Some of them are open source and some have proprietary licenses. For personal computers there are, for example, Mission Planner, APM Planner 2.0, MAVProxy, UgCS and QGroundControl. For mobile devices there are Tower, AndroPilot, MAV Pilot 1.4, SidePilot and QGroundControl (mobile version).
All of them offer more or less the same functionality—firmware programming in the flight controller board, configuration of vehicle parameters, sensor calibration, RC system configuration and calibration, telemetry monitoring, flight mode management, 3D waypoint navigation and mission control, vehicle global position visualization on a map, FPV video monitoring, and others.
In general, all can be used with flight controller hardware and firmware from both Ardupilot and PX4, because all of them use the MAVLink protocol to communicate with vehicles, to send commands and receive telemetry and parameter data. However, it is possible that some MAVLink message types may not be implemented in some ground control software or the flight controllers, themselves.
THE MAVLINK PROTOCOL
MAVLink (Micro Air Vehicle Link) is an efficient telemetry protocol for communicating with small unmanned vehicles [7], which typically are resource- and bandwidth-constrained systems. It has two major versions, v1.0 and v2.0. The latter is backwards compatible with the former. With the risk of oversimplifying a bit, it can be said that the protocol works basically on two “modes”: multicast publish/subscribe, and point-to-point guaranteed delivery transmissions. The first mode is typically used for sending telemetry data streams from drones to ground control stations, onboard computers and cloud systems. The second is typically used for transmitting data and commands that require guaranteed delivery, such as when changing system configuration parameters in the vehicle or configuring onboard GPS navigation missions.
By mixing both modes, MAVLink achieves high efficiency. A protocol frame in v2.0 has just 14 bytes of overhead, and a maximum of 27 bytes if message authentication is used. It can support up to 255 concurrent systems that can include vehicles, ground control stations, antenna trackers and so on. It has been implemented in other flight controller platforms, besides Ardupilot and PX4, such as: AutoQuad 6 AutoPilot, iNAV and SmartAP Autopilot, along with other ground stations, such as Side Pilot, JAGCS, Flightzoomer, Inexa Control, Synturian Control and some QGroundControl variants (AutoQuad GCS, SmartAP GCS, Yuneec Datapilot, Sentera Groundstation, WingtraPilot).
High-level APIs/SDKs are also available that support the protocol for developing drone applications, such as MAVSDK (written in C++ with bindings to Python, Swift, Java and JavaScript), MAVROS (an ROS-to-MAVLink bridge), DroneKit (which supports Python and Android) and Rosetta Drone, which is a MAVLink wrapper to fly DJI drones with MAVLink-based ground control software.
In Part 2 of this article series next month, I describe how to build a quadcopter with Ardupilot or PX4. I’ll discuss some similarities and differences between both platforms relevant to the build, and also expand a bit about their APIs for coding drone applications. I will also talk briefly about how we can make the quadcopter fly autonomously. Stay tuned!
RESOURCES
References:
[1] http://www.bowersflybaby.com/tech/props.html[2] https://www.robotshop.com/media/files/pdf/hyperion-g5-50c-3s-1100mah-lipo-battery-User-Guide.pdf
[3] https://en.wikipedia.org/wiki/ArduPilot#History
[4] https://auterion.com/the-history-of-pixhawk
[5] http://ardupilot.org/copter/docs/common-autopilots.html
[6] https://docs.px4.io/v1.9.0/en/flight_controller/index.html
[7] https://mavlink.io/en/about/overview.html
Ardupilot platform
http://ardupilot.org
PX4 platform
https://px4.io
mRobotics
https://mrobotics.io
Holybro
http://www.holybro.com
HobbyKing
https://hobbyking.com
Honeywell | www.honeywell.com
Invensense | www.invensense.com
U-blox | www.u-blox.com
STMicroelectronics | www.st.com
TE Connectivity | www.te.com
PUBLISHED IN CIRCUIT CELLAR MAGAZINE • APRIL 2020 #357 – Get a PDF of the issue
Sponsor this ArticleRaul Alvarez Torrico has a B.E. in electronics engineering and is the founder of TecBolivia, a company offering services in physical computing and educational robotics in Bolivia. In his spare time, he likes to experiment with wireless sensor networks, robotics and artificial intelligence. He also publishes articles and video tutorials about embedded systems and programming in his native language (Spanish), at his company’s web site www.TecBolivia.com. You may contact him at raul@tecbolivia.com