Next Article in Journal
Speed Tracking for IFOC Induction Motor Speed Control Using Hybrid Sensorless Speed Estimator Based on Flux Error for Electric Vehicles Application
Previous Article in Journal
Influence of Different Reflux Groove Structures on the Flow Characteristics of the Roots Pump
Previous Article in Special Issue
Formation and Change of Unmanned Ground Vehicles under Formation Change Influence Factor
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Fault Tolerant Control of Quadrotor Based on Sensor Fault Diagnosis and Recovery Information

Temasek Laboratories, National University of Singapore, T-Lab Building, 5A, Engineering Drive 1, Unit 09-02, Singapore 117411, Singapore
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Machines 2022, 10(11), 1088; https://doi.org/10.3390/machines10111088
Submission received: 8 October 2022 / Revised: 7 November 2022 / Accepted: 14 November 2022 / Published: 17 November 2022
(This article belongs to the Special Issue Dynamics and Motion Control of Unmanned Aerial/Underwater Vehicles)

Abstract

:
Drones have been developed for more than two decades. They have become central to the functions of various civil aviation and military services. Commercial usage of drones continues to grow steadily. As the drones have been used widely in different areas, this raises a safety concern, i.e., all the multi-rotors have an increased risk of motor or sensor faults. This paper considers a fault-tolerant control (FTC) problem against the inertial motion unit (IMU) sensor fault. First, a neural network estimator is built for the purpose of fault diagnosis. Second, a fault detection scheme is designed by comparing the IMU reading with the estimator, where it uses a logic rule to monitor the IMU state. Third, if the IMU sensor is in faulty state, the Euler angle estimator with neural network built is used to recover the IMU information which is fed into the controller designed. Finally, simulation studies are given to illustrate the effectiveness of the proposed FTC.

1. Introduction

Unmanned aerial vehicles (UAVs) have been used in many fields, such as photographing, monitoring traffic congestion, survellience, and multi-cameras coverage etc [1,2,3]. The missions for UAVs are becoming more and more challenging. An important problem in a UAV control system is to monitor the sensor or rotor changes when they are working. Much work has been done in this area. It has been shown that the use of an analytic model can allow early detection by measuring available variables. For example, in [4], the authors develop an incipient fault diagnosis method for a class of induction motors against stator/rotor winding faults; in [5], the authors present a incipient fault detection filter based on the generalised correntropy criterion; in [6], the authors propose a diagnosis method for broken rotor by using the analytic equations related to current signals; in [7], the authors present a fault detection method for a class of linear discrete time-varying systems. On the other hand, for UAV applications, it is important not only to detect sensor faults such as GPS, and inertial measurement units (IMU), but also to accommodate the faults (this is the so-called fault tolerant control). This topic has attracted increasing attention [8,9]. In this paper, IMU sensor fault is considered. The problem can be defined as a fault tolerant control that can accommodate IMU sensor faults, maintaining an acceptable performance. In [10], the authors presented a data-driven sensor fault diagnosis method. In [11], the authors also use data-driven method for detecting UAV faults. In [12], the authors propose a classifier for detecting UAV sensor fault. In [13], the authors use artificial intelligence (AI) method to learn the samples and estimate roll rate after the gyroscope has a fault. In [14], the authors develop an Euler angle estimator for improving the result of [13].
In this paper, we propose a fault-tolerant control to handle IMU sensor fault for quadrotor. The main idea is to build an angular rate estimator for the IMU sensor fault detection, which is also used for the IMU recovery. It should be noticed that the IMU fault affects not only angular rate but also the Euler angles. Our paper considers both when designing the estimator. First, the observability analysis is used for selecting the variables for building the angular rate estimator from the sixteen states of the quadrotor studied. Second, the proposed estimator is composed of a long short-term memory (LSTM) neural network trained from the collected data. Third, an Euler angle estimator is designed for improving the angular rate estimation. Finally, a fault diagnosis and IMU recovery mechanism is proposed. The proposed method extends the result of [14] to more fields: (1) the variable selection of the proposed neural network observer is analyzed; (2) the convergence analysis of the proposed scheme is discussed; (3) the modified estimator of Euler angle is given. The contributions of the present paper include:
  • Fault-tolerant control method for dealing with IMU sensor faults completely
  • Neural network learning for estimating Euler angles and recovering IMU sensor information

2. Model of Quadrotor and IMU Sensor Fault

We use a quadrotor model as shown in [14] for our research and conducting simulation. The drone is assumed to be a rigid body, as shown in Figure 1.
For sensor faults, we consider roll or pitch faults caused by gyroscope sensor.

3. Framework of FTC for Sensor Detection and Recovery

In this section, we present a FTC framework against sensor faults. As shown in Figure 2, it is composed of a normal controller and a sensor processing unit. The former one works as a normal controller of quadrotor, and the latter one can monitor the system and recover the sensor information if the fault is diagnosed. The whole system is a fault-tolerant controller which can detect the IMU sensor faults and continue to maintain the drone to work safely by recovering the sensor by using the sensor estimator. It is observed that the two parts are separated and we can design each part independently.
We assume that the other sensors work well, for example compass, barometer and accelerometer.

4. AI-Based FTC against IMU Sensor Fault

As shown in the quadrotor model, the attitude state includes Euler angles and angular rates. These attitude states can be measured by IMU which contains accelerometer and gyroscope. Sometimes a gyroscope may have faults. This implies that the angular rates may not be available for the rate closed control loop. In this case, the drone may be out of control, causing the drone crash, even if the accelerometer is still available. Of course, in general, the compass is also available (this implies that ψ is known). Thus, we intend to estimate the angular rates by observing other states such as the position (x, y, z), Euler angles as well as the control inputs. The designed estimator will be used for IMU fault detection as well as IMU recovery.
We will first discuss the analysis of the observability in order to design the estimator.

4.1. Selecting Variables

In a quadrotor model, we have the sixteen states including the positions, velocities, Euler angles, angular rates and four PWM signals. How many variables used for designing estimator angular rates is challenging. One way is to analyze nonlinear model. In [14], we have given the detailed model which is nonlinear. We can use nonlinear observability analysis to decide which variables will be used for the estimator design. The following theorem will be used in our analysis.
Theorem 1.
[15] Let
x ˙ = f ( x , u )
y = h ( x )
where x is the manifold of dimension n. Let G be the set of all finite linear combinations formed with the Lie derivatives of h 1 , h 2 , . . . h p with respect to f and constant u. Let dG denote the set of the gradients of the elements of G. The system is weakly (locally) observable if the system satisfies the controllability rank condition at x 0 , i.e., dG contains n linearly independent vectors.
We focus on the attitude equations and have the following model.
ϕ ˙ = p + q s i n ( ϕ ) t a n ( θ ) + r c o s ( ϕ ) t a n ( θ )
θ ˙ = q c o s ( ϕ ) r s i n ( ϕ )
ψ ˙ = q s i n ( ϕ ) s e c ( θ ) + r c o s ( ϕ ) s e c ( θ )
p ˙ = M p I x q r ( I z I y ) I x
q ˙ = M q I y p r ( I x I z ) I y
r ˙ = M r I z p q ( I y I x ) I z .
The angular rate controls M p , M q , and M r can be further allocated by the following equations
M p = k T l y ( ω 1 2 ω 2 2 + ω 3 2 + ω 4 2 )
M q = k T l x ( ω 1 2 ω 2 2 ω 3 2 + ω 4 2 )
M r = k D ( ω 1 2 ω 2 2 + ω 3 2 ω 4 2 )
T z = k T ( ω 1 2 + ω 2 2 + ω 3 2 + ω 4 2 )
where ω i represents the spinning speed of the ith motor, l x and l y are the arm length along x and y axes, respectively, and k T and k D are the thrust and torque constants, respectively.
Furthermore, we assume that the Euler angles have small changes. This implies that p ϕ ˙ , q θ ˙ , r ψ ˙ . Rearranging the attitude equations, we have
x ˙   =   f ( x ) + g ( x , u ) = x 2 + x 4 s i n ( x 1 ) t a n ( x 3 ) + x 6 c o s ( x 1 ) t a n ( x 3 ) x 4 x 6 ( I z I y ) I x x 4 c o s ( x 1 ) x 6 s i n ( x 1 ) ; x 2 x 6 ( I x I z ) I y x 4 s i n ( x 1 ) s e c ( x 3 ) + x 6 c o s ( x 1 ) s e c ( x 3 ) ; x 2 x 4 ( I y I x ) I z + 0 M p I x 0 M q I y 0 M r I z
y = x 1 x 3 x 5 = h ( x )
where
x = [ ϕ , ϕ ˙ , θ , θ ˙ , ψ , ψ ˙ ] T .
The linear combinations with the Lie derivatives are given by
G = x 1 x 3 x 5 x 2 x 4 x 6 x 4 x 6 ( I z I y ) I x + M p 0 I x x 2 x 6 ( I x I z ) I y + M q 0 I y x 2 x 4 ( I y I x ) I z + M r 0 I z
where Ω r 0 is a constant, and M p 0 , M q 0 , M r 0 are the control input constants.
The set of the gradients of G is given by
d G = 1 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 x 6 ( I z I y ) I x 0 x 4 ( I z I y ) I x 0 x 6 ( I x I z ) I y 0 0 0 x 2 ( I x I z ) I y 0 x 4 ( I y I x ) I z 0 x 2 ( I y I x ) I z 0 0
Check the rank of dG. It is observed that rank(dG)=6. This means that the system is locally observable at the hover state and is verified near hovering state. This property will be lost away from that point.
Furthermore, we consider a full description of quadrotor as
x ¨ = 1 m ( R ( ϕ , θ , ψ ) T ¯ m g ¯ ) ϕ ˙ = p + q s i n ( ϕ ) t a n ( θ ) + r c o s ( ϕ ) t a n ( θ ) θ ˙ = q c o s ( ϕ ) r s i n ( ϕ ) ψ ˙ = q s i n ( ϕ ) s e c ( θ ) + r c o s ( ϕ ) s e c ( θ ) p ˙ = M p I x q r ( I z I y ) I x q ˙ = M q I y p r ( I x I z ) I y r ˙ = M r I z p q ( I y I x ) I z
where x represents the position [ x , y , z ] , and T ¯ = [ 0 ; 0 ; T ] T , g ¯ = [ 0 ; 0 ; g ] T .
If considering the measured variables (velocities) to be [ x ˙ , y ˙ , z ˙ ], we check if the system is observable. Still, we check the rank of dG and it is not 9, but 7. Thus, it is concluded that in this situation, the system is not observable.
Based on the analysis above, we select ten variables related to the estimator design as shown in Table 1.

4.2. Neural Network Angular Rate Estimator

For handling gyroscope fault, we will consider to use AI techniques to build a nonlinear mapping function between input and output by learning sample data sets. One of existing AI methods is the LSTM neural network which is powerful in dealing with time series problems. The advantage of LSTM is that the current unit can get the information of all the units before this unit, but the disadvantage is that the information of the units after this unit cannot be obtained. For our application, it is to model sequential data and the LSTM is suitable for our modelling.
It should be noticed that the flight is a time dynamical behavior. Thus, the built LSTM model can be used for estimating or predicting the next state. The variables used in the network are attitude information–roll, pitch and yaw and their corresponding three angular rates. To consider the control action, each PWM signal (it is represented by propeller speed) is also considered. As shown by the observability computation, these ten variables will be used for the LSTM modelling.
It denotes
x = [ x 1 , x 2 , . . . x 10 ] T = [ ϕ , θ , ψ , p , q , r , ω 1 2 , ω 2 2 , ω 3 2 , ω 4 2 ] T .
For building the LSTM network, the following input and output vectors are used
X t = x 1 , t D + 1 , x 1 , t D + 2 . . . x 1 , t x 2 , t D + 1 , x 2 , t D + 2 . . . x 2 , t . . . . . . . . . . . . x 10 , t D + 1 , x 10 , t D + 2 , . . . x 10 , t
Y t = x 1 , t + 1 x 2 , t + 1 x 6 , t + 1
where X t represents the input of the LSTM model at time t, Y t including Euler angles and angular rates, represents the LSTM output which is used for observing roll, pitch and yaw rates, and D represents the data size. In practices, D will be determined by observing the training performance.
As shown in Figure 3, in our application, the LSTM network consists of three parts: input, LSTM and output layers.
By the training, the angular rates can be estimated by using the LSTM network as show below
X k + 1 = F N N ( X k , X k 1 , . . . , X k d 1 , u k , . . . , u k d 1 )
where X k = [ ϕ ( k ) , θ ( k ) , ψ ( k ) , p ( k ) , q ( k ) , r ( k ) ] T , u k = [ ω 1 2 ( k ) , ω 2 2 ( k ) , ω 3 2 ( k ) , ω 4 2 ( k ) ] T , and F N N represents the LSTM network. The input and output of the model are shown in Figure 4.
Before the LSTM training, the data should be normalized for the purpose of the calculation stability. After that, the trained prediction model is used to denormalize the prediction result, so as to compare and analyze the error with the actual value. After the prediction sample data are constructed, the LSTM model can be established for training and prediction according to the following steps.
Step 1. Select a flight or simulation data, and construct training samples and prediction samples.
Step 2. Data preprocessing, normalize training samples and prediction samples.
Step 3. Input the training samples into the LSTM, change the number of hidden layer nodes of the LSTM, and determine the network structure by minimizing the error between the output result and the real sample.
Step 4. Input the prediction sample into the trained network, get the trajectory prediction result, and perform denormalization.
Step 5. compare with other algorithms and analyze the prediction effect. Therefore, the flow chart of the LSTM-based trajectory prediction model algorithm is shown in Figure 5.
The loss function uses the root mean square error (RMSE) function which is given by
E R M S E = 1 N i = 1 N ( y L S T M p r e d i c t i o n y i ) 2
where y L S T M p r e d i c t i o n is the LSTM output, and y i is the output of the sample.
It is observed that the angular rate information can be obtained by
X ^ k + 1 = F N N ( X ^ k , X ^ k 1 , . . . , X ^ k d 1 , u k , . . . , u k d 1 ) + L ( Z k Z ^ k )
Z ^ k = C X ^ k
where
X ^ k = [ ϕ ^ ( k ) , θ ^ ( k ) , ψ ^ ( k ) , p ^ ( k ) , q ^ ( k ) , r ^ ( k ) ] T , u k = [ ω 1 2 ( k ) , ω 2 2 ( k ) , ω 3 2 ( k ) , ω 4 2 ( k ) ] T , C = 1 0 0 0 0 0 0 1 0 0 0 0 0 0 1 0 0 0 Z k = [ ϕ ( k ) , θ ( k ) , ψ ( k ) ] T , Z ^ k = [ ϕ ^ ( k ) , θ ^ ( k ) , ψ ^ ( k ) ] T .
For analysis purpose, we re-arrange the equation as
X k + 1 = X k + F N N ( X k 1 , X k 2 , . . . , X k d 1 , u k 1 , . . . , u k d 1 ) X k = X k + F ¯ N N ( X k 1 , X k 2 , . . . , X k d 1 , u k 1 , . . . , u k d 1 )
where F ¯ N N = F N N X k . It should be noticed that this can also be written as
X ^ k + 1 = X ^ k + F ¯ N N ( X ^ k 1 , X ^ k 2 , . . . , X ^ k d 1 , u k 1 , . . . , u k d 1 ) + L ( Z k Z ^ k ) Z k = C X k Z ^ k = C X ^ k
Thus, we have the error equation
X ˜ k + 1 = X ˜ k + ε ( · ) L C X ˜ k = ( I L C ) X ˜ k + ε ( · ) = A ¯ X ˜ k + ε ( · )
Z ˜ k = C X ˜ k
where X ˜ k = X k X ^ k , A ¯ = I L C ,
ε ( · ) = F ¯ N N ( X k 1 , . . . , X k d 1 , . . . , u k d 1 ) F ¯ N N ( X ^ k 1 , . . . , X ^ k d 1 , u k 1 , . . . , u k d 1 ) ,
and Z ˜ k = Z k Z ^ k . A reasonable assumption is that the output of the actual system is bounded. It should be noticed that the neural network output F ¯ is bounded. Thus, ε is also bounded.
It can be seen that the proposed LSTM network is a nonlinear observer-like estimator by using the observed vector Z k . Such a design can enhance the performance of the estimator. The convergence analysis of the proposed estimator can be given below.
Define a Lyapunov function
V = X ˜ k T P X ˜ k
Thus, we have
Δ V = X ˜ k + 1 T P X ˜ k + 1 X ˜ k T P X ˜ k = X ˜ k T ( A ¯ T P A ¯ P ) X ˜ k + 1 + 2 X ˜ k T A ¯ T P ε + ε T P ε λ m i n ( Q ) | | X ˜ k | | 2 + λ m i n 2 ( Q ) | | X ˜ k | | 2 + 2 λ m i n ( Q ) | | A ¯ T P | | 2 ε 2 + P ε 2 = λ m i n 2 ( Q ) | | X ˜ k | | 2 + ε ¯
where we have used the inequality 2 a b σ a 2 + 1 σ b 2 , ε ¯ = m a x { 2 λ m i n ( Q ) | | A ¯ T P | | 2 ε 2 + P ε 2 } , Q can be obtained from the following equation
A ¯ T P A ¯ P + Q = 0 .
with λ m i n ( Q ) denoted as the minimum eigenvalue of Q. It should be noticed that Δ V < 0 if | | X ¯ k | | > ε ¯ λ m i n 2 ( Q ) . This implies that it is uniformly ultimate bounded according to [16].
It can be observed from the above that the LSTM neural network is a key part in the proposed estimator. It can be trained by learning the samples collected from the drone.

4.3. Euler Angle Estimator

In a quadrotor, the gyroscope sensor not only affects the angular rate measurement, but also Euler angle reading. This implies that when the gyroscope is in faulty state, it also affects the Euler angle reading. Since we assume that the compass works well, the yaw angle is still fine. We will estimate the Euler angles ( ϕ , θ ) when the gyroscope fault occurs.
For Euler angle estimation, we use the following translational motion equations.
m T z E m = m T z [ x ¨ y ¨ z ¨ 0 0 g ] = c o s ( ϕ ) s i n ( θ ) c o s ( ψ ) + s i n ( ϕ ) s i n ( ψ ) c o s ( ϕ ) s i n ( θ ) s i n ( ψ ) s i n ( ϕ ) c o s ( ψ ) c o s ( ϕ ) c o s ( θ )
where E m = a I g , a I = [ x ¨ , y ¨ , z ¨ ] T and g = [ 0 , 0 , g ] T .
Let
b = c o s ( ϕ ) s i n ( θ ) c o s ( ψ ) + s i n ( ϕ ) s i n ( ψ ) c o s ( ϕ ) s i n ( θ ) s i n ( ψ ) s i n ( ϕ ) c o s ( ψ ) c o s ( ϕ ) c o s ( θ ) .
Taking normalization of two sides, we have
m T z E m | | m T z E m | | = b | | b | | .
It should be noticed that
| | b | | = c 2 ϕ s 2 θ c 2 ψ + s 2 ϕ s 2 ψ + c 2 ϕ s 2 θ s 2 ψ + s 2 ϕ c 2 ψ + c 2 ϕ c 2 θ = c 2 s 2 θ + s 2 + c 2 ϕ c 2 θ = c 2 s + s 2 = 1
where c 2 ϕ = c o s 2 ( ϕ ) , s 2 θ = s i n 2 ( θ ) , c 2 ψ = c o s 2 ( ψ ) , s 2 ϕ = s i n 2 ( ϕ ) , s 2 ψ = s i n 2 ( ψ ) , c 2 θ = c o s 2 ( θ ) . Thus, we hve
m T z E m | | m T z E m | | E n = E m | | E m | |
E n = c o s ( ϕ ) s i n ( θ ) c o s ( ψ ) + s i n ( ϕ ) s i n ( ψ ) c o s ( ϕ ) s i n ( θ ) s i n ( ψ ) s i n ( ϕ ) c o s ( ψ ) c o s ( ϕ ) c o s ( θ ) .
From our calculation, it can be seen that the vector E n = [ e n 1 , e n 2 , e n 3 ] T does not have the mass m and thrust T z . This simplifies our computation. Thus, we have the following equations
ϕ ^ = s i n 1 ( e n 1 s i n ( ψ ) + e n 2 c o s ( ψ ) )
θ ^ = s i n 1 ( e n 1 c o s ( ψ ) + e n 2 s i n ( ψ ) e n 3 2 + ( e n 1 c o s ( ψ ) + e n 2 s i n ( ψ ) ) 2 ) .
The estimated Euler angle should be calibrated by using the measured acceleration readings ϕ a c c e l , θ a c c e l . The working principle of using acceleration to estimate Euler angle is as follows.
We can obtain the acceleration information a b = [ a b x , a b y , a b z ] T and the gravity vector g . During the hovering state, by ignoring the effect of yaw, we have
a b = c o s ϕ 0 s i n θ s i n θ s i n ϕ c o s ϕ c o s θ s i n ϕ s i n θ c o s ϕ s i n ϕ c o s θ c o s ϕ g .
Thus, we have
ϕ a c c e l = a r c t a n ( a b y a b z )
θ a c c e l = a r c s i n ( a b x g )
The following calibration is used for estimating angles
ϕ ^ e s t = α ϕ ^ + ( 1 α ) ϕ a c c e l
θ ^ e s t = α θ ^ + ( 1 α ) θ a c c e l
where α is a factor which is a filter-like one. This factor is determined by training. The estimation of Euler angle is obtained.

4.4. Imu Fault Detection and Recovery Decision Mechanism

From the obtained LSTM neural network, we can obtain the estimated LSTM network error, that is y ˜ = y y ^ , where y is the sample data, and y ^ is the network output. Based on the statistic information, we can obtain a threshold given by
T h r e s h o l d = m e a n v a l u e + c o n s t d e v i a t i o n
where m e a n v a l u e represents the mean of the statistic information, d e v i a t i o n represents the standard deviation of the statistic information, and c o n s t is determined by users. The fault diagnosis mechanism regarding IMU sensor is given by
  • If the LSTM neural network estimated | | y ˜ | | > T h r e s h o l d , IMU has faults in angular rate;
  • otherwise, IMU has no fault occurrence. In this situation, the actual angular rate measurement is used.
Once the angular rate fault in IMU sensor is detected, the recovery should be made by using the proposed estimator. Figure 6 shows the angular rate estimator. The entire fault-tolerant control against sensor fault with diagnosis and recovery scheme is shown in Figure 7, where the fault diagnosis determines the switching between the sensor reading and recovery.

5. Simulation Experiments

The proposed AI-based FTC can be verified by our simulation. During the simulation, the IMU sensor is assumed to have a fault at a certain time and the recovery is triggered to maintain the drone control. The simulation studies below use the computer ThinkPad X390 which has the 8th Gen Intel Core processors. MATLAB and its Deep Learning Toolbox are used in the simulation. The toolbox is a framework developed by the MathWorks used in the development of deep neural networks, including the LSTM network.
The rate gyro fault is considered. The proposed LSTM estimator can predict Euler angle and angular rate by using the previous states. The structure of the proposed LSTM network is composed of 10 inputs, 288 hidden units, and 6 outputs. For the LSTM learning, we use the random number to generate the four rotor control signals which are fed into the quadrotor model of [14] to receive the six output states (three Euler angles and three angular rates). In total, 59,960 sample data are collected. These data are divided into two groups: training set and test set. The training set has 50,981 samples, while the test set has 8979 samples. For time series X k , X k 1 , . . . X k D , the delayed term D is 20. During the LSTM learning, it takes 158 epochs (about 592 min) satisfying the RMSE performance requirement. The convergence process is shown in Figure 8. For the training set, Figure 9 shows the estimates of Euler angles, while Figure 10 shows the estimates of angular rates (we zoom in the figure, having a better insight into the data). For the test set, Figure 11 shows the estimates of Euler angle, while Figure 12 shows the estimates of angular rate (we zoom in the figure, having a better insight into the data). It can be seen that the estimated values from the LSTM network closely match the sample data. This implies that the LSTM network can be used for estimating angular rate. Furthermore, the nonlinear estimator is designed by using (23) and (24), where the matrix L is selected as
L = 0.9 0 0 0 0.9 0 0 0 0.9 0.9 0 0 0 0.9 0 0 0 0.9
As our discussion before, when having IMU fault, Euler angle estimator is necessary for calibration. The calibration rules are shown in Equations (40) and (41), where the factor α = 0.95 . The estimated Euler angles are input to the LSTM network.
In the simulation, it is assumed that a fault at IMU (roll rate) occurs at time = 25 s, where the bias fault is introduced (the bias offset is 1.2 rad/s). The random noise with amplitude = 0.00025 rad/s is added in the simulation. Figure 13 shows the position (xyz) result, while Figure 14 shows the 2D (xy) result. It should be noticed that the tracking performance along x, y, z axes is good, even the IMU sensor fault occurrence. For the fault diagnosis, we use Figure 15 to demonstrate it, where the threshold is chosen as 1.01 rad/s. It can be seen that the sensor fault is detected immediately once it happens. Thus, both Euler angle and LSTM estimators are used. The roll rate signal is recovered by using the proposed scheme. For Euler angle estimation, the result is shown in Figure 16. It can be seen that the difference between both the estimated and actual angles is small. For the roll and pitch rate estimation, the result is shown in Figure 17. From the figure, it is found that the outputs of the LSTM network are close to the actual ones without fault occurrence. We also tested the control without considering gyroscope fault estimator when the bias fault happens. In this case, we do not use any gyroscope sensor handling. Figure 18 shows the control performance of the position along x,y,z axes, while Figure 19 shows the 2D position profile along x,y axes. It is observed that the control performance is poor without considering gyroscope sensor handling. From the figures, it is shown that the position along y-axis is out of control. This also proves that a FTC technology has to incorporate sensor fault processing unit such that the system can continue to be operated safely.
We consider another fault type—multiplication fault. In the simulation, it is assumed that the fault at IMU (roll rate) occurs at time = 25 s, where the roll rate multiplies by 2.8. For this kind of fault, Figure 20 shows the position (xyz) result, while Figure 21 shows the 2D (xy) result. It should be noticed that the tracking performance along x, y, z axes is still good, even with the fault occurrence. For the fault diagnosis, we use Figure 22 to demonstrate it, where the threshold is chosen as 1.01 rad/s. It can be seen that the sensor fault is detected immediately once it happens. Thus, both Euler angle and LSTM estimators are used. The roll rate signal is recovered by using the proposed scheme. For Euler angle estimation, the result is shown in Figure 23. It can be seen that the difference between both the estimated and actual angles is small. For the roll and pitch rate estimation, the result is shown in Figure 24. From the figure, it can be seen that the estimated angular rates are close to the actual ones. We also tested the control without considering the sensor estimator. In this case, we do not use any gyroscope sensor handling. Unfortunately, the attitude control is out of control at time = 27.28 s. Figure 25 shows the control result of Euler angle, where the maximum amplitudes of the roll, pitch and yaw angles are 79.25 rad (4557.3 deg), 33.02 rad (1891.9 deg) and 6.0074 × 10 4 rad (3.442 × 10 6 deg), respectively. Figure 26 shows the control result of angular rate. Obviously, a breakdown is observed from the angular rate control.
The proposed LSTM estimator of the angular rate requires to learn sequence data: Euler angle, angular rate and all rotor control signals. As discussed in the previous section, the LSTM is a complex unit which uses a model based on short-term memory processes to build longer-term memory. Two study cases have shown that Euler angle and angular rate can be estimated correctly. Even if during the drone control process, the IMU fault occurs, the designed scheme still can diagnose the fault and recover the sensor information. The drawback of the proposed scheme is that during the whole recovery process, the other sensors such as accelerometer and compass must be healthy.
Comments: In [13], the authors use the LSTM for the IMU fault diagnosis and recovery. However, the authors assume that Euler angles are available. This is not realistic because the Euler angle measurement is a fusion of gyroscope with accelerometer. This implies that Euler angle measurement is not reliable in this situation. The proposed method solves this issue by adding the Euler angle estimator.

6. Discussion and Conclusions

The development of sensor fault diagnosis and recovery is an important topic in the drone control. AI-based design in estimating the angular rate of IMU is still a challenge. The difficulty point is that the estimator also involves Euler angle compensation due to the IMU fault.
This paper has presented a FTC design method when having a IMU sensor fault. It is assumed that the sensor fault may have a bias or multiplication fault. The proposed LSTM neural network is adopted to perform the supervised learning. Since the IMU fault also affects Euler angle measurement, we have proposed to use the translational equations for calibrating Euler angle. The detailed simulation has be given to show the effectiveness of the proposed method. For future work, we will implement the proposed algorithm in a real quadrotor. Furthermore, we will develop an anti GPS spoofing scheme for UAV control.

Author Contributions

Conceptualization: S.H.; methodology: S.H.; software: S.H. supervision: F.L., R.S.H.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

This paper has been approved by Temasek Lab. on 21 September 2022 (Number is 2752).

Data Availability Statement

The attached data set is for LSTM training.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Huang, S.; Teo, R.S.H.; Leong, W.L.; Martinel, N.; Forest, G.L.; Micheloni, C. Coverage Control of Multiple Unmanned Aerial Vehicles: A Short Review. Unmanned Syst. 2018, 6, 131–144. [Google Scholar] [CrossRef]
  2. Huang, S.; Teo, R.S.H.; Tan, K.K. Collision avoidance of multi unmanned aerial vehicles: A review. Annu. Rev. Control 2019, 48, 147–164. [Google Scholar] [CrossRef]
  3. Zhang, X.; Ma, J.M.; Cheng, Z.; Huang, S.; de Silva, C.W.; Lee, T.H. Accelerated hierarchical admm for nonconvex optimization in multi-agent decision making. arXiv 2020, arXiv:2011.00463. [Google Scholar]
  4. Wu, Y.; Jiang, B.; Wang, Y. Incipient winding fault detection and diagnosis for squirrel-cage induction motors equipped on CRH trains. ISA Trans. 2020, 99, 488–495. [Google Scholar] [CrossRef] [PubMed]
  5. Li, L.; Yao, L. Incipient fault prediction based on generalised correntropy filtering for non-Gaussian stochastic systems. Int. J. Syst. Sci. 2021, 52, 3035–3043. [Google Scholar] [CrossRef]
  6. Chen, J.; Hu, N.; Zhang, L.; Chen, L.; Wang, B.; Zhou, Y. A method for broken rotor bars diagnosis based on sum-of-squares of current signals. Appl. Sci. 2020, 10, 5980. [Google Scholar] [CrossRef]
  7. Wu, Y.; Zhao, D.; Liu, S.; Li, Y. Fault detection for linear discrete time-varying systems with multiplicative noise based on parity space method. ISA Trans. 2022, 121, 156–170. [Google Scholar] [CrossRef] [PubMed]
  8. Kortela, J.; Jämsä-Jounela, S.-L. Fault-tolerant model predictive control (FTMPC) for the BioGrate boiler. In Proceedings of the 2015 IEEE 20th Conference on Emerging Technologies & Factory Automation, Luxembourg, 8–11 September 2015. [Google Scholar]
  9. Hagh, Y.S.; Asl, R.M.; Cocquempot, V. A hybrid robust fault tolerant control based on adaptive joint unscented Kalman filter. ISA Trans. 2017, 66, 262–274. [Google Scholar] [CrossRef] [PubMed]
  10. Salim, M.; Ahmed, S.; Khosrowjerdi, M.J. A data-driven sensor fault-tolerant control scheme based on subspace identification. Int. Robust Nonlinear Control 2021, 31, 6991–7006. [Google Scholar] [CrossRef]
  11. Khalastchi, E.; Kalech, M.; Kaminka, G.A.; Lin, R. Online datadriven anomaly detection in autonomous robots. Knowl. Inf. Syst. 2015, 43, 657–688. [Google Scholar] [CrossRef]
  12. Guo, K.; Liu, L.; Shi, S.; Liu, D.; Peng, X. Uav sensor fault detection using a classifier without negative samples: A local density regulated optimization algorithm. Sensors 2019, 19, 771. [Google Scholar] [CrossRef] [PubMed]
  13. Wang, B.; Liu, D.; Peng, Y.; Peng, X. Multivariate regression based fault detection and recovery of uav flight data. IEEE Trans. Instrum. Meas. 2020, 69, 3527–3537. [Google Scholar] [CrossRef]
  14. Huang, S.; Liao, F.; Teo, R. AI-based fault-tolerant controller design for handling both actuator and sensor faults of multirotors. In Proceedings of the 2022 International Conference on Unmanned Aircraft Systems (ICUAS), Dubrovnik, Croatia, 21–24 June 2022; pp. 599–607. [Google Scholar]
  15. Hermann, R.; Krener, A.J. Nonlinear controllability and observability. IEEE Trans. Autom. Control 1977, AC-22, 728–740. [Google Scholar] [CrossRef] [Green Version]
  16. Ding, Z.; Cheng, G. A new uniformly ultimate boundedness criterion for discrete-time nonlinear systems. Appl. Math. 2011, 2, 1323–1326. [Google Scholar] [CrossRef]
Figure 1. Quadrotor in cross (x) configuration.
Figure 1. Quadrotor in cross (x) configuration.
Machines 10 01088 g001
Figure 2. Architecture Overview of FTC.
Figure 2. Architecture Overview of FTC.
Machines 10 01088 g002
Figure 3. LSTM network used.
Figure 3. LSTM network used.
Machines 10 01088 g003
Figure 4. Modelling diagram of LSTM network.
Figure 4. Modelling diagram of LSTM network.
Machines 10 01088 g004
Figure 5. Algorithm flow chart.
Figure 5. Algorithm flow chart.
Machines 10 01088 g005
Figure 6. Sensor estimator.
Figure 6. Sensor estimator.
Machines 10 01088 g006
Figure 7. FTC against sensor fault with fault diagnosis.
Figure 7. FTC against sensor fault with fault diagnosis.
Machines 10 01088 g007
Figure 8. Convergence of the LSTM training.
Figure 8. Convergence of the LSTM training.
Machines 10 01088 g008
Figure 9. Estimated Euler angles of the LSTM training set: red line represents LSTM output; blue line represents sample output.
Figure 9. Estimated Euler angles of the LSTM training set: red line represents LSTM output; blue line represents sample output.
Machines 10 01088 g009
Figure 10. Estimated same angular rates of the LSTM training set: red line represents LSTM output; blue line represents sample output.
Figure 10. Estimated same angular rates of the LSTM training set: red line represents LSTM output; blue line represents sample output.
Machines 10 01088 g010
Figure 11. Estimated Euler angles of the LSTM test set: red line represents LSTM output; blue line represents sample output.
Figure 11. Estimated Euler angles of the LSTM test set: red line represents LSTM output; blue line represents sample output.
Machines 10 01088 g011
Figure 12. Estimated angular rates of the LSTM test set: red line represents LSTM output; blue line represents sample output.
Figure 12. Estimated angular rates of the LSTM test set: red line represents LSTM output; blue line represents sample output.
Machines 10 01088 g012
Figure 13. Bias fault: the position control performance (red line–desired, blue line–actual).
Figure 13. Bias fault: the position control performance (red line–desired, blue line–actual).
Machines 10 01088 g013
Figure 14. Bias fault: the 2D position control performance.
Figure 14. Bias fault: the 2D position control performance.
Machines 10 01088 g014
Figure 15. Bias fault: fault diagnosis result (red line–threshold, blue line–residual).
Figure 15. Bias fault: fault diagnosis result (red line–threshold, blue line–residual).
Machines 10 01088 g015
Figure 16. Bias fault: Euler angle estimation (red line–estimated angle, blue line–actual angle measurement).
Figure 16. Bias fault: Euler angle estimation (red line–estimated angle, blue line–actual angle measurement).
Machines 10 01088 g016
Figure 17. Bias fault: angular rate estimation (red line–estimated signal, blue line–faulty signal, green line–actual signal without fault occurrence).
Figure 17. Bias fault: angular rate estimation (red line–estimated signal, blue line–faulty signal, green line–actual signal without fault occurrence).
Machines 10 01088 g017
Figure 18. Bias fault: control result without sensor handling: the position profile (red line–desired, blue line–actual).
Figure 18. Bias fault: control result without sensor handling: the position profile (red line–desired, blue line–actual).
Machines 10 01088 g018
Figure 19. Bias fault: control result without sensor handling: the 2D position profile.
Figure 19. Bias fault: control result without sensor handling: the 2D position profile.
Machines 10 01088 g019
Figure 20. Multiplication fault: the position control performance (red line–desired, blue line–actual).
Figure 20. Multiplication fault: the position control performance (red line–desired, blue line–actual).
Machines 10 01088 g020
Figure 21. Multiplication fault: the 2D position control performance.
Figure 21. Multiplication fault: the 2D position control performance.
Machines 10 01088 g021
Figure 22. Multiplication fault: fault detection result (red line–threshold, blue line–residual).
Figure 22. Multiplication fault: fault detection result (red line–threshold, blue line–residual).
Machines 10 01088 g022
Figure 23. Multiplication fault: Euler angle estimation (red line–estimated angle, blue line–actual angle measurement).
Figure 23. Multiplication fault: Euler angle estimation (red line–estimated angle, blue line–actual angle measurement).
Machines 10 01088 g023
Figure 24. Multiplication fault: angular rate estimation (red line–estimated signal, blue line–faulty signal, green line–actual signal without fault occurrence).
Figure 24. Multiplication fault: angular rate estimation (red line–estimated signal, blue line–faulty signal, green line–actual signal without fault occurrence).
Machines 10 01088 g024
Figure 25. Multiplication fault: control result of Euler angle without sensor handling.
Figure 25. Multiplication fault: control result of Euler angle without sensor handling.
Machines 10 01088 g025
Figure 26. Multiplication fault: control result of angular rate without sensor handling.
Figure 26. Multiplication fault: control result of angular rate without sensor handling.
Machines 10 01088 g026
Table 1. Variables used for estimator design.
Table 1. Variables used for estimator design.
SymbolParameterUnit
ϕ Rollrad
θ Pitchrad
ψ Yawrad
pRoll raterad/s
qPitch raterad/s
rYaw raterad/s
ω 1 Motor 1’s speedrad/s
ω 2 Motor 2’s speedrad/s
ω 3 Motor 3’s speedrad/s
ω 4 Motor 4’s speedrad/s
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Huang, S.; Liao, F.; Teo, R.S.H. Fault Tolerant Control of Quadrotor Based on Sensor Fault Diagnosis and Recovery Information. Machines 2022, 10, 1088. https://doi.org/10.3390/machines10111088

AMA Style

Huang S, Liao F, Teo RSH. Fault Tolerant Control of Quadrotor Based on Sensor Fault Diagnosis and Recovery Information. Machines. 2022; 10(11):1088. https://doi.org/10.3390/machines10111088

Chicago/Turabian Style

Huang, Sunan, Fang Liao, and Rodney Swee Huat Teo. 2022. "Fault Tolerant Control of Quadrotor Based on Sensor Fault Diagnosis and Recovery Information" Machines 10, no. 11: 1088. https://doi.org/10.3390/machines10111088

APA Style

Huang, S., Liao, F., & Teo, R. S. H. (2022). Fault Tolerant Control of Quadrotor Based on Sensor Fault Diagnosis and Recovery Information. Machines, 10(11), 1088. https://doi.org/10.3390/machines10111088

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop