Available via license: CC BY 4.0
Content may be subject to copyright.
Design, Modeling and Control for a Tilt-rotor VTOL UAV in the
Presence of Actuator Failure
Mohammadreza Mousaei, Junyi Geng, Azarakhsh Keipour, Dongwei Bai, and Sebastian Scherer
Abstract— Enabling vertical take-off and landing while pro-
viding the ability to fly long ranges opens the door to a wide
range of new real-world aircraft applications while improving
many existing tasks. Tiltrotor vertical take-off and landing
(VTOL) unmanned aerial vehicles (UAVs) are a better choice
than fixed-wing and multirotor aircraft for such applications.
Prior works on these aircraft have addressed the aerodynamic
performance, design, modeling, and control. However, a less ex-
plored area is the study of their potential fault tolerance due to
their inherent redundancy, which allows them to tolerate some
degree of actuation failure. This paper introduces tolerance to
several types of actuator failures in a tiltrotor VTOL aircraft.
We discuss the design and modeling of a custom tiltrotor VTOL
UAV, which is a combination of a fixed-wing aircraft and a
quadrotor with tilting rotors, where the four propellers can
be rotated individually. Then, we analyze the feasible wrench
space the vehicle can generate and design the dynamic control
allocation so that the system can adapt to actuator failures,
benefiting from the configuration redundancy. The proposed
approach is lightweight and is implemented as an extension to
an already-existing flight control stack. Extensive experiments
validate that the system can maintain the controlled flight under
different actuator failures. This work is the first study of the
tiltrotor VTOL’s fault-tolerance that exploits the configuration
redundancy to the best of our knowledge.
I. INTRODUCTION
Unmanned Aerial Vehicles (UAVs) have gained lots of
interest in recent years in various applications, such as
autonomous aerial cinematography [1], 3D mapping and
photography [2], aerial manipulation, and physical inter-
action [3], [4] due to their versatility. UAVs with fixed
rotors (e.g., multirotors) have vertical take-off and landing
(VTOL) capabilities. However, due to the significant thrust
required to counter the gravity, they are inefficient in the
forward flight. On the other hand, fixed-wing vehicles (e.g.,
airplanes) are very efficient in forward flight and can fly
much longer ranges than multirotors. However, they lack
VTOL capabilities and usually require runways for take-off
and landings, and they cannot hover in the air. As the third
class, VTOL hybrid or convertible UAVs combine VTOL
capabilities with efficient forward flight by using propellers
to hover, take-off, and land vertically, and wings for efficient
long-range cruising.
In general, there are three main types of VTOLs: tailsitters,
tiltrotors, and standard VTOLs. However, it is challenging
to balance the configuration complexity and the control
simplicity. For example, although standard VTOLs are the
Mohammadreza Mousaei, Junyi Geng, Azarakhsh Keipour, Dongwei Bai,
and Sebastian Scherer are with the Robotics Institute, Carnegie Mellon
University, Pittsburgh, PA 15213, USA. {mmousaei, junyigen,
akeipour, dongweib, basti}@andrew.cmu.edu
Fig. 1: Tiltrotor VTOL aircraft designed in this work with four
rotors, four tilting mechanisms, two ailerons, one elevator, and one
rudder. The quadrotor arms have airfoil cross-sections.
easiest to control, they add additional weight from separate
hover/forward flight propulsion systems. Tailsitter VTOLs
have the minimum set of actuators; however, they can be
hard to control, particularly in the wind. As for the tiltrotors,
they are easier to control in hover than tailsitters due to
more control authority, but the additional tilting mechanism
increases the system’s complexity.
Safety requirements have become more and more critical
as the number of operating UAVs grow. To safely integrate
UAVs into the airspace and for real-world applications, the
aircraft should maintain controlled flight even when actuator
failure happens, with a subsequent fail-safe mechanism,
i.e., return-to-home or emergency landing. Hence, the flight
control system must be able to tolerate some degree of
failure. In general, such kind of control system with the
fault-tolerant ability can either be achieved by designing the
controller in a robust manner [5], [6] or by dynamically
adapting the controller to the detected failure. While the
former usually requires a complete redesign based on the
aircraft configuration, the latter requires additional fault
detection and identification. This paper focuses on the latter
option, assuming that the system failure can be quickly
detected and identified so that the existing autopilots with
more powerful flight stacks can be used with a minimum
amount of further development. Real-time failure detection
methods for aircraft already exist that can provide the failure
status almost immediately after the failure happens [7], [8].
There are many ways to handle actuator failures depending
arXiv:2205.05533v1 [cs.RO] 11 May 2022
on the aircraft’s configuration. Multirotors with less than
six propellers are still able to fly after the loss of one
or more propellers [9]. However, with a failed motor they
cannot statically hover and can only keep the position while
rotating in-place around the gravity vector. This concept
of dynamic hovering can be an acceptable compromise if
the flying space is not constrained and if the perception
system can still operate in such conditions. It has been
shown that six rotors are required at minimum to achieve
static hovering robustness to a motor failure [10]. In par-
ticular, only star-shaped hexarotors with tilted propellers
and Y-shaped hexarotors can achieve static hovering robust-
ness [11]. On fixed-wing aircraft, exploiting aerodynamic
effects for passive stability or utilizing actuator redundancy
for failure adaptation are the possible ways to achieve fault-
tolerance [12]. As for the hybrid VTOL UAVs, although the
existing works addressed the aerodynamic performance [13],
design [14], [15], modeling [16] and control [17], [18], fault-
tolerance is less explored. Due to the hybrid configuration
design, VTOLs have configuration redundancy. However, the
research utilizing redundancy to address actuator failures is
minimal. The authors of [19] investigate the fault-tolerant
flight control of a tailsitter VTOL. Aerodynamic passive
stability and control allocation adjustment are exploited to
achieve the fault-tolerant system performance.
This paper introduces tolerance to several types of actuator
failures in a tiltrotor VTOL aircraft. The model and design
of a custom tiltrotor VTOL are discussed, which combines
a fixed-wing aircraft and a variable-pitch quadrotor UAV.
The direction of the four propellers can be individually
controlled. Different from the tilting design of [16] with
an additional arm length, twin-rotors [20] or other tilting
multi-rotors [21], our quadrotor arms are entirely separated
from the main wing, which makes the control less affected
by the unexpected wing deformation. In addition, our tilting
mechanism directly tilts the rotors at the end of the quadro-
tor arm. Moreover, the quadrotor arms have airfoil cross-
sections, which can provide additional lift for the vehicle
during forward motion. We model the nonlinear dynamics of
this tiltrotor VTOL and analyze the feasible wrench space the
vehicle can generate. Then, we design the dynamic control
allocation that allows the system to adapt to the potential
configuration changes in real-time. This dynamic control
allocation benefits from configuration redundancy to make
the aircraft robust to actuator failures. By solving a constraint
optimization problem under a carefully designed objective,
the aircraft can recover from a set of actuator failures in
different flight phases of the VTOL.
Our main contributions include: leftmargin=*
1) Proposing a dynamic control allocation method that
allows the system to adapt to actuator failures. The
proposed approach is light-weight and can be quickly
extended on an already-existing flight control stack;
2) Designing and modeling a tiltrotor VTOL with the
ability to rotate each individual propeller;
3) Validating the system performance under the set of
possible actuator failures in different flight phases;
Fig. 2: Rotation mechanism in three different positions.
4) Providing the source code for the proposed strategies
implemented on the PX4 flight controller firmware
along with our simulation environment.
II. SYS TEM OV ERVIE W
This section presents the designed aircraft and its avionics
system.
A. Vehicle Design
The aircraft has two streamlined airfoil tubes integrated
vertically into the fuselage as the quadrotor arms. Different
from the design of [16] that has the quadrotor arms parallel to
the fuselage, our design makes the arm completely separate
from the main wing. This provides several advantages: (1)
the control authority of the tiltrotor gets less affected by the
unexpected wing structure deformation; (2) the tilt mecha-
nism can be directly attached to the end of the arm without
a conflict with the structure; (3) the airfoil cross-section of
the arm provides additional lift to the aircraft. We attach
four brushless electrical motors directly to the arms’ ends,
where they can drive a 12.5" propeller and provide 27.36 N
at 100% throttle. The component that connects the motor and
propeller to the fuselage is the rotation mechanism powered
by an MG996R servo which has a maximum rotation angle of
180° and enables the propeller to tilt forward and backward,
as shown in Fig. 2.
A set of wings with a wingspan of 2 m is attached to
the fuselage. The elevator and rudder are mounted to the
extended structure from the fuselage. A 16000 mAh 6S LiPo
battery is used and mounted on the fuselage. Fig. 1 shows
the aircraft with its avionics.
B. Avionics
A cube orange flight controller [22] is the core of the
avionics. It features three inertial measurement units (IMUs),
an integrated accelerometer, a barometer, a gyroscope, and
a 400 Mhz 32-bit ARM Cortex-M7 processor. Long-range
telemetry, a differential pitot tube, and a GPS are connected
to the cube orange to provide communication, airspeed, and
position updates. The Extended Kalman Filter (EKF) of the
PX4 open source firmware [23] performs sensor fusion to
estimate the aircraft states and enable automatic control.
III. MOD EL
This section briefly describes the definitions and the math-
ematical model of our VTOL system used for control. A
more detailed model is discussed in [16].
A. Definitions
The inertial frame is defined as FI={OI,ˆen,ˆee,ˆed},
where OIis the 3-D origin point, and ˆen,ˆee, and ˆedare the
unit vectors pointing to the North, East and Down directions.
The body-fixed frame is defined as FB={OB,ˆex,ˆey,ˆez},
where OB=pis the position of the vehicle’s center of
mass in the inertial frame, and ˆex,ˆey, and ˆezare the unit
vectors pointing to the front, right and bottom directions of
the vehicle, respectively. The wind frame is defined as FW=
{OW{ ,ˆxw,ˆyw,ˆzw}where OW{ is arbitrary, the ˆxwaxis is
in the positive direction of the vehicle’s velocity relative to
the wind, ˆzwis perpendicular to ˆxwand positive below the
vehicle, and ˆywis perpendicular to the ˆxwˆzwplane following
the right-hand rule. The angle of attack αis the angle of the
velocity vector with the ˆxwˆywplane, and the sideslip angle
βis the angle between the velocity vector and the projection
of the vehicle’s longitudinal axis to the ˆxwˆywplane. RB
I
and RI
Bdefine the rotations from FBto FIand FIto FB,
respectively.
As described in Section II, the system has 12 actuators that
can be described using a set of parameters. The deviation an-
gles of the left and right ailerons from the neutral position are
δa1and δa2, respectively. The elevator and rudder deviation
angles from their neutral positions are described by δeand
δr. The rotation velocity of the ith rotor is represented by
ωi. Finally, the rotation angle for each rotor iis described
by χi. Angle χiis designated as the rotation angle of the
ith rotor’s axis with −ˆezaround the −ˆeyaxis. Therefore, χi
will be zero when the ith rotor is pointing upward and π
2
when they are pointing to the front of the vehicle. All angles
are described in radians.
Finally, the thrust and torque generated by the ith rotor
are defined as Tiand τi, the unit vector in the direction
of Ti(rotor axis) is ˆuiand the vector from the body-
fixed origin (i.e., the center of mass) to the base of the
ith rotor arm is defined as rB
i. Assuming that all rotors are
similar, the magnitude of the thrust Tiand torque τican be
approximated as:
kTik=Ti=cFω2
i
kτik=τi= (−1)dicKω2
i
,(1)
where cF>0and cK>0are the thrust and torque constant
coefficients of the rotors, and di={0,1}is the rotation
direction of the ith rotor around its axis (i.e., clockwise or
counter-clockwise).
B. Forces
Three main forces are applied to the VTOL: gravitational,
thrust, and aerodynamic. We describe these forces in the
body-fixed frame FBfor convenience.
Given the total mass of the vehicle as m, the gravitational
force is:
FB
g=RB
I
0
0
mgˆed
(2)
The thrust forces are the result of the thrusts generated by
the propellers. Assuming a negligible induced drag, for the
total thrust force we have:
FB
r=
4
X
i=1
TB
i=
4
X
i=1
TiˆuB
i=cF
4
X
i=1
ω2
i
sin χi
0
−cos χi
(3)
The aerodynamic forces are the forces exerted on the robot
by the air and can be expressed as:
FB
a=RB
W
XW
YW
ZW
(4)
where we have:
XW= ¯qSCX(α, β)(Drag Force)
YW= ¯qSCY(β)(Lateral Force)
ZW= ¯qSCZ(α)(Lift Force)
(5)
In this equation, Sis the wing surface area and ¯q=
ρV 2
a/2is the dynamic pressure, where ρis the air density
and Vais the airspeed. The lateral force is negligible (i.e.,
CY≈0) during the typical cruise flight. For the lift and drag
coefficients we have:
CX(α, β)≈CD,0+CD,αα2
CZ(α)≈CZ,0+CZ,αα(6)
where CD,0and CD,α are the coefficients of parasite drag
and induced drag, and CZ,0and CZ,α are the lift coefficients,
and all are usually obtained from wind tunnel tests.
The total forces applied to the VTOL are calculated as the
sum of all three force types:
FB=FB
r+FB
a+FB
g(7)
C. Moments
There are several types of moments affecting the VTOL
vehicle. However, in reality, the gyroscopic torques can
be ignored for normal steady operations. Therefore, the
principal moments applied to the VTOL are thrust, resisting,
and fixed-wing aerodynamic moments.
Thrust moments are the result of the rotor thrust being
applied at an offset from the center of mass. These moments
can be calculated as:
MB
r=
4
X
i=1 rB
i×Ti(8)
Resisting moments are the result of rotor rotation and rotor
arm rotation applying the opposite rotation moments to the
robot’s body. If we assume the effect of the rotor arm rotation
is small, the resisting moments can be computed as:
Fig. 3: Visualization of the tiltrotor VTOL’s feasible wrench sets. MC stands for multirotor and FW stands for the fixed-wing configuration.
The wrench sets are computed around the trimmed condition for fixed-wing.
MB
g=
4
X
i=1
τB
i=cK
4
X
i=1
(−1)diω2
i
sin χi
0
−cos χi
(9)
Aerodynamic moments are the moments exerted on the
aircraft in fixed-wing configuration:
MB
a=
LB
MB
NB
(10)
where for a cruise flight with small slide slip angle and
angular rate, it can be approximated as:
LB≈¯qSbCLaδa
MB≈¯qS¯cCM eδe
NB≈¯qSbCN rδr
(11)
In this equation, Sis the wing surface area, ¯qis the
dynamic pressure, ¯cis the mean aerodynamic chord, and bis
the wingspan. CLa is the effectiveness of the aileron, CMe is
the effectiveness of the elevator, and CNr is the effectiveness
of the rudder. These coefficients are usually obtained from
wind tunnel test data.
Finally, the total moment is calculated as:
MB=MB
r+MB
g+MB
a(12)
IV. FEASIBLE WRENCH SPACE
This section aims to perform the wrench space analysis for
the tiltrotor VTOL and find their correspondence for different
flight configurations.
From Eq. 7 and Eq. 12, it can be seen that generally the
total wrench WB= [MB,FB]>is nonlinear with respect to
the actuator inputs u. In other words, FB=f(u),MB=
g(u)except in multirotor configuration, where WBbecomes
linear with respect to u(notated as FB=Fmu,MB=
Gmu). Let us assume that each entry of the input uis limited
with the lower and upper bound to be umin and umax, i.e.,
u∈U= [umin, umax ], where Uis the set of feasible inputs.
Then, the feasible wrench set is defined as the image set of
Uthrough the nonlinear map h(·):
W={w∈Rn| ∀u:w=h(u)}.(13)
Following this definition, the sets of feasible inputs at steady-
state operation, as the sets of control inputs that can maintain
the hover and cruise are defined as:
Uh={u∈Rn|u:||Fmu|| ≥ mg}(14)
Uc={u∈Rn|u:fx(u)≥0}(15)
where fx(·)is the x-component of the result vector. Feasible
wrench sets at hover or cruise W·+are defined as the image
set of U(·)through the mapping h(·). Note that W·+∈ W
since U(·)∈U.
A. Static Hovering
The vehicle is capable of static hovering when it can reach
and maintain a constant position and orientation, i.e.,
˙
pB→0,ωB→0(16)
Ref. [10] has proved that the following conditions are re-
quired for keeping the static hovering ability
rank{Fm}= 3 (17)
∃u∈int(U)s.t. ||Fmu|| ≥ mg
Gmu=0(18)
where int denotes the interior of U.
It is clear that the aircraft can statically hover if and only if
0∈int(Wh+). If the origin is on the boundary or is outside
of Wh+, the aircraft cannot statically hover since the system
will not be robust to disturbance.
B. Cruise Flight
The vehicle is able to keep cruise flight in the fixed-wing
configuration when it can keep the constant altitude, heading
and forward speed, i.e.,
¨
pB
x→0,˙
pB
z→0,˙
ψ→0(19)
Fig. 4: VTOL control diagram with dynamic control allocation.
The wrench needs to satisfy the following condition to keep
cruise flight:
∃u∈int(U) & s.t.
fx(u)≥0
fz(u)≥mg
g(u) = 0
(20)
VTOL’s steady state ability can be seen from the feasible
wrench set (see Fig. 3 (a) and Fig. 3 (c)).
C. Actuator Failures
This section highlights the effect of actuator failure on the
VTOL’s steady-state capability. Here, the actuator failure can
be a motor failure, a servo tilt failure, or a control surface
failure. We denote kW·+the feasible wrench set at steady-
state when the kth actuator fails.
Fig. 3(b) and Fig. 3(d-f) show the wrench space when
a motor fails at hover or cruise flight or a control surface
fails at cruise flight.1We can see that a single motor failure
causes a significant cutoff of the feasible wrench space
for both the multirotor and fixed-wing configurations. The
payload capacity was clearly reduced (see the force). When
the elevator or the aileron fails, the range of Myor Mxgets
narrowed. In fact, the elevator is the main pitch (My) control
authority while the aileron controls the roll motion (Mx).
V. NOMINAL CO NTRO L
This section describes the actuation principles and the
control diagram of the nominal flight case without any
actuator failures.
A. Nominal Actuation Principle
Our tiltrotor VTOL control scheme consists of a multirotor
mode and a fixed-wing mode, either running separately
in the corresponding VTOL phases or together during the
transition. The vehicle starts with the multirotor phase, in
which the UAV takes off vertically and keeps hovering at
the desired altitude. Then, when a transition is triggered,
the vehicle speeds up laterally and tilts the rotors to make
them face forward. The transition phase ends when the
vehicle gains enough airspeed and fully tilts the rotors. The
1The wrench space for the tilt failure is not shown here due to its
similarity to a motor failure.
vehicle subsequently stays in the fixed-wing phase for the
rest of the flight until it transitions back to hovering and the
multirotor phase for a vertical landing. Note that the specific
VTOL attitude control facilitates the necessary switching and
blending logic for multirotor and fixed-wing modes during
the transition phase.
B. Dynamic Control Allocation
Although PX4 provides the off-the-shelf controller for this
type of aircraft, it usually needs to load the proper mixer files
to map the desired control wrench to each actuator input,
which can only handle the aircraft with a fixed configuration.
Instead, we developed a dynamic control allocation scheme,
so it adapts to a potential vehicle configuration change,
such as an actuator failure. Therefore, the modified control
diagram becomes like Fig. 4.
Given the desired control wrench WB, i.e., the force and
torque from the velocity and angular rate controllers, the
goal is to allocate them to each of the actuators based on the
current states and the aircraft configuration. We formulate a
constrained optimization problem to perform this allocation.
Specifically, in the transition and fixed-wing phases, we
linearize h(·)with respect to the trimmed vehicle state based
on the small perturbation theory.
FB=FB
trim +FB
∆,MB=MB
trim +MB
∆(21)
A first-order perturbation is used to approximate the pertur-
bation:
FB
∆=∂f (u)
∂u|x0,u0∆u,MB
∆=∂g(u)
∂u|x0,u0∆u(22)
where x0,u0represent the trimmed state and the input.
Therefore,
WB=
MB
∆
· · · · · ·
FB
∆
=A∆u(23)
with
A=
∂g(u)
∂u|x0,u0
·········
∂f (u)
∂u|x0,u0
(24)
as the control allocation’s effectiveness matrix. For the tiltro-
tor VTOL UAV with more actuators than required, the system
is overdetermined with infinite number of solutions. The
least-norm solution minimizes the total actuator effort while
satisfying the force and moment constraints (see Eq. 23).
It can be computed by the pseudo-inverse of A. Actuator
outputs that exist in the null space of Aare utilized to
satisfy other constraints, such as the actuator limits to avoid
saturation. Therefore,
∆u= ∆uLN + ∆uNull (25)
where
∆uNull =˜
Aλ(26)
Here, A∆uNull = 0.˜
Ais the matrix which columns are the
basis of the null space of A.λis the coefficient of ˜
A, which
TABLE I: Actuator failure cases in different VTOL flight phases.
Flight Phase Failure Description Cause
Multirotor Lock of one tilt in hover Broken servo
Single motor failure in hover Motor flaw/propeller loss
Fixed-wing
Single motor failure in cruise Motor flaw/propeller loss
Lock of one elevator in cruise Broken servo
Lock of one aileron in cruise Broken servo
†We consider the failures in the multirotor and fixed-wing cruise flight phases
since most of the flight stays in those two phases.
will be solved by the following optimization problem:
min
λJ(usp)(27)
s.tumin,i ≤usp,i ≤umax,i
where usp is the overall control setpoint:
usp =u0+ ∆u(28)
J(·)is the objective function where we try to minimize
actuator change from the trimmed condition,
J= (usp −usp,trim)>R(usp −usp,trim )(29)
where Ris the weight matrix that accounts for the contri-
bution from different actuators. The inequality constraints of
the problem (see Eq. 27) ensure that the output is within the
actuators’ limits, where irepresents the ith actuator.
VI. CON TROL I N ACTUATO R FAILURE
In this section, we analyze the effect of a set of actuator
failure cases (see Table. I). We then propose changes to
the nominal control to enable the system’s recovery from
failures.
For the tiltrotor VTOL designed in Sec.II, there are 12
actuators to control the six degrees of freedom (6 DOF)
rigid body motion. The system, therefore, has 6 DOF control
redundancy. This redundancy enables the system to handle
the actuator failure. For example, suppose one of the motors
fails in the multirotor phase. In that case, the tilts can be
active and compensate for this failure with different rotor
speeds and thrust directions, enabling the aircraft to maintain
its flight. Alternatively, suppose the elevator gets locked
during the fixed-wing cruise flight. In that case, although
the aircraft loses some degree of pitch control authority for
the fixed-wing configuration, the combination of multirotor
and tilts can compensate for it. Therefore, we adjust our
nominal control allocation to adapt to the actuator failure
as long as the control wrench is within the feasible wrench
space discussed in Sec. IV.
We denote by kAthe control effectiveness matrix in
which the kth column of Ahas been zeroed or equivalently,
removed. Such matrix represents the control effectiveness
matrix of the tiltrotor VTOL in which the kth actuator does
not work anymore after a failure. In other words, uk=uf
for the tilt lock or control surface (aileron or elevator) lock
scenarios, where ufis a constant value within the servo limit.
For motor failure, ufis usually a small value or zero. Here,
TABLE II: Physical parameters of the aircraft.
Parameter Description Value
mMass 4.6 kg
bWingspan 2.0 m
ρAir density 1.2250 kg/m3
¯cMean chord 0.22 m
SWing surface area 0.44 m2
cTPropeller thrust coefficient 2.2164e-5
cKPropeller torque coefficient 1.1082e-6
CLa Aileron coefficient 0.1173
CMe Elevator coefficient 0.5560
CNr Rudder coefficient 0.0881
CZ,0,CZ,α Lift coefficient 0.35, 0.11
CD,0,CD,α Drag coefficient 0.01, 0.2
we assume that ufis known.2ui6=kis the actuator input
for all the functioning actuators. We also denote kathe kth
column of A. Thus, we have the desired control wrench
WB=WB
i6=k+WB
k=kAui6=k+kauk(30)
WB
i6=k=kAutrim,i6=k+kA∆ui6=k
=WB
trim,i6=k+WB
∆,i6=k
where WB
i6=kand WB
krepresent the control wrench gener-
ated by the normal and failed actuators. Therefore,
WB−WB
k−WB
trim,i6=k=kA∆ui6=k(31)
Note that Eq. (31) has the same format as Eq. (23).
Therefore, we solve the constraint optimization problem to
find the output for the normal actuators.
VII. EXP ERI MENTS AND RESULTS
A. Experiment Setup
We modeled the tiltrotor VTOL in the Gazebo simulator
based on the design described in Sec. II. The dynamic control
allocation is developed on top of the PX4 source code, which
can run directly on real aircraft. The constrained optimization
is solved using Algilib [25], which is an open-source header-
only numerical analysis and data processing library. The
numerical values of the constants used during the experiment
are shown in Table. II.
B. Results
1) Motor Failure in Hover: To test this failure case, we
completely shut down one of the motors after the take-
off during hovering and before the transition. Fig. 5 shows
the allocated actuator commands. It is clear that when the
front right motor fails, all the functioning actuators adjust
themselves and compensate for the thrust loss. Notice that
the tilt angle corresponding to the failed motor quickly
converges to zero, which is reasonable since the failed rotor
can no longer generate any effective wrench. The actuator
commands converge after about 10 seconds. After recovery,
the aircraft is still controllable and can follow the desired
waypoints.
2Some failure detection and identification mechanisms [7], [24] can be
deployed on the aircraft to achieve this.
5 101520
time (s)
0
20
40
60
80
100
%
Motor Commands
Motor 0 (failed)
Motor 1
Motor 2
Motor 3
5 101520
time (s)
-80
-60
-40
-20
0
20
40
60
80
angle(deg)
Tilt Commands
Tilt 0
Tilt 1
Tilt 2
Tilt 3
Fig. 5: Actuator commands when a motor failure happens in hover.
5 101520
time (s)
-150
-100
-50
0
50
100
150
Angle (deg)
Attitude (informed)
Roll
Pitch
Yaw
5 101520
time (s)
-100
0
100
200
Angle (deg)
Attitude (not informed)
Roll
Pitch
Yaw
-10 -5 0 5 10
X (m)
-10
-5
0
5
10
Y (m)
Path (informed)
-10 -5 0 5 10
X (m)
-10
-5
0
5
10
Y (m)
Path (not informed)
Fig. 6: Aircraft attitude and path when a motor failure happens in
hover.
We compare our method with the case where the controller
is not informed about the motor failure. Fig. 6 presents
the aircraft attitude and flight path for the two scenarios:
with and without being informed of the system failure.
Without the failure knowledge, the system is still trying to
allocate a control wrench to the failed actuator, resulting in
the aircraft immediately getting into an aggressive rotation,
losing control, and crashing.
2) Tilt Angle Failure in Hover: This failure was simulated
by suddenly locking the tilt servo at a fixed position (here
at about 60° tilt). Fig. 7 shows the actuator commands. We
can see that even with a 60° tilt angle change, the system
can quickly recover after a significant sudden disturbance
by dynamically reallocating to the rest of the actuators.
Successful flights were performed with Xi=±90 deg.
3) Motor Failure During Cruise Flight: Fig. 8 shows a
simulated motor failure during cruise flight. The dynamical
control allocation enables the aircraft to adapt to the failure
and quickly return to the normal flight. It is worth noting
that the optimization solution results in all the tilts being
kept at full tilts (all the rotors are facing forward). By
adjusting the motor speeds and the control surfaces, the
vehicle can recover from failure. In fact, in high-speed cruise
flight, relying more on motor speeds and control surfaces
positively affects the aircraft since the drastic tilt change
may be hazardous to the aircraft structure. Compared to the
5 1015202530
time (s)
0
20
40
60
80
100
%
Motor Commands
Motor 0
Motor 1
Motor 2
Motor 3
5 1015202530
time (s)
-80
-60
-40
-20
0
20
40
60
80
angle(deg)
Tilt Commands
Tilt 0 (failed)
Tilt 1
Tilt 2
Tilt 3
Fig. 7: Actuator commands when a tilt servo failure happens in
hover.
Fig. 8: Actuator commands and the flight path when a motor failure
happens in cruise flight.
scenario of the system without the failure knowledge, it is
clear that being aware of the failure allows the aircraft to
maintain a straight path while being agnostic to the failure
leads to a significant path deviation.
4) Elevator Failure During Cruise Flight: We inject the
elevator failure with the elevator locked at 6°. Since the
elevator is the only control surface for pitch, the tilt angles
must adapt when failure happens. Fig. 9 shows the allocated
actuator commands. The rear two rotors tilt back, and the
front two tilt slightly forward over 90° to compensate for the
constant pitch-up moment generated by the locked elevator.
The aircraft can keep a reasonable constant altitude with only
a 4 m variation.
5) Aileron Failure During Cruise Flight: When the
aileron gets locked at 15°, the other healthy control surfaces
adjust to compensate for the lost roll control authority (see
Fig. 10). In particular, the other aileron has a significant
adaptation to compensate for the roll. At the same time, the
motors speed up with the left two spinning faster than the
right two to compensate for the induced yaw moment due
to the sudden sideslip caused by the roll disturbance. The
tilt angles still keep facing forward to avoid drastic structure
change. The controller can handle the locked aileron in calm
wind conditions up to δa=±15°, which is about half of the
5 10152025
time (s)
0
20
40
60
80
100
%
Motor Commands
Motor 0
Motor 1
Motor 2
Motor 3
5 10152025
time (s)
-50
0
50
100
angle(deg)
Tilt Commands
Tilt 0
Tilt 1
Tilt 2
Tilt 3
5 10152025
time (s)
-1
-0.5
0
0.5
1
command [-1, 1]
Surface Commands
aileronL
aileronR
elevator (failed)
rudder
5 10152025
time (s)
-60
-50
-40
-30
Z (m)
Altitude
Fig. 9: Actuator commands and the flight altitude when the elevator
failure happens in cruise flight.
5 1015202530
time (s)
0
20
40
60
80
100
%
Motor Commands
Motor 0
Motor 1
Motor 2
Motor 3
5 1015202530
time (s)
-1
-0.5
0
0.5
1
angle(deg)
Surface Commands
aileronL
aileronR (failed)
elevator
rudder
Fig. 10: Actuator commands when the aileron failure happens in
cruise flight.
maximum aileron deflection range.
VIII. CONCLUSION AND FUTURE WORK
This paper introduced fault tolerance to the design of
a tiltrotor VTOL. The VTOL is a hybrid of a fixed-wing
aircraft and a variable-pitch quadrotor. The rotor arms’
design with airfoil cross-sections decouples the structure
of the quadrotor arm and the main wing, making the tilt
design cleaner and the control less affected by the unexpected
wing structure deformation. The four propellers can rotate
individually.
We modeled the aircraft’s nonlinear dynamics and ana-
lyzed the feasible wrench space that the vehicle can generate.
Then, we designed the dynamic control allocation so that the
system can adapt to actuator failures. The proposed approach
is lightweight and is implemented as an extension to the PX4
flight control stack.
Finally, we presented extensive experiment results val-
idating the system’s performance under different actuator
failures. Future research includes performing the real flight
test to validate the developed approach further.
REFERENCES
[1] R. Bonatti, W. Wang, C. Ho, A. Ahuja, M. Gschwindt, E. Camci,
E. Kayacan, S. Choudhury, and S. Scherer, “Autonomous aerial
cinematography in unstructured environments with learned artistic
decision-making,” Journal of Field Robotics, vol. 37, no. 4, pp. 606–
641, 2020.
[2] S. Zhao, H. Zhang, P. Wang, L. Nogueira, and S. Scherer, “Super
odometry: Imu-centric lidar-visual-inertial estimator for challenging
environments,” in 2021 IEEE/RSJ International Conference on Intel-
ligent Robots and Systems (IROS). IEEE, 2021, pp. 8729–8736.
[3] J. Geng and J. W. Langelaan, “Cooperative transport of a slung
load using load-leading control,” Journal of Guidance, Control, and
Dynamics, vol. 43, no. 7, pp. 1313–1331, 2020.
[4] A. Keipour, M. Mousaei, A. T. Ashley, and S. Scherer,
“Integration of fully-actuated multirotors into real-world applications,”
arXiv:2011.06666, pp. 1–5, 2020. [Online]. Available: https:
//arxiv.org/abs/2011.06666
[5] N. Hegde, V. George, C. Gurudas Nayak, and K. Kumar, “Transition
flight modeling and robust control of a VTOL unmanned quad tilt-
rotor aerial vehicle,” Indonesian Journal of Electrical Engineering and
Computer Science, vol. 18, no. 3, pp. 1252–1261, Jan. 2020.
[6] J. A. Guerrero, R. Lozano, G. Romero, D. Lara-Alabazares, and K. C.
Wong, “Robust control design based on sliding mode control for hover
flight of a mini tail-sitter unmanned aerial vehicle,” in 2009 35th
Annual Conference of IEEE Industrial Electronics, 2009, pp. 2342–
2347.
[7] A. Keipour, M. Mousaei, and S. Scherer, “Automatic real-time
anomaly detection for autonomous aerial vehicles,” in 2019
International Conference on Robotics and Automation (ICRA).
IEEE, 2019, pp. 5679–5685. [Online]. Available: https://ieeexplore.
ieee.org/document/8794286
[8] M. Mousaei, A. Keipour, J. Geng, and S. Scherer, “VTOL failure
detection and recovery by utilizing redundancy,” in Workshop on
Intelligent Aerial Robotics: From Autonomous Micro Aerial Vehicles
to Sustainable Urban Air Mobility and Operations, 2022.
[9] M. W. Mueller and R. D’Andrea, “Relaxed hover solutions for mul-
ticopters: Application to algorithmic redundancy and novel vehicles,”
The International Journal of Robotics Research, vol. 35, no. 8, pp.
873–889, 2016.
[10] G. Michieletto, M. Ryll, and A. Franchi, “Fundamental actuation
properties of multirotors: Force–moment decoupling and fail–safe
robustness,” IEEE Transactions on Robotics, vol. 34, no. 3, pp. 702–
715, 2018.
[11] E. Baskaya, M. Hamandi, M. Bronz, and A. Franchi, “A novel robust
hexarotor capable of static hovering in presence of propeller failure,”
IEEE Robotics and Automation Letters, vol. 6, no. 2, pp. 4001–4008,
2021.
[12] T. Stastny and R. Siegwart, “Nonlinear model predictive guidance
for fixed-wing UAVs using identified control augmented dynamics,”
in 2018 International Conference on Unmanned Aircraft Systems
(ICUAS). IEEE, 2018, pp. 432–442.
[13] R. C. Busan, P. C. Murphy, D. B. Hatke, and B. M. Simmons, “Wind
tunnel testing techniques for a tandem tilt-wing, distributed electric
propulsion VTOL aircraft,” in AIAA SciTech 2021 Forum, 2021, p.
1189.
[14] X. Lyu, H. Gu, Y. Wang, Z. Li, S. Shen, and F. Zhang, “Design and
implementation of a quadrotor tail-sitter VTOL UAV,” in 2017 IEEE
international conference on robotics and automation (ICRA). IEEE,
2017, pp. 3924–3930.
[15] A. Kamal and A. Ramirez-Serrano, “Conceptual design of a highly-
maneuverable transitional VTOL UAV with new maneuver and control
capabilities,” in AIAA Scitech 2020 Forum, 2020, p. 1733.
[16] G. Ducard and M.-D. Hua, “Modeling of an unmanned hybrid aerial
vehicle,” in 2014 IEEE Conference on Control Applications (CCA).
IEEE, 2014, pp. 1011–1016.
[17] J. Zhang, P. Bhardwaj, S. A. Raab, S. Saboo, and F. Holzapfel,
“Control allocation framework for a tilt-rotor vertical take-off and
landing transition aircraft configuration,” in 2018 Applied Aerodynam-
ics Conference, 2018, p. 3480.
[18] L. Bauersfeld, L. Spannagl, G. J. Ducard, and C. H. Onder, “Mpc
flight control for a tilt-rotor VTOL aircraft,” IEEE Transactions on
Aerospace and Electronic Systems, vol. 57, no. 4, pp. 2395–2409,
2021.
[19] S. Fuhrer, S. Verling, T. Stastny, and R. Siegwart, “Fault-tolerant flight
control of a VTOL tailsitter UAV,” in 2019 International Conference
on Robotics and Automation (ICRA). IEEE, 2019, pp. 4134–4140.
[20] C. Papachristos, K. Alexis, and A. Tzes, “Design and experimental
attitude control of an unmanned tilt-rotor aerial vehicle,” in 2011 15th
International Conference on Advanced Robotics (ICAR). IEEE, 2011,
pp. 465–470.
[21] M.-D. Hua, T. Hamel, and C. Samson, “Control of VTOL vehicles
with thrust-tilting augmentation,” IFAC Proceedings Volumes, vol. 47,
no. 3, pp. 2237–2244, 2014.
[22] CubePilot. (2021) The cube orange standard set. Accessed: 2022-03-
01. [Online]. Available: https://cubepilot.org/#/cube
[23] L. Meier, D. Honegger, and M. Pollefeys, “Px4: A node-based
multithreaded open source robotics framework for deeply embedded
platforms,” in 2015 IEEE international conference on robotics and
automation (ICRA). IEEE, 2015, pp. 6235–6240.
[24] A. Keipour, M. Mousaei, and S. Scherer, “ALFA: A dataset for UAV
fault and anomaly detection,” The International Journal of Robotics
Research, vol. 40, no. 2-3, pp. 515–520, 2021. [Online]. Available:
https://journals.sagepub.com/doi/10.1177/0278364920966642
[25] S. Bochkano. (1999) Alglib. Accessed: 2022-03-01. [Online].
Available: www.alglib.net