Introduction
I thought it would be a cool idea to build a super small airplane that could fly long range on a 4G connection. To my surprise, I could not find anything like this on the internet. At least not as small as I wanted it to be. The closest is probably a modified Parrot Disco, weighing just under a kilogram.
Objectives
The objective is to build an airplane that has:
- Flight time at least one hour
- “Unlimited” range by 4G connection
- Live video
- GPS for waypoint missions
- Lightweight
Technical Specifications
I settled on the ZOHD Drift because it is the smallest possible airframe I could find which would still be able to fit all the necessary components. It has nice access hatches on all sides. The model is designed for slow flying and gliding, thus should also be very efficient.
The final specifications of the aircraft where the following:
- ZOHD Drift Airframe
- 2x 18650 Li-ion battery
- Raspberry Pi Zero 2W
- ZeroCam fisheye camera
- Huawei 4G LTE dongle
- Mateksys F411-WTE flight controller
- Mateksys M8Q-5883 (GPS and compass)
- Total weight: 340 gram
- Flight time: 1 hour 20 minutes
- Cruise speed: 10 m/s
Build
Why not Ardupilot or PX4
The easy way to build a 4G airplane is to use an ArduPilot/PX4-capable flight controller. Then you can run something like mavlink-bridge on the Raspberry Pi and use QGroundControl or another ground station to control the flight.
However, the problem with these ArduPilot/PX4 flight controllers is that they are too big for an airplane like the ZOHD Drift. Looking at it the other way around: All flight controllers that fit in the ZOHD Drift are not compatible with ArduPilot/PX4 because they don’t have sufficient ROM.
The Matek F411-WTE flight controller fits perfectly in the ZOHD Drift, but cannot run ArduPilot/PX4.
INAV
ArduPilot/PX4 needs a lot of ROM because it is full of features that I don’t need. Essentially, the flight controller should just be able to read all the sensors and stabilize the airplane. Navigation tasks could even be outsourced to the Raspberry Pi.
The INAV software provides a nice balance and even has waypoint navigation capabilities, while remaining small enough to fit on smaller flight controllers. It is a fork of BetaFlight, but more suited towards fixed-wing and GPS navigation. However, not using Ardupilot or PX4 poses some additional challenges.
Enabling flight control via the internet
Normally, INAV can only take flight control commands from the radio link. In this project, I still use a radio transmitter for low-latency flight control. This is necessary to fly the aircraft in partially stabilized modes, such as takeoff and landing.
When the aircraft is in the air and flying in GPS assisted modes, the latency is no longer critical. In this phase of the flight, the aircraft could also be controlled via an unstable high-latency internet connection. Typical commands would be direction change or vertical speed setpoints. Even more high-level commands include: Enable/disable waypoint mission, return home or loiter.
The Raspberry Pi can send flight control commands to the flight controller via UART. To make this work with INAV, it is necessary to compile the software with the MSP_RC_OVERRIDE flag enabled. INAV provides instruction on this, but I suspect it is not often used because it triggered a compiler error.
In src/main/target/common.h
, uncomment the line that says:
#define USE_MSP_RC_OVERRIDE
.
To ‘fix’ the compiler error, I had to remove a (false positive) static assert in src/main/cms/cms_menu_osd.c
(“missing OSD elements in CMS”).
Communication loss failsafes
Enabling MSP_RC_OVERRIDE allows me to control the plane via 4G or radio. However, by default, the airplane will activate the failsafe when the radio link is lost (even when it receives 4G commands). Since I wanted the ability to fly outside the range of the radio, I needed to modify this failsafe behavior. I made the following modification in src/main/rx/rx.c
:
if (rxFlightChannelsValid && rxSignalReceived) {
failsafeOnValidDataReceived();
#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
} else if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe()) {
failsafeOnValidDataReceived();
#endif
} else {
failsafeOnValidDataFailed();
}
With the additional code, the updated behavior is as follows: When there is no radio signal received, the code will check if the 4G control mode is active. If that is the case, and the 4G control mode is not in a failsafe condition, the condition is now considered valid.
However, if both the radio link and the 4G connection are lost, the failsafe is activated. I configured the failsafe to be a Return-to-Home (RTH) action. Before using RTH as failsafe, it is very important to check the behavior while still in radio line of sight. If a problem happens during testing, it is then still possible to handle the situation safely.
The procedure for testing and activating failsafes should always be:
- Set failsafe to engine off, fixed roll angle. This prevents potential fly-aways.
- Test navigation modes, make sure the airplane is capable of return to home.
- Do all of the tuning in radio line of sight.
- Only when you are 100% certain that the airplane behaves correctly in all navigation modes, configure Return-to-Home as failsafe. Make sure to also check auto-landing.
When the airplane approaches the home position, you will probably be able to take back control before auto-landing starts. However, if your radio transmitter is breaks during the flight, this makes sure the flight ends as soon as possible in a reasonably controllable way.
Minimum speed behavior
While testing the GPS assisted flight modes, I observed some strange behavior. The airplane would sometimes throttle up to almost full throttle (I could clearly hear it from the ground) and back to idle after a few seconds. I noticed this especially during days with a bit of wind.
After some digging in the code, I found a hard-coded threshold of 7 m/s. If the groundspeed of the airplane would drop below 7 m/s, an integrator started winding up quickly with a high hard-coded gain. The value of this integrator would be added to the throttle command, up to a maximum of 50% on top of the cruise throttle setting. With cruise throttle at 40%, it would add up to 90% throttle.
The responsible function is applyFixedWingMinSpeedController
in src/main/navigation/navigation_fixedwing.c
. The idea behind this is good. If the aircraft encounters a strong headwind during a Return-to-Home action, this would make sure the aircraft maintains a minimum ground speed of 7 m/s. Without this function, the aircraft could even start flying backwards and it would never make it back home in a failsafe situation.
Actually, there is another failsafe in INAV that triggers a landing when the aircrafts distance to home keeps increasing during Return-to-Home. This prevents a fly-away but you will still lose your aircraft.
The gain of the integrator is set really high, which causes the airspeed to oscillate a lot around the minimum speed of 7 m/s. Arguably this is better than a gain that is set too low, because then the groundspeed may become negative. Since the heading of the plane is determined from ground track instead of compass, the aircraft will then also turn away from home and make the situation even worse (potentially resulting in a fly-away).
For the ZOHD Drift, the most efficient cruise speed seems to be around the 10 m/s mark. That’s probably much lower than most aircraft that use INAV. Therefore, I felt comfortable reducing the minimum groundspeed to 5 m/s. This allows me to fly in 5 m/s winds without triggering the minimum speed controller.
I also reduced the hard-coded integrator gain from 1.5 to 0.5 and did a lot of testing on days with a little bit over 5 m/s wind. There is still a little bit of oscillation on throttle/airspeed when flying into the wind, but definitely acceptable. By allowing a little bit of oscillation, we are still on the safe side.
4G telemetry and joystick control
To control the aircraft via 4G, I made a small Svelte application that I ran locally on the laptop. The application opens a websocket to a custom program running on the Raspberry Pi. The Svelte application reads the values from a joystick (a playstation 4 controller) and sends those values over the websocket. The other way around, this websocket is also used to receive telemetry data from the Raspberry Pi.
The custom program on the Raspberry Pi simply translates websocket messages to MSP commands on the UART connection to the flight controller board. The other way around, it receives telemetry from the flight controller board and sends those over the websocket.
Low-latency livestream
I configured a Janus Streaming Server which would receive a RTP H264 payload. In the Svelte application, I created a viewer. Janus works really well for low-latency video, which is essential for controlling the airplane via 4G.
On the Raspberry Pi, I would use ffmpeg or gstreamer to open the pi-cam, pack the stream into RTP and send it to the Janus server.
Tailscale
The Raspberry Pi automatically connects to the internet when the Huawei 4G dongle is connected. However the Raspberry Pi does not have a public IP address. To solve this, I installed tailscale on the Raspberry Pi and on my laptop. This sets up a virtual private LAN which allows me to connect directly with the Raspberry Pi.
4G connection stability
The connection of the 4G connection was not very stable. I was usually flying between 30 and 50 meters altitude. Even with a clear radio-line-of-sight between the airplane and the cell tower (only 300 meters away), the connection was not stable.
After a lot of testing, I noticed that the connection would be less stable when the aircraft was in a turn. Especially in loiter mode, this makes the connection really unstable. After flying straight for a couple of seconds, the connection would be stable (showing uninterrupted livestream). As soon as I started a turn, the livestream would be temporarily interrupted.
Next steps
Off course it is super cool to fly via 4G, but it would be much cooler when it would actually be allowed to fly long distance. This airplane is technically able to fly a distance of 40 km. Unfortunately I have not been able to see this airplane to its full potential.
These types of airplanes are relatively cheap to make and could for example be deployed in a swarm. The Raspberry Pi or another onboard computer could do some basic image processing, perhaps to assist in search-and-rescue or wildfire monitoring.
I am also intrigued by the idea of scaling up. I’ve seen examples on the internet of more than 10 hours flight time using a 2.4 meter wingspan Phoenix 2400. I imagine a couple of drone airports where these planes are deployed from. The airplanes can do observation missions or respond to emergencies. With a 4G internet connection, they can cover large areas. Only very few drone airports are required. The planes then need a runway or grass strip to land, but that might be acceptable if it can stay airborne for 10 hours. I think this would be an interesting alternative to drone-in-a-box systems, especially for situations where a large area needs to be covered.