Conference PaperPDF Available

Fault Tolerance Control for Quad-Rotor UAV Using Gain-Scheduling in Matlab/Gazebo

Authors:
  • Dubai Futue Labs

Abstract and Figures

Nowadays, multi-rotor Unmanned Aerial Vehicles (UAVs) are deployed widely in different fields to serve multiple purposes. Safety and reliability of multi-rotor system are rapidly growing research area, and enhancing the control design to account for system failure. In this paper, the Fault-Tolerance Control (FTC) is introduced as a method for recovery from failure in quad-rotor UAV actuator in hovering mode. The ultimate aim is to land safely with minimal damage. This research focuses on designing a FTC method that is capable of handling one and/or two rotors failures. Two different controllers are designed and implemented in simulation for controlling the UAV which are Proportional-Integral-Derivative (PID) control and Linear Quadratic Regulator (LQR). LQR shows its effectiveness after comparing both methods responses. Furthermore, a state observer is designed using Linear Quadratic Estimator (LQE). Gain scheduling (GS) method is developed to switch between the controllers of the system in the event of failure. The GS-PID control design is validated in ROS/Gazebo using the new Robotics System Toolbox showing the effectiveness of the proposed method.
Content may be subject to copyright.
Fault Tolerance Control for Quad-Rotor UAV Using
Gain-Scheduling in Matlab/Gazebo
Fatima Alkhoori
Emirates Technology
and Innovation Center
Khalifa University
of Science and Technology
P.O. Box 127788,
Abu Dhabi, United Arab Emirates
Yahya Zweiri
Faculty of Science,
Engineering and Computing
Kingston University London
London SW15 3DW, UK
Visiting Associate Professor,
Robotics Institute
Khalifa University
of Science and Technology
P.O. Box 127788,
Abu Dhabi, United Arab Emirates
Ahmad Bani Younes, Tarek Taha
and Lakmal Seneviratne
Khalifa University
of Science and Technology
P.O. Box 127788,
Abu Dhabi, United Arab Emirates
Abstract—Nowadays, multi-rotor Unmanned Aerial Vehicles
(UAVs) are deployed widely in different fields to serve multiple
purposes. Safety and reliability of multi-rotor system are rapidly
growing research area, and enhancing the control design to
account for system failure. In this paper, the Fault-Tolerance
Control (FTC) is introduced as a method for recovery from
failure in quad-rotor UAV actuator in hovering mode. The
ultimate aim is to land safely with minimal damage. This research
focuses on designing a FTC method that is capable of handling
one and/or two rotors failures. Two different controllers are
designed and implemented in simulation for controlling the UAV
which are Proportional-Integral-Derivative (PID) control and
Linear Quadratic Regulator (LQR). LQR shows its effectiveness
after comparing both methods responses. Furthermore, a state
observer is designed using Linear Quadratic Estimator (LQE).
Gain scheduling (GS) method is developed to switch between
the controllers of the system in the event of failure. The
GS-PID control design is validated in ROS/Gazebo using the
new Robotics System Toolbox showing the effectiveness of the
proposed method.
Index Terms—Fault Tolerance Control, Failure, UAV, Quad-
copter, Multi-rotor, Gain-Scheduling, LQR, LQE
I. INTRODUCTION
In the last few decades, Unmanned Aerial Vehicles (UAVs)
have gained a great value in the market due to its numerous
applications. They can be widely used in various defense and
civilian applications because of their capability of carrying
various sensor payloads and specialized hardware (e.g. gimbal,
cameras, laser range finder, radars etc).
In general, UAVs are exposed to different types of failures
in their components whether in sensors or actuators. Other
failures could be in the structure partially or even a total
structural damage which are discussed in [1]. Failure could
be, also, in form of partial or total loss of effectiveness as
considered in this research. Noting that, each type is treated
differently and requires different approach.
Fault Tolerance Control (FTC) is a technique applied to
enable a system to recover and/or continue its operation in
an acceptable performance or land safely in the event of one
or/and more faults or failures [2]. An effective FTC technique
is essential to enable the system to continue operating in
a controlled manner. A FTC technique can reduce physical
damages and minimize safety risks that can occur where a
simple fault can escalate to a total system failure. Moreover,
integrating FTC in a flight system adds reliability to the
overall control system, thus increases its robustness and its
applications. Saving the expensive payloads is an important
aspect nowadays since the integrated sensors with the platform
are more valuable than the platform itself. The ultimate goal,
which should be of the highest priority, is minimizing risk
to peoples lives when operating UAV in populated areas.
A properly developed FTC technique should be capable of
dealing with worst case scenario, catastrophic failure, and
significantly reduce the risk factor by executing appropriate
safe maneuvers.
FTC could be categorized into two types; Active FTC
(AFTC) and Passive FTC (PFTC). The AFTC corresponds in
real time by reconfiguring the control system according to
the fault detected [3]. The passive FTC tolerates set of pre-
defined failures by using a pre-computed fixed-controller that
contains limited failure modes along with the free-fault mode.
The PFTC is designed to work off-line and to be sufficiently
robust to bear the pre-defined malfunctions.
Different FTC multi-rotor based algorithms were surveyed
such as: sliding mode control (SMC) [4]–[6], adaptive control
[7]–[11], feedback linearization approach [12]–[14], relaxed
hover solution [15], [16], backstepping approach [17], Model
predictive control (MPC) [18], and Gain Scheduling [19]–[21].
Many other methods are available in the literature since it is
still a vital issue.
In this paper, Gain Scheduling (GS) with PID controller
is applied to quad-rotor UAV to switch between free failure
mode and a failure mode. The failure scenario is to recover
from actuator failure in one or two opposing motors. The case
Fig. 1. UAV configuration
of failure in one motor is treated as two motor failure where the
opposite motor is switched of directly. The aim of this paper is
to test the method in the new Matlab/Simulink Robotic System
toolbox.
II. UAV DYNAM IC MO DE L AN D CON TRO L
The quad-rotor UAV, shown in Fig. (1), adopted from
[22].Two main frames are used; north-east-down (NED) frame
which is the inertial frame, and body frame (B-frame) is fixed
on the quad-rotor platform. Moreover, motor 1 and 3 spin
clock-wise and motor 2 and 4 spin counter-clock-wise. The
linearized model corresponds to the hovering mode is
˙z=w(1)
˙w=2CT
m0(Ω12+ Ω34)(2)
where the model is linearized around the trim point. zand
wcorrespond to the position and linear velocity in z-axis
respectively, CTis the thrust power coefficient 1.5108 ×105
kg.m, mis the total mass 1.32 kg, 0is the rotor angular
velocity in the trimming point equals 463.1rad/sec and is
the angular velocity of the rotors. The brush-less motor model
is treated as first order linear system
˙
m,i =10 Ωm,i + 7 Ufor i= 1, ..., 4(3)
where Uis the motor input. Combining (1) and (3) to
develop the dynamical model for the hovering mode. The
motors speeds are considered as part of the model states for
fault tolerance purposes where the motor speed provides an
indication of failure.
The same linearized model has been used for the failure
mode in two opposite motors where (3) is used for motor 1
and 3 only and motors 2 and 4 are eliminated as shown in
Fig. (2).
A. Control law
Two controllers have been used which are PID and LQR to
control the vertical position.
Fig. 2. The quad-rotor in failure case
Fig. 3. System feedback loop with PID controller
1) PID controller: Two loops are used to control the UAV
vertical movement as shown in Fig. (3). The inner loop
is used to control the vertical velocity where P controller
was sufficient. The outer loop is used to control the vertical
position using PD controller. The detailed implementation of
PID controller is discussed in [23]. The derivative controller
is introduced as high pass filter as shown in (4)
KP D =kpp+skd
αs + 1 (4)
where α= 0.02 is the low pass filter time constant.
2) LQR: Linear Quadratic Regulator (LQR) is another
method for state feedback control that provides a systematic
procedure for determining the control gains. Considering our
system, the aim of this method is to minimize the cost function
J
J=Zt
t0
(xTQ x +uTR u)dt (5)
where Qand Rare the weight matrices that are positive
definite specifying the relative importance of the error and en-
ergy consumption. In order to minimize J, the state feedback
control can be
u=K x (6)
where Kis the control gain. It is determined by solving the
steady state Riccati equation
ATP+P A P B R1BTP+Q= 0 (7)
and then using Pto find the control gain K
K=R1BTP(8)
The aim of implementing this method is to control the
UAV’s altitude as shown in Fig. (4)
Fig. 4. LQR Simulink model
3) LQG: It was important to design an observer for state
estimation since measuring the states is an expensive proce-
dure. Therefore, Linear Quadratic Gaussian (LQG) is a method
that combines Linear Quadratic Regulator (LQR) and Linear
Quadratic Estimation (LQE). For the observer, the system state
space representation becomes
˙
ˆx =x +Bu +T(yˆy)
ˆy =x (9)
where ˆx is the estimated state vector, ˆy is the estimated
output and Tis the control gain. By substituting ˆ
yfor (9)
and re-arranging
˙
ˆx˙x= (AT C )ˆx+ (AT C)x(10)
In terms of the error vector, it becomes
˙e = (AT C)e(11)
This equation presents the error dynamics in terms of the
system matrix A, the measurement matrix Cand the observer
gain T.Tto be chosen according to two aspects. First,
(AT C)is stable matrix (the real part of the eigenvalues
is negative), then as t→ ∞ the error vector e0. It means
that the produced estimates are asymptotically stable. The gain
Tcan be calculated based on LQE method.
Introducing a disturbance to the system Vand a white
Gaussian noise to the measurements W, the linear dynamic
system becomes
˙x =Ax +Bu +V
y=Cx +W(12)
The optimal Kalman filter gain Tis obtained from A,C,W
and Vby solving the steady state Riccati equation
ATP+P A P C W1CTP+V= 0 (13)
then, the observer gain is
T=P CTW1(14)
The results obtained by implementing the LQG method
is shown in Fig. (5). This results have been obtained after
modifying the observer gain by increasing its value in order
to reject the disturbances. However, the noise signal has
increased, therefore, a filter is used for the output signal. These
steps created a robust and reliable control law that is applied
to the system.
012345678910
Time [sec]
-5
0
5
10
15
20
25
Position [m]
Measured z
filtered z
estimated z
Fig. 5. yvs. ˆywith noise and disturbance injection, filter and modified
gain
Similar steps have been implemented to the system with
failure, where only number of states is reduced.
III. FAULT TOLERANCE CONT ROL
A. FTC using Gain Scheduling
The FTC technique, in this paper, is based on combining
both quad-rotor models developed previously and switch be-
tween them at the failure event. The models are taken with
their control law to account for the free fault mode and the
failure mode. The intended methodology is to switch the
control gains of the LQG at the instant of failure. This is
called gain scheduling. In order to test our methodology, the
failure is introduced at tfsecond. A fault detection unit is
assumed to be implemented to capture the failure. Once the
system is alerted to the existence of the failure, two opposite
motors angular velocities are set to zeros.
In the simulation, the failure is injected at tf= 8 sec in
motors 2 and 4. The switching condition is triggered by a zero
angular velocity signal which is sent by the observer. The mea-
sured data are continuously sent as a non-zero value, where
all values are multiplied together. Once a motor produces a
zero angular velocity, the switch detects the zero signal and
shifts to the control system that accounts for the failure. At the
moment of switching, the position response of the free fault
model passes its final value to the failure model. Therefore, the
switches are designed to allow for an overlap of one sample
time for the final value of the position to be passed. The sample
time is chosen as tp= 0.01 sec. Figure(6) demonstrates the
idea more clearly. First, the control signal in figure(7) is sent to
the four rotors model with consideration of the sample time
tp. Thus the four rotors model is running for 8.01 seconds.
However, the two rotors model starts running at the failure time
tf= 8, as shown in figure(8). This one sample time overlap
allows for the position final value from the four rotor model
to pass through the two rotor system as an initial condition.
Fig. 6. Switching using overlap approach
Fig. 7. Control signal block for the four rotor
Figure (9) shows the response of the system to the GS
method. A command of landing is given to the system in order
to recover with minimal damage. The figure shows a lag of
response in the lading; however, it is within our benefits since
we aim to increase the landing time in order to decrease the
impact of the platform on the ground.
IV. IMPLEMENTATION AND RESU LTS
It was essential to have a suitable environment for vali-
dation. There are multiple ways for validation such as flight-
testing, parameter identification or using a real simulated envi-
ronment. Flight testing requires an access to costly hardware,
field test with trained pilot and significant amount of time.
Moreover, field test does not produce an expected or successful
outcome from the beginning and sometimes it could damage
the UAV. Parameter identification is a suitable validation
method if there is an access to a measured data. Therefore,
the real simulation environment ROS/Gazebo is chosen due
Fig. 8. Control signal block for the two rotor
0 2 4 6 8 10 12 14 16 18 20
Time [sec]
-5
0
5
10
15
20
25
Position [m]
z (reference)
z (free-fault)
z (reference)
z (failure)
Fig. 9. FTC model response
to availability of software and expertise in Khalifa University
campus (KURI Lab). Robotics Operating System (ROS) is a
recent software that provides interface communication (e.g.
send and receive data) with a robot simulator system and
Gazebo simulate a real physical robotic machine. The firmware
used for validation was already validated and tested in actual
platform and proven its reliability. Moreover, the interface
between Matlab/Simulink and ROS/Gazebo is carried out via a
recent toolbox added to MathWorks toolboxes called Robotics
System Toolbox. It allows for direct communication with ROS
by sending and receiving messages, generating and deploying
nodes in ROS, and C++ code generation.
Figure (10) shows the Simulink model developed to inter-
face with ROS/Gazebo. The blocks shown on the left side
and magnified in Fig. (11) are the subscribers to the position
and velocity published by Gazebo. The Command Velocity
Publisher block shown in Fig. (12) describes the publishing
method where the signal is assigned with a message type.
Initially, PID controller is implemented to control the UAV.
Figure (13) shows the take-off and hover behaviors of the UAV
in Gazebo comparing to the Matlab/Simulink behavior when
constrained to the same system requirements as Gazebo. A
similar behavior between both systems is achieved, although
there is a delay in the Gazebo model due to the necessity of
the platform to reach a certain velocity prior take-off.
In Gazebo, the failure in two rotors is created by shutting-
Fig. 10. Simulink model with Gazebo interface
Fig. 11. Position and velocity subscriber blocks
off two opposite motors at random time. The behavior of the
UAV at the instant of failure is described in figure(14). The
abnormal performance is due to the spinning of the UAV and
its attempt to reach the desired altitude. The goal is to land
the UAV safely while it is spinning. Therefore, a switching
mechanism is applied where the system detects the failure
and switches to landing mode immediately. A signal taken
from Gazebo that publishes the angular velocity of the motors
is fed to the switch. This is done with the assumption of
Fig. 12. Velocity publisher block
0 5 10 15 20 25 30 35 40 45
Time [sec]
-1
0
1
2
3
4
5
6
Position [m]/Velocity [m/s]
Velocity Simulation
Position Simulation
Position Gazebo
Velocity Gazebo
Fig. 13. Simulation vs. Gazebo response for PID controller (simulation
refers to Matlab simulation)
pre-implementation of a failure detection unit. The switch
commands the system to land when a zero angular velocity
is captured. Moreover, gain scheduling is implemented where
the switching mechanism is applied to the controlling gains as
well. Another switch commands the system to stop the UAV
before reaching the ground by 15cm.
In Fig. (14), the UAV took less than 3 seconds to crash after
the abnormal behavior. It is shown in figure(15) that the UAV
landed in around 4 seconds. This is due to the gain scheduling
method used where the controller parameters are re-tuned to
account for the failure case. An acceptable performance in
following the landing command is shown which allows for
safe landing of the UAV. In this case, we demand a longer
time in the landing mode to prevent fast impact which might
damage the UAV.
V. CONCLUSION
Fault tolerance control is a wide field that can be ap-
proached from different perspectives. In this paper, failure
scenario is considered for total loss of two opposing rotors.
The simulation results showed the effectiveness of the Gain
Scheduling method applied, where the UAV was able to track
the trajectory (stay hovering) in a controlled manner and land.
Moreover, the system was validated using ROS/Gazebo and
the Robotics toolbox in Matlab/Simulink where the UAV was
0 10 20 30 40 50 60 70
Time [sec]
-4
-3
-2
-1
0
1
2
3
4
5
Position [m]/Velocity [m/s]
Velocity
Position
Fig. 14. UAV behavior in failure mode without FTC
0 2 4 6 8 10 12 14 16 18
Time [sec]
-3
-2
-1
0
1
2
3
4
5
6
Position [m]/Velocity [m/s]
Velocity
Position
trajectory
Fig. 15. UAV behavior in gain scheduling with tuning
able to recover and land safely immediately after the failure.
In future, LQR is intended to be tested in ROS/Gazebo.
REFERENCES
[1] I. Sadeghzadeh and Y. Zhang, “A review on fault-tolerant control for
unmanned aerial vehicles (uavs),” in Infotech@ Aerospace 2011, 2011,
p. 1472.
[2] D. Henry, J. Cieslak, D. Efimov, P. Goupil et al.,Fault diagnosis and
fault-tolerant control and guidance for aerospace vehicles: from theory
to application. Springer Science & Business Media, 2013.
[3] J. Jiang and X. Yu, “Fault-tolerant control systems: A comparative study
between active and passive approaches,Annual Reviews in control,
vol. 36, no. 1, pp. 60–72, 2012.
[4] F. Sharifi, M. Mirzaei, B. W. Gordon, and Y. Zhang, “Fault tolerant
control of a quadrotor uav using sliding mode control,” in Control and
Fault-Tolerant Systems (SysTol), 2010 Conference on. IEEE, 2010, pp.
239–244.
[5] T. Li, Y. Zhang, and B. W. Gordon, “Nonlinear fault-tolerant control
of a quadrotor uav based on sliding mode control technique,” IFAC
Proceedings Volumes, vol. 45, no. 20, pp. 1317–1322, 2012.
[6] A.-R. Merheb, H. Noura, and F. Bateman, “Passive fault tolerant control
of quadrotor uav using regular and cascaded sliding mode control,
in Control and Fault-Tolerant Systems (SysTol), 2013 Conference on.
IEEE, 2013, pp. 330–335.
[7] F. Chen, Q. Wu, B. Jiang, and G. Tao, “A reconfiguration scheme for
quadrotor helicopter via simple adaptive control and quantum logic,
IEEE Transactions on Industrial Electronics, vol. 62, no. 7, pp. 4328–
4335, 2015.
[8] A. Chamseddine, Y. Zhang, C.-A. Rabbath, J. Apkarian, and C. Fulford,
“Model reference adaptive fault tolerant control of a quadrotor uav,” in
Infotech@ Aerospace 2011, 2011, p. 1606.
[9] Z. T. Dydek, A. M. Annaswamy, and E. Lavretsky, “Adaptive control
of quadrotor uavs: A design trade study with flight evaluations,IEEE
Transactions on control systems technology, vol. 21, no. 4, pp. 1400–
1406, 2010.
[10] A. Milhim, Y. Zhang, and C.-A. Rabbath, “Gain scheduling based pid
controller for fault tolerant control of quad-rotor uav,” in AIAA infotech@
aerospace 2010, 2010, p. 3530.
[11] I. Sadeghzadeh, A. Mehta, A. Chamseddine, and Y. Zhang, “Active
fault tolerant control of a quadrotor uav based on gainscheduled pid
control,” in Electrical & Computer Engineering (CCECE), 2012 25th
IEEE Canadian Conference on. IEEE, 2012, pp. 1–4.
[12] A. Freddi, A. Lanzon, and S. Longhi, “A feedback linearization approach
to fault tolerance in quadrotor vehicles,” IFAC Proceedings Volumes,
vol. 44, no. 1, pp. 5413–5418, 2011.
[13] M. Ranjbaran and K. Khorasani, “Fault recovery of an under-actuated
quadrotor aerial vehicle,” in Decision and Control (CDC), 2010 49th
IEEE Conference on. IEEE, 2010, pp. 4385–4392.
[14] ——, “Generalized fault recovery of an under-actuated quadrotor aerial
vehicle,” in American Control Conference (ACC), 2012. IEEE, 2012,
pp. 2515–2520.
[15] M. W. Mueller and R. D’Andrea, “Stability and control of a quadro-
copter despite the complete loss of one, two, or three propellers,” in
Robotics and Automation (ICRA), 2014 IEEE International Conference
on. IEEE, 2014, pp. 45–52.
[16] M. W. Mueller and R. DAndrea, “Relaxed hover solutions for multi-
copters: Application to algorithmic redundancy and novel vehicles,The
International Journal of Robotics Research, vol. 35, no. 8, pp. 873–889,
2016.
[17] X. Zhang, Y. Zhang, C.-Y. Su, and Y. Feng, “Fault-tolerant control for
quadrotor uav via backstepping approach,” in 48th AIAA Aerospace
Sciences Meeting Including the New Horizons Forum and Aerospace
Exposition, 2010, p. 947.
[18] H. A. Izadi, Y. Zhang, and B. W. Gordon, “Fault tolerant model pre-
dictive control of quad-rotor helicopters with actuator fault estimation,
IFAC Proceedings Volumes, vol. 44, no. 1, pp. 6343–6348, 2011.
[19] I. Sadeghzadeh, A. Mehta, and Y. Zhang, “Fault / Damage Tolerant
Control of a Quadrotor Helicopter UAV using Model Reference Adaptive
Control and Gain-,” AIAA Guidance, Navigation, and Control Confer-
ence, no. August, pp. 1–13, 2011.
[20] A. Milhim, Y. Zhang, and C.-a. Rabbath, “Gain scheduling based
PID controller for fault tolerant control of a quad-rotor UAV,AIAA
Infotech at Aerospace 2010, no. April, pp. 1–13, 2010. [Online].
Available: http://www.scopus.com/inward/record.url?eid=2-s2.0-
78650013533&partnerID=40&md5=4bdfe4094eb7284261ef9628b86e5964
[21] I. Sadeghzadeh, A. Mehta, A. Chamseddine, and Y. Zhang, “Active
Fault Tolerant Control of a Quadrotor Uav Based on Gain- Scheduled
Pid Control,” Electrical & Computer Engineering (CCECE), 2012 25th
IEEE Canadian Conference on, pp. 1–4, 2012. [Online]. Available:
http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=6335037
[22] T. Jiˇ
rinec, “Stabilization and control of unmanned quadcopter. M.Sc.
thesis, Czech Technical University in Prague, 2011.
[23] F. Alkhoori, “Fault tolerance control for quad-rotor uav.” M.Sc. thesis,
Khalifa University for Science and Technology, 2017.
... For example, a sudden fault in the system can affect the dynamic of the drone differently over time whereas simulating this requires a command from the user. In this section, a number of software that researchers have used for simulation purposes are introduced [41,[100][101][102][103][104]. Thus, the following reports several related software that are found feasible in analysing the dynamic of the proposed vehicle. ...
... Since the software became known worldwide for its great features, users began to use it on multi robots and indoor environments testing various mathematical models, designing robots to meet user requirements, and more importantly, being able to test Artificial intelligence (AI) systems within realistic situations. Moreover, the open source software also allows users to program their robots and view the reaction through graphical user interfaces (GUI) platform [41,101,107]. ...
... So far, there has been numerous simulators developed to test and evaluate single robots only. However, ARGos has the ability to test multiple machines working simultaneously while providing results, but, a drawback of increased computational power and degraded performance is encountered as the number of robots are increased [41,102]. ...
Article
Full-text available
Over the past decade, unmanned aerial vehicles (UAVs) have received a significant attention due to their diverse capabilities for non-combatant and military applications. The primary aim of this study is to unveil a clear categorization overview for more than a decade worth of substantial progress in UAVs. The paper will begin with a general overview of the advancements, followed by an up-to-date explanation of the different mechanical structures and technical elements that have been included. The paper will then explore and examine various vertical take-off and landing (VTOL) configurations, followed by expressing the dynamics, applicable simulation tools and control strategies for a Quadrotor. In conclusion to this review, the dynamic system presented will always face limitations such as internal and/or external disturbances. Hence, this can be minimised by the choice of introducing appropriate control techniques or mechanical enhancements.
Conference Paper
Full-text available
In this paper, in view of the advantages of widely used Proportional-Integral-Derivative (PID) controller and gain scheduling control strategy in aerospace and industrial applications, a control strategy by using gain scheduling based PID controller is proposed for fault tolerant control (FTC) of a quad-rotor Unmanned Aerial Vehicle (UAV). The nonlinear dynamic equations of motion of the quad-rotor UAV are firstly derived based on the Newton’s second law. PID controllers under fault-free and several different fault situations are then designed and tuned to control the quad-rotor UAV model under normal and different faults flight conditions. Each PID controller uses the speed and the orientation of each propeller for stabilizing and hovering motion of the quad-rotor UAV. Based on a decision variable (used as scheduling variable in this case) associated with a fault detection and isolation module, switching of each pre-tuned PID controller can be made in real-time and on-line. Simulation results under different fault scenarios have shown the effectiveness of the proposed approach for a six-degree-of-freedom nonlinear quad-rotor UAV model.
Conference Paper
This paper presents periodic solutions for a quadrocopter maintaining a height around a position in space despite having lost a single, two opposing, or three propellers. In each case the control strategy consists of the quadrocopter spinning about a primary axis, fixed with respect to the vehicle, and tilting this axis for translational control. A linear, timeinvariant description of deviations from the attitude equilibrium is derived, allowing for a convenient cascaded control design. The results for the cases of losing one and two propellers are validated in experiment, while the case of losing three propellers is validated in a nonlinear simulation. These results have application in multicopter fault-tolerant control design, and also point to possible design directions for novel flying vehicles.
Article
This paper presents a relaxed definition of hover for multicopters with propellers pointing in a common direction. These solutions are found by requiring that the multicopter remain substantially in one position, and that the solutions be constant when expressed in a coordinate system attached to the vehicle. The vehicle's angular velocity is then shown to be either zero or parallel to gravity. The controllability of a vehicle's attitude about these solutions is then investigated. These relaxed hover solutions may be applied as an algorithmic failsafe, allowing, for example, a quadrocopter to fly despite the complete loss of one, two, or three of its propellers. Experimental results validate the quadrocopter failsafe for two types of failure (a single propeller and two opposing propellers failing), and a nonlinear simulation validates the remaining two types of failure (two adjacent and three propellers failing). The relaxed hover solutions are also shown to allow a multicopter to maintain flight in spite of extreme center of mass offsets. Finally, the design and experimental validation of three novel vehicles is presented.
Article
A reconfiguration control scheme is proposed for a quadrotor helicopter with loss of control effectiveness via simple adaptive control and quantum logic. Some good control performances of the helicopter can be achieved by applying quadratic optimal control with scheduled stability degree when the system is in normal operation. A parallel feedforward compensator is introduced to fulfill the condition of positive realness, and thus, the simple adaptive controller can be utilized for the helicopter. Quantum logic is also applied to the quadrotor control system, which achieves the quantization of the disturbances patterns. A mathematical model of the quadrotor helicopter for application is obtained from its dynamic equations with pitch, roll, and yaw axes, which includes the parameter perturbation and outer disturbances. Several simulation and experimental results for the faulty helicopter validate the robustness and reconfiguration control capability of the proposed scheme.
Conference Paper
Model predictive control (MPC) at each time step minimizes a cost function subject to dynamical constraints to obtain a stabilizing control signal. Further, MPC is one of the few methodologies that can be used to design feedback control for nonlinear dynamical systems with actuator saturations. It can thus serve as a suitable fault tolerant control approach for quad-rotor helicopter governed by a nonlinear dynamics. Using MPC, changes in the dynamics due to failure can be reflected into the control signal calculation at each sampling step. However, MPC needs a relatively accurate model of the post-failure system to calculate a stabilizing control signal. The problem becomes more critical where the system dynamics is described by a nonlinear model because there exist few nonlinear parameter estimators with reasonable online computation time. To address this issue, for online actuator fault estimation this paper investigates Moving Horizon Estimation (MHE) and Unscented Kalman Filter (UKF) as two methods for nonlinear parameter estimation. A framework is then formulated for integrating MHE and UKF based fault estimators with MPC, to achieve a fault tolerant controller for the quad-rotor helicopter with highly nonlinear constrained dynamics. Performance and computation requirement comparison of both algorithms are also investigated.
Conference Paper
In this paper, a sliding mode based fault-tolerant control (SM-FTC) is designed, implemented and tested in a quadrotor unmanned small helicopter under the propeller damage and actuator fault conditions. Based on the concept of sliding mode control, both passive and active fault-tolerant control laws have been designed and experimentally testbed on a quadrotor UAV (unmanned aerial vehicle) testbed available at Concordia University. These two types of controllers are carried out and compared through both theoretical analyses and experimental tests on the quadrotor UAV system.
Conference Paper
In this paper, two useful approaches to Fault Tolerant Control (FTC) for a quadrotor helicopter Unmanned Aerial Vehicle (UAV) in the presence of fault(s) in one or more actuators during flight have been investigated and experimentally tested based on a Model Reference Adaptive Control (MRAC) and a Gain-Scheduled Proportional-IntegralDerivative (GS-PID) control. A Linear Quadratic Regulator (LQR) controller is used in cooperation with the MRAC and the GS-PID to control the pitch and roll attitudes of the helicopter. Unlike the MRAC, the GS-PID is used only to control the helicopter in height control mode. MRAC is used to control the helicopter in both height control as well as trajectory control. For damage tolerant control the MRAC is evaluated based on partial damage of one of propellers during flight. Finally, the experimental flight testing results of both controllers are presented for the fault tolerant control performance comparison in the presence of actuator faults in the quadrotor UAV.
Conference Paper
Different from the previous work for quadrotor which mostly discusses application of different controllers to quadrotor control under normal flight conditions, this paper introduces a new design strategy which considers fault tolerant capability of the quadrotor control problems. By utilizing Passive Fault Tolerant Control Systems (PFTCS) concept with backstepping control approach, the trajectory tracking control of the quadrotor UAV has been achieved and simulation results have shown the effectiveness of the proposed backstepping control with higher controller gains when different levels of actuator faults occur in the quadrotor UAV. Copyright © 2010 by the American Institute of Aeronautics and Astronautics, Inc.
Conference Paper
The growing number of Unmanned Aerial Vehicles (UAVs) is considerable in the last decades. Many flight test scenarios, including single and multi-vehicle formation flights, are demonstrated using different control algorithms with different test platforms. In this paper, we present a brief literature review on the development and key issues of current researches in the field of Fault-Tolerant Control (FTC) applied to UAVs. It consists of various intelligent or hierarchical control architectures for a single vehicle or a group of UAVs in order to provide potential solutions for tolerance to the faults, failures or damages in relevant to UAV components during flight. Among various UAV test-bed structures, a sample of every class of UAVs, including single-rotor, quadrotor, and fixed-wing types, are selected and briefly illustrated. Also, a short description of terms, definitions, and classifications of fault-tolerant control systems (FTCS) is presented before the main contents of review.
Conference Paper
This paper presents some experimental results on actuator fault-tolerant control (FTC) for a quadrotor Unmanned Aerial Vehicle (UAV) system. The strategy is based on Model Reference Adaptive Control (MRAC) where three different MRAC techniques are implemented and compared with a Linear Quadratic Regulator (LQR) baseline controller, namely the MIT rule MRAC, the Conventional MRAC (C-MRAC) and the Modified MRAC (M-MRAC). The main advantage of the MRAC strategy is that it does not require an explicit information about the fault location and/or amplitude and thus, a fault detection and diagnosis module is not needed to detect, isolate and identify the occurred faults. The performance of this MRAC-based FTC is tested in the presence of three types of actuator faults: loss of effectiveness in the total thrust, loss of effectiveness in one of the rotors and partial damage of one propeller. © 2011 by the American Institute of Aeronautics and Astronautics, Inc. All rights reserved.