Keywords

1 Introduction

In the last decade, the term Unmanned Aerial Vehicles (UAV) has become near-synonymous with so called “drones” - small lightweight multirotor craft, kept stable by active control using cheap lightweight MEMS sensors that became ubiquitous as a byproduct of the smartphone revolution [1]. Their popularity is mirrored in the field of aerial robotic research. The vast majority of work cover multirotor craft, and to a lesser degree, fixed wing aircraft and helicopters. Thus, flight electronics, control software and simulation tools are readily available for these types of vehicles [2, 3]. This allows researchers to build up a suitable autonomous flying platform for any research task with ease, using commercial off the shelf (COTS) components and open source software.

In contrast, lighter-than-air vehicles (LTAV) such as rigid and nonrigid dirigibles (Fig. 1) have fallen out of fashion, despite their superiority for some applications [4]. LTAV are uniquely suited as mobile aerial communication relays as well as for monitoring and wildlife conservation tasks. They produce little noise, have high energy efficiency and long flight times, display benign collision and crash characteristics, pose low danger and cause little environmental impact. However, their comparably high handling complexity, size, lifting gas requirements and cost create an entry barrier for researchers. Unlike for heavier-than-air “drones”, there have been no COTS flight controllers that support autonomous dirigible flight. Therefore, guidance and control algorithms have to be implemented for each vehicle - even though various suitable control strategies can be found in the literature [4,5,6,7,8,9,10]. Similar to both rotor craft and fixed wing UAVs, dirigibles come in many types of actuator arrangements: fixed or vectoring main thrusters, differential thrust, different tail fin arrangements and auxiliary thrusters, single or double hull, etc. Thus, a control algorithm for a specific vehicle might not always be applicable to others.

Fig. 1.
figure 1

Our flying blimp. An autonomous deformable lighter-than-air vehicle (LTAV).

Development of control algorithms is further complicated by the lack of realistic simulation. Existing robotic simulation environments [2] are often ill-suited for the characteristics of LTAV. As LTAV are highly susceptible to wind and turbulence, it is crucial to accurately model both aerodynamic forces and the effects these have on an inherently non-rigid vehicle. To our knowledge, no existing realtime robotic simulation environment addresses this, although analytic studies of these effects have been conducted in the past [11].

In this work, we attempt to solve the aforementioned issues in the context of LTAV and provide researchers in the field of aerial robotics with the tools they are accustomed to when working with fixed wing and rotor craft. Our contributions, for which all source code is providedFootnote 1, are:

  1. 1.

    A robotic simulation framework, using ROS/Gazebo [2, 12] for real time hardware in the loop (HITL) and software in the loop (SITL) simulation of easily customizable airship models in a realistic virtual environment.

    1. (a)

      Realistic simulation of wind, turbulence [13] and aerodynamic forces on a custom shaped, modular, non-rigid deformable air frame.

    2. (b)

      Simulated deformation of the air frame in response to aerodynamic, control, thrust and collision forces.

    3. (c)

      Simulation of buoyancy variation, changes in rigidity and shape, depending on hull pressure and structural parameters.

  2. 2.

    A baseline guidance and control algorithm for autonomous navigation of airships using hierarchical PI controllers. We employ a generic design, to operate on a large subset of possible airship shape and actuator configurations.

    1. (a)

      Implemented based on the Librepilot [2, 14] open source flight control tool chain, to integrate with existing SITL & HITL frameworks and available COTS flight control hardware as well as the above mentioned simulation framework.

    2. (b)

      Full integration with ROS [12]. This facilitates easy integration of lighter-than-air vehicles into existing and future robotic research projects for higher level tasks.

  3. 3.

    Through simulation experiments, we show the effect of changes in rigidity and wind turbulence on the vehicle’s controllability, including the introduction of oscillation modes not present in rigid models.

  4. 4.

    Through real flight experiments, we demonstrate the flight behavior of a \(5\,\text{ m }\) autonomous blimp UAV, with control coefficients previously determined in our simulation, thus validating our simulation results.

In Sect. 2, we compare our work to the state of the art. We explain our methodology in Sect. 3. Experiments and results are shown in Sect. 4, followed by a remark on limitations in Sect. 5 and our summarizing conclusions in Sect. 6.

2 State of the Art

The seminal work involving the AURORA airship [4, 10, 15] describes the development of a complete system, including novel on board electronics, communication, control algorithms and a flight simulator, both for control evaluation and human operator training. The hierarchical PI control algorithm described there is similar to our implementation, but it does not utilize dynamic thrust vector control. It also makes many simplifications, including flight at constant airspeed. Although a separate hover control scheme is mentioned, which does use thrust vector control, this is not described in detail. Their simulation assumes rigidity of the air frame. Aerodynamics are modeled based on existing wind tunnel data from a different airship with similar proportions. In contrast, we use modern COTS UAV components and freely available open source software, which greatly enhances reproducibility and the ability to integrate with common robotic components [12]. We also model nonrigid deformation effects in our simulation. Our aerodynamic approach is more generic and allows modeling arbitrary dirigibles, even when no detailed aerodynamic measurements are available - based on geometric shape.

The literature review paper [11] covers modeling of airships, including analysis of deformation and its effect on aerodynamics, spanning 100 years of research, from wind tunnel tests in the early 20th century [16] to computational fluid dynamics (CFD) analysis in the 2000s [17]. We take inspiration from some of the presented methods, especially [18], which we apply to real time simulation of aerodynamically relevant components. We consider these rigid individually, but allow non-rigid interactions on joints between them. Our simulation does not take aerodynamic cross-interactions between individual components into account. However, we argue that these can be approximated by artificially adjusting lift and drag coefficients to minimize the overall modeling error. This could be done, for example, by comparison to CFD analysis of the rigid shape. However, this is not covered by our current work.

More recent work on airships often involve coupling control with perception and computer vision, such as [5, 9, 19, 20]. All of these work makes simplifying assumptions, such as frame rigidity and disregard of wind turbulence.

A novel airship guidance and control scheme was presented in [8], using a backstepping control strategy. Its performance is mathematically proven utilizing a highly simplified analytical plant model under the assumption of rigidity. No real-world experiments have been made. This has inspired some more recent theoretical work on various airship guidance schemes [21, 22]. However, none of it seems to have been validated in real-world flight. In contrast, we base our model on observed real-world flight behavior and validate our results in additional real-world flights.

The airship control problem can also be addressed with a model free or learned-model approach [6, 7]. These techniques are well suited to deal with the dynamics of a deforming vehicle under changing conditions from a control perspective, and can be directly applied to the real world. However, a simulation, as presented in our work, is still required to validate and compare the performance of learned algorithms under controlled, reproducible conditions.

3 Methodology

3.1 Simulation

Gazebo is a physics simulator often used in robotics, which seamlessly integrates with the Robot Operating System (ROS) [12]. Gazebo models rigid physical objects (primitives) based on shape, mass and moments of inertia. Using an XML/URDF description file, these component objects can be described and linked together into hierarchical compound objects. Rigid joints are simulated, using very stiff springs with high damping. These joint parameters can be altered for both linear and rotational freedom. Motion limits, stiffness and dampening properties can be set to simulate non-rigid compound objects. The simulator employs a solver engine to calculate object motions under Newtonian physics, taking all joint forces, collisions and gravity into account. This can be extended through plugins that add additional forces to component objects or joints to model actuators or thrusters. The simulator models time in discrete time steps with configurable temporal resolution and can handle most scenarios in real time with sufficient accuracy. Simulated sensors, which provide simulation data measurements for IMU and positioning sensors as ROS messages are also provided by plugins attached to their respective component objects.

We model a blimp (Fig. 2) as a flexible compound object, consisting of rigid primitive component objects for all actuated and non-actuated components. These are fins, rudders, the gondola, thrusters, ballast weights, etc. We model the main hull with at least two separate components, to allow flexibility of the shape as well as higher granularity of forces during rotations. Plugins are added to these primitives to model buoyancy, aerodynamic forces, control actuation and thrust. This setup allows the physical properties of the blimp to be modeled as the sum of its physical components. Mass, dimensions and inertial moments of homogeneous basic shapes can be easily determined by first principles or by measuring the corresponding part on real hardware.

Fig. 2.
figure 2

Our real-world blimp with our team and the corresponding simulated object.

Buoyancy. Buoyancy is modeled as a single upward force on sections of the hull based on their volume and coefficients. Lift coefficients can be altered at run-time during the simulation, to experiment with the effects of changing buoyancy.

Wind. We model wind as a turbulent flow field, using the Dryden turbulence model (MIL-F-8785C) [13], the implementation of which is from the FlightGear open source flight simulator [3]. It must be noted that this frequency model simulates both the spatial and temporal variability of turbulence in a single, moving point only. As such, we can only calculate a single, time variable global flow vector, which we assume constant in space; the same assumption that was made by FlightGear. For small airships we deem this is an acceptable limitation. This flow vector is published as a ROS message, so it is available to other plugins at any point in time.

Lift and Drag. For all aerodynamically relevant primitive objects, including hull sections, we calculate the local lift and drag forces based on the orientation and motion of the object through the flow field, defined by the current wind flow vector. These are then taken into account by the physics solver to model the effect on the whole vehicle as well as its deformations. We model two types of basic lifting primitives, “quasi-planar” and “quasi-cylindrical”. Let \(\overline{f}\) be the flow vector relative to the primitive, consisting of orthogonal components, \(f_{x}\) from the front, \(f_{y}\) from the left and \(f_{z}\) from above. For quasi-planar types \(f_{y}\) is ignored. Quasi-cylindrical objects are rotated around their x (forward) axis. This yield a rotated flow \(_{r}\overline{f}\) such that

$$\begin{aligned} _{r}\overline{f}=\left[ f_{x},0,\left| f_{y}\right| +\left| f_{z}\right| \right] \end{aligned}$$
(1)

From that point on, they are treated identical to quasi-planar types. We calculate the angle of attack \(\alpha \), the normalized drag vector \(\hat{f}_{d}\), normalized lift vector \(\hat{f}_{l}\) and dynamic pressure \(q_{d}\) as

$$\begin{aligned} \alpha =\arctan \left( \frac{f_{z}}{f_{x}}\right) \text{, } \end{aligned}$$
(2)
$$\begin{aligned} \hat{f}_{d}=\frac{\overline{f}_{d}}{\left| \overline{f}_{d}\right| } \text{ for } \overline{f}_{d}=\left[ f_{x},0,f_{z}\right] \text{, } \end{aligned}$$
(3)
$$\begin{aligned} \hat{f}_{l}=\hat{f}_{d}\times \left[ 0,\frac{\alpha }{\left| \alpha \right| },0\right] \text{, } \end{aligned}$$
(4)
$$\begin{aligned} q_{d}=k\left( f_{x}^{2}+f_{z}^{2}\right) \text{. } \end{aligned}$$
(5)

Let A be the relevant area of the object, given coefficients \(c_{l_{0}}\), \(c_{d_{0}}\), \(c_{d_{1}}\) and \(\alpha _{stall}\). We calculate forces for lift \(\overline{F}_{l}\) and drag \(\overline{F}_{d}\) as

$$\begin{aligned} \overline{F}_{l}=q_{d}A\hat{f}_{l}c_{l} \text{, } c_{l}=c_{l_{0}}{\left\{ \begin{array}{ll} \frac{\left| \alpha \right| }{\alpha _{stall}} &{} \text{ if } \left| \alpha \right| \le \alpha _{stall}\\ \frac{\pi -2\left| \alpha \right| }{\pi -2\alpha _{stall}} &{} \text{ if } \left| \alpha \right| >\alpha _{stall} \end{array}\right. } \text{, } \end{aligned}$$
(6)
$$\begin{aligned} \overline{F}_{d}=q_{d}A\hat{f}_{d}c_{d} \text{, } c_{d}=c_{d_{0}}\left( 1-\frac{2\left| \alpha \right| }{\pi }\right) +c_{d_{1}}\frac{2\left| \alpha \right| }{\pi } \text{. } \end{aligned}$$
(7)

Both functions are highly simplified linear approximations (Fig. 3) of the true lift and drag curves. For each primitive object, only 4 aerodynamic coefficients are needed. The approximate drag coefficients for basic primitive shapes, both for frontal and sideways flow, are commonly known, as are lift coefficients of thin rectangular plates or cylinders. Care has to be taken to adjust the coefficients when nearby primitives interact with each other on a compound object. For example, only the first and last section of the hull would have a high \(c_{d_{0}}\) due to pressure drag, while any intermediate sections would only experience friction drag which typically is an order of magnitude lower. Due to the linear contribution, assuming identical A for n hull sections and frontal flow drag coefficient \(_{H}c_{d}\) for the basic shape, we observe

$$\begin{aligned} \underset{k=1}{\overset{n}{\sum }}{}_{k}c_{d_{0}}={}_{H}c_{d} \text{, } \end{aligned}$$
(8)

and set the coefficients for the hull sections accordingly, weighted by their expected drag contribution.

Fig. 3.
figure 3

Functions for lift and drag coefficients for a simulated object component. These are calculated for each aerodynamically relevant primitive component of the blimp.

As another example, fins attached to the hull might encounter increased lift due to increased dynamic pressure of the airflow around the hull, which can be modeled by artificially inflated lift coefficients for these surfaces.

If an aerodynamic model exists for a specific vehicle, it should be possible to solve for a “best fit” of the primitive coefficients. However, our approach has the advantage that a roughly approximated aerodynamic model can be created based on geometric shape only, which we argue is a valuable property for evaluating new vehicle designs.

Non-rigidity. Gazebo joint properties in compound objects can be manipulated through a ROS service while a simulation is running. We wrote a script that can simultaneously adjust both the rotational and linear spring stiffness, as well as the range of free rotation for all joint connections between the blimp hull and other components such as fins and gondola around all axis of rotation. The same program also adjusts the buoyancy of the blimp. This way, the effects of a drop or increase in lifting gas pressure and volume can be evaluated at any time, both regarding flight behavior and controllability (Fig. 4).

Fig. 4.
figure 4

Deflation of the blimp affects its shape, both in reality and simulation. The hull is visually rendered rigid, but aerodynamically it is simulated in sections. Under their weight, the fins sink into the hull and drag the tail down until the bottom fin carries part of the blimp’s weight. These images show severe deflation for better visibility. Flight in this state would not be possible.

3.2 Control

We employ a cascaded PI controller design similar to the controller presented in [4, 10], with extensions. Librepilot [2, 14] offers a vehicle-agnostic control hierarchy based on virtual control axes, which are mapped to physical actuators through a configurable matrix. This maps a “Pitch” virtual axis on the elevator servos, the “Yaw” virtual axis on both rudder servos and a yaw thruster, as well as a “Thrust” virtual axis on both main thrusters. We decided not to employ main thruster differential thrust for control, due to the low torsional moment and high strain inflicted between gondola and hull. A simple PI control loop controls the yaw rate, while a hierarchical controller with an outer loop proportional term controls the pitch angle based on an PI inner loop controlling pitching rate. Implementations for these already exist and are utilized both for fixed wing and multirotor control.

In extension, we implemented a novel path follower, which determines the setpoints for the lower level control: Pitch P, Yaw rate \(\dot{Y}\), Thrust T and Thrust vector angle \(0\le \gamma \le \frac{\pi }{2}\). Its inputs are a setpoint velocity vector in 3d space \(\overline{v}_{S}\), the airspeed \(v_{I}\), the velocity in 3d space \(\overline{v}=\left[ v_{x},v_{y},v_{z}\right] \) and the current attitude of the vehicle in Euler angles \(q=\left[ q_{r},q_{p},q_{y}\right] \). All the state estimates come from the flight controller’s state estimation using an extended Kalman filter (EKF). If no airspeed sensor is available, \(v_{I}\) is assumed to be the forward component of \(\overline{v}\). We compensated the wind to calculate motion relative to the flow field. Let \(q\left( v_{I}\right) \) be a function that rotates \(v_{I}\) into the world-frame. We then calculate the estimated wind flow vector \(\overline{f}_{l}\) and the corrected velocity in air \(\tilde{\overline{v}}\) as

$$\begin{aligned} \overline{f}_{l}=\overline{v}-q\left( v_{I}\right) \text{, } \end{aligned}$$
(9)
$$\begin{aligned} \tilde{\overline{v}}=\left[ \tilde{v}_{x},\tilde{v}_{y},\tilde{v}_{z}\right] =\overline{v}-\overline{f}_{l} \text{. } \end{aligned}$$
(10)

For each vehicle a minimum controllable airspeed \(v_{min}\) and a maximum achievable airspeed \(v_{max}\) are defined. We solve for a wind-corrected setpoint \(\tilde{\overline{v}}_{S}\)

$$\begin{aligned} \tilde{\overline{v}}_{S}=\left[ \begin{array}{c} \tilde{v}_{sx}\\ \tilde{v}_{sy}\\ \tilde{v}_{sz} \end{array}\right] =b\overline{v}_{s}-\overline{f}_{l} \text{, } {\left\{ \begin{array}{ll} b>0\text{, } \left| b\overline{v}_{s}-\overline{f}_{l}\right| =v_{min} &{} \text{ if } \left| \overline{v}_{S}-\overline{f}_{l}\right| <v_{min}\\ b=1 &{} \text{ if } v_{min}\le \left| \overline{v}_{S}-\overline{f}_{l}\right| \le v_{max}\\ b>0\text{, } \left| b\overline{v}_{s}-\overline{f}_{l}\right| =v_{max} &{} \text{ if } \left| \overline{v}_{S}-\overline{f}_{l}\right| >v_{max} \end{array}\right. } \text{. } \end{aligned}$$
(11)

If the wind is stronger than the vehicle’s maximum speed, there might be no solution with \(b>0\). In this case, the solution with the highest b is chosen, which minimizes the positional error accumulated under these conditions.

Separate controllers are employed for direction \(C_{d}\), airspeed \(C_{v}\), climb rate \(C_{\dot{h}}\) and thrust vector \(C_{\gamma }\). Let be the signed angular difference between \(\overline{a}\) and \(\overline{b}\) while \(\int _{\left\langle \pm l_{i}\right\rangle }\) shall denote an integral accumulator limited by \(\pm l_{i}\). Then

(12)
$$\begin{aligned} P=C_{\dot{h}}\left( \tilde{\overline{v}}_{S},\tilde{\overline{v}}\right) ={}_{P}k_{p}\left( \tilde{v}_{sz}-\tilde{v}_{z}\right) +\int _{\left\langle \pm _{P}l_{i}\right\rangle }\left( _{P}k_{i}\left( \tilde{v}_{sz}-\tilde{v}_{z}\right) dt\right) \text{, } \end{aligned}$$
(13)
$$\begin{aligned} T=C_{v}\left( \tilde{\overline{v}}_{S},\tilde{\overline{v}}\right) ={}_{T}k_{p}\left( \left| \tilde{\overline{v}}_{S}\right| -\left| \tilde{\overline{v}}\right| \right) +\int _{\left\langle \pm _{T}l_{i}\right\rangle }\left( _{T}k_{i}\left( \left| \tilde{\overline{v}}_{S}\right| -\left| \tilde{\overline{v}}\right| \right) dt\right) +{}_{P\times T}k_{p}P \text{, } \end{aligned}$$
(14)
$$\begin{aligned} \gamma =C_{\gamma }\left( \tilde{\overline{v}}_{S},\tilde{\overline{v}}\right) ={}_{\gamma }k_{p}P \text{. } \end{aligned}$$
(15)

The main addition to [4, 10] is the thrust vector term \(C_{\gamma }\) which, in combination with the proportional climb speed cross term \(_{P\times T}k_{p}P\) in \(C_{v}\), employs the main thrusters for altitude control. For a vehicle without thrust vector control, the corresponding coefficients \(_{\gamma }k_{p}\), \(_{P\times T}k_{p}\) would remain 0.

3.3 Middleware

The flight control algorithm is implemented in C/C++ and executed either on a physical embedded flight controller (Openpilot Revolution) [2] on the LTAV, both in flight or for HITL simulation, or compiled as a computer program for SITL simulation. The Librepilot Ground Control Software (GCS) connects to either, using telemetry or networking. The GCS offers a HITL/SITL interface, in which the flight controller’s sensor measurements are overridden with simulated data and actuator commands are sent to the simulator. We extended this interface, in order to connect with ROS, and as such our Gazebo simulation. We also wrote additional software that interfaces with the flight controller directly (via USB or Networking) and allows HITL/SITL without the GCS. Its main purpose however, is to send sensor and state estimate data to ROS components running on board and in flight. In turn ROS can send the flight controller guidance setpoints. This facilitates high level autonomous control, such as vision or perception based algorithms, through ROS. Of course, these components are useful beyond their application for airships.

3.4 Robotic Hardware

We equipped a commercial \(5\,\text{ m }\) blimp (Fig. 2) (CloudMedia Sopot, Sopot, Poland), designed for advertising and aerial photography, with an Openpilot Revolution flight controller (including an IMU, 3 axis magnetometer, barometer and processor), a GPS receiver, a digital airspeed sensor, and an onboard computer for data logging and wireless networking. All sensors and the flight controller have been installed on the top vertical tail fin, to avoid electromagnetic interference. The main computer, a NVIDIA Jetson TX1, is installed in the gondola and connected with a lightweight USB cable. Telemetry is relayed to the ground via 5 GHz WiFi using the main computer’s inbuilt transceiver. The blimp can be flown manually using a Graupner flight control transmitter (TX), a matching receiver is connected to the flight controller. Autonomous flight modes are engaged using switches on the TX. The blimp has 8 independently controllable actuators: i) Bottom fin lateral thruster (propeller with forward and reverse thrust), ii) Top rudder (servo), iii) Bottom rudder (servo), iv) Left elevator (servo), v) Right elevator (servo), vi) Thrust vector control axis (servo), vii) Left main thruster (forward and reverse thrust), viii) Right main thruster (forward and reverse thrust). This vehicle has a mass of \(10\,\text{ kg }\) including a payload or ballast of approximately \(1\,\text{ kg }\).

3.5 HITL

In our HITL setup, all flight control computation is done on board the embedded flight computer on robotic hardware. Servos are physically actuated, while thrusters are left unpowered for safety reasons. The value of each actuation channel is also sent via USB telemetry to the Gazebo simulator and simultaneously applied to virtual actuators in the simulation. Simulated sensor data generated by the simulation is sent back over the same telemetry link and supersedes all on board sensors, including IMU and GPS. The measured time delay induced by sending sensor data over USB is less than \(0.5\,\text {ms}\) and therefore negligible. The physical sensors on the flight controller are read out at a fixed rate of \(500\,\text {Hz}\). For accurate HITL simulation this rate must be matched by the simulators physics engine for the simulated sensors, with Gazebo this is possible on sufficiently fast hardware.

4 Experiments and Results

We conducted several experiments, both in simulation as well as real-world validation.

4.1 Simulation Experiments

Simulation Experiment 1 - Manual Simulated Flight - Based on data from physical measurements and observations of a tethered real-world test flightFootnote 2, the simulation model was configured and tested in manual simulated flight. Unknown coefficients were adjusted until simulation and reality were in qualitative agreementFootnote 3.

Simulation Experiment 2 - Loitering - The control algorithm was implemented and control parameters were tuned in simulation, starting with the lowest level control loop. Given manual setpoint inputs, P and I rate control coefficients were determined for pitch and yaw rate, followed by P coefficient for the pitch control loop. When these were satisfactory, the \(C_{d}\) control loop was tuned, followed by \(C_{\dot{h}}\), \(C_{v}\) and \(C_{\gamma }\). We then followed an iterative tuning procedure, while the simulated blimp was constantly loitering around a position \(P_{0}\). Given current position estimate P, the velocity setpoint is calculated as

$$\begin{aligned} \overline{v}_{S}=k\left( P_{0}-P\right) \text{. } \end{aligned}$$
(16)

With the simulated blimp loitering, the performance in each controlled domain was monitored and control coefficients for whichever parameter (speed, altitude, course) was deemed worst were adjusted until satisfactory results were achieved (Fig. 5).

Fig. 5.
figure 5

Simulation experiment 2 - The simulated blimp loiters around a given position. Without wind, the steady state becomes a circle at airspeed \(v_{min}=1\,\text{ m/s }\) and at the minimum possible turn radius. The turn rate throughout all experiments was limited at .

Simulation Experiment 3 - Trajectory Following - We employ the path planner in Librepilot to follow a waypoint sequence with 4 waypoints. We denote \(\hat{p}=\frac{\overline{p}}{\left| \overline{p}\right| }\) as the notation for a normalized vector. For any pair of consecutive waypoints \(P_{0}\), \(P_{1}\) and desired velocity \(v_{0}\), we determine \(\overline{v}_{S}\) via

$$\begin{aligned} \overline{p}_{a}=P-P_{0} \text{, } \end{aligned}$$
(17)
$$\begin{aligned} \overline{p}_{b}=P_{1}-P_{0} \text{, } \end{aligned}$$
(18)
$$\begin{aligned} \overline{v}_{S}=v_{0}\hat{p}_{b}+k\left( \overline{p}_{b}\left( \overline{p}_{a}\cdot \hat{p}_{b}\right) -\overline{p}_{a}\right) \text{. } \end{aligned}$$
(19)

In Eq. (19) the term \(v_{0}\hat{p}_{b}\) moves the vehicle along the desired path vector, while the second term corrects any orthogonal deviance from the path, as \(\overline{p}_{b}\left( \overline{p}_{a}\cdot \hat{p}_{b}\right) \) projects \(\overline{p}_{a}\) on \(\overline{p}_{b}\). This guidance scheme allows observations of the control behavior in steady state, while the vehicle follow a reproducible trajectory repeatedly (Fig. 6).

Simulation Experiment 4 - Wind and Turbulence - We added wind and turbulence to situations from both simulation experiments 2 and 3 and observe the effects. Wind velocities between \(v_{min}\) and \(v_{max}\) allowed the simulated blimp to hover on the spot with good accuracy. We noted altitude excursions of several meters due to vertical wind gust components. During the trajectory following, wind from the rear poses a challenge if \(v_{min}\) is set too low, as the blimp is almost stationary in relation to the air-stream. Consequently, the control surfaces have very limited authority. This led to a noticeable overshoot of waypoints due to the time it took for the blimp to reorient. This can be alleviated by commanding a higher \(v_{min}\) (Fig. 7).

Fig. 6.
figure 6

Simulation experiment 3 - The simulated blimp follows a waypoint sequence at a commanded speed of \(2\,\text{ m/s }\).

Fig. 7.
figure 7

Simulation experiment 4 - Navigating in wind poses a challenge for the simulated blimp, as the simple action of turning around after an overshoot leads to significant drift downwind. However, with the wind speed between \(v_{min}=1\,\text{ m/s }\) and \(v_{max}=2\,\text{ m/s }\) the blimp manages to hover in close proximity of the reference point. The “random walk” is an effect of turbulent fluctuations in wind speed and direction. When navigating a waypoint sequence, the ground speed is severely increased on the downwind leg, even at an airspeed of \(v_{min}\), resulting in large turn radii and overshoot. On the upwind leg the ground speed is greatly reduced, coming to a near halt during strong gusts. The gusty wind poses challenges to the blimp’s ability to maintain altitude, vertical gust components cause severe altitude excursions of several meters which the blimp then compensates to the best of its abilities. These are reproducible regardless of the guidance mode, leading to similar excursions at the same time in each experiment, whenever the same wind gusts are encountered. Simulated wind is coming from south-east (135°) with an average velocity of \(1.5\,\text{ m/s }\), simulated turbulence for the Dryden model was set to magnitude 3.

Simulation Experiment 5 - Deflation - We re-conducted both simulation experiments 2 and 3. During the experiment we adjusted the rigidity of the simulated blimp to simulate helium loss and observe the effects. Simulated loss of hull pressure and the resulting decrease in rigidity reduced the controllability of the blimp. A reduction in altitude accuracy and oscillations in both pitch, altitude and also in course were observed. The ability of the fins to flex and twist in response to control actuation not only adds additional oscillation modes, especially for the top fin which houses the IMU (both in simulation and on the real-world blimp), it also reduces the control effects, since the fins rotate in response to the control forces until a new force equilibrium is reached. This significantly reduces the overall control force enacted on the hull, since the angle of attack of the fin and attached rudder negate each other. Nevertheless, the blimp remains controllable, as long as sufficient buoyancy is present to maintain altitude (Fig. 8).

Fig. 8.
figure 8

Simulation experiment 5 - The simulated blimp was partially deflated at the half time mark of each experiment (“deflate_blimp.sh /blimp 8 0 0.2 .95”). In the loiter experiment, this exposes a severe oscillation instability in altitude and pitch that was not present when fully inflated, although the blimp is still able to control itself. In both situations, the altitude accuracy is noticeably decreased. In this plot, the yaw gyroscope signal is plotted, revealing a high frequency oscillation in yaw, as the actuation of the rudder now moves the fin that the simulated gyroscope is mounted to, relative to the blimp.

Fig. 9.
figure 9

Real-world experiment - The blimp loiters around a given position in the real world, while losing helium. The winds were benign, but a single gust at the \(160\,\text{ s }\) mark results in a noticeable drop in altitude which the control subsequently corrected, similar to those seen in simulation experiment 4. Due to lack of functional airspeed sensor and higher than tuned-for thrust, the ground speed and turn radius are larger than in the simulation. As predicted in simulation experiment 5, the blimp displays pitch-altitude oscillations throughout the flight. A high frequency oscillation in the yaw axis was also present (drawn down-scaled by factor 100), as predicted.

4.2 Real-World Experiment

Loitering Outdoor with Wind and Deflation - We configured the real-world blimp with the control coefficients determined in simulation and engaged position hold mode. Due to a previous ground test incident, the hull had developed significant leakage. As such we were able to reproduce the effects in simulation experiment 5 in real-world, with the blimp’s internal pressure far below optimum and dropping. Although we were able to maintain buoyancy by removing ballast weights, the blimp’s flight performance was below optimal. As predicted in simulation experiment 5, a high frequency oscillation developed in the yaw axis. The rudder actuation imparted momentum and flexion on the top fin which was picked up by the IMU gyroscope. The real-world blimp was flown with identical control coefficients to those used in simulation experiments. However, due to changes on the electronic speed controller (ESC), the blimp produced higher thrust than anticipated. This might have contributed to oscillations in pitch and altitude, which were similar, but more persistent and of higher frequency than those observed in simulation experiment 5. Our airspeed sensor failed to work and had to be deactivated, leading to \(v_{I}\) estimated based on ground speed, but we expect minor impact due to the benign winds that day (\({<}1\,\text{ m/s }\) average). The altitude and position were controlled reliably for more than 5 min of continuous flight time. One observed wind gust caused an altitude excursion, as predicted by simulation experiment 4. No intervention by the pilot was required at any time (Fig. 9)Footnote 4.

4.3 Discussion

Our experiments have confirmed that changes in rigidity, as simulated in our framework, have significant effects on behavior and control of airships, which is well documented by the literature [11]. Modeling of wind gusts has also exposed notable control behavior, not seen in non-turbulent air. We have shown that a simulation framework as presented here can be used to develop, tune and evaluate a control algorithm with results comparable to and representative of the real world, with limitations discussed below.

5 Limitations

Very large airships would benefit from wind and turbulence simulation, that accurately models local variations of the wind flow at the same point in time. This would require the wind model to be modified, to estimate a whole wind field and calculate the wind vector as a function of both space and time for multiple places. Due to our modular aerodynamics approach, it would be relatively straightforward to incorporate this data into a simulation with a sufficiently segmented hull, although this is beyond the scope of our current work.

Our current simulation is not quantitatively accurate for our vehicle and we cannot accurately estimate the simulation to real-world discrepancy. To achieve quantitative simulation accuracy, or to analyze the simulation error made by the model, it would be necessary to compare the calculated forces to those determined in wind tunnel tests of CFD analysis. The latter could be done with acceptable effort for the rigid case only. Based on this analysis, “best fitting” coefficients on all component objects could be determined, to minimize the simulation error. This would also show, if additional correction coefficients are needed to model aerodynamic interaction between different components, or if the current set of coefficients in combination with higher granularity is sufficient. Lacking ground truth aerodynamic data, we have to defer this to future work.

Our current aerodynamic model can not model “prop wash” and the effects it has on impinged control surfaces and fins. This should be addressed by future work to improve the blimp simulation, although solving this would also be beneficial for other vehicles such as multicopters and fixed wing.

Although our model can simulate deformations of the hull as a whole, it can not model surface deformations of the skin such as wrinkling or denting. Temporary changes of the geometric shape of a component could have significant effects on the drag coefficient as mentioned in [11]. These have been observed to occur in our real-world experiment. Although we could dynamically adjust the aerodynamic coefficients of component objects in the simulation, this would require knowledge of the relationship between aerodynamic forces, internal pressure, shape and effects on aerodynamics. This is a hard problem and has not been well researched yet, as noted in [11]. It justifies future work.

6 Summary

We have created a solution for SITL and HITL simulation as well as a control algorithm, which allows researchers to set up and fly LTAVs with the same tools and flight electronics that have been used for years with fixed wing and multicopters. The seamless integration with ROS and Gazebo incorporates airship support into popular robotic tool chains. As such, this work should facilitate a significant reduction of the gap between heavier- and lighter-than-air UAV robotics. Although LTAVs can be cumbersome to work with due to size and lifting gas handling, turning them into autonomous research platforms is now straightforward. Researchers can attach a COTS flight controller and run freely available open-source tools on any flight hardware. This had previously been possible only for heavier-than-air craft.

We have shown that modeling both wind turbulence and deformation is crucial for realistic simulation of LTAVs. Rigid models in non-turbulent air can not predict important aspects of the vehicle’s behavior.

We presented a reproducible approach for modeling non-rigidity in simulation, in combination with wind turbulence. This allows researchers to test, evaluate, or, in case of learning algorithms, to “train” control algorithms under these conditions. The simulation environment is well suited for multi vehicle experiments and allows research on mixed formations involving both ground robots, heavier-than-air and LTAV. Although our current simulation models a specific blimp, it is straightforward to modify the configuration for other LTAVs. Only the robot XML/URDF configuration has to be changed.

The authors consider this work to be the foundation for their own future lighter-than-air research and hope the scientific community will find it useful as well.