Next Article in Journal
GPS Multipath Analysis Using Fresnel Zones
Previous Article in Journal
Have I Seen This Place Before? A Fast and Robust Loop Detection and Correction Method for 3D Lidar SLAM
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Novel Fuzzy PID-Type Iterative Learning Control for Quadrotor UAV

College of Electronics and Information Engineering, Tongji University, Shanghai 200000, China
*
Author to whom correspondence should be addressed.
Sensors 2019, 19(1), 24; https://doi.org/10.3390/s19010024
Submission received: 17 November 2018 / Revised: 14 December 2018 / Accepted: 18 December 2018 / Published: 21 December 2018
(This article belongs to the Section Remote Sensors)

Abstract

:
Due to the under-actuated and strong coupling characteristics of quadrotor aircraft, traditional trajectory tracking methods have low control precision, and poor anti-interference ability. A novel fuzzy proportional-interactive-derivative (PID)-type iterative learning control (ILC) was designed for a quadrotor unmanned aerial vehicle (UAV). The control method combined PID-ILC control and fuzzy control, so it inherited the robustness to disturbances and system model uncertainties of the ILC control. A new control law based on the PID-ILC algorithm was introduced to solve the problem of chattering caused by an external disturbance in the ILC control alone. Fuzzy control was used to set the PID parameters of three learning gain matrices to restrain the influence of uncertain factors on the system and improve the control precision. The system stability with the new design was verified using Lyapunov stability theory. The Gazebo simulation showed that the proposed design method creates effective ILC controllers for quadrotor aircraft.

1. Introduction

The quadrotor [1,2,3], as a branch of unmanned aerial vehicles (UAVs), is highly favored in both military and civilian applications given its vertical take-off and landing ability, insensibility to varying environments, high mobility and stability, and easy operation modes. The quadrotor system is highly-coupled, under-actuated, and inherently non-linear, which challenges the system stability involving the microprocessor, the sensor, the mechanism, and the navigation and control algorithm. Over the past few years, much work has been completed on the modeling [4,5] and control [6,7,8] of the quadrotor UAV. The concept was introduced as early as 1907. Since then, the theoretical and experimental research results on the aspects of posture balance and perfect trajectory tracking have been extensively reported, such as adaptive control [9], fuzzy control [10], optimal control [11], and loop shaping theory [12]. Bouadi et al. [13] used a sliding mode control algorithm based on the reverse step to control the aircraft and derived the attitude angle from the higher-order nonholonomic constraints, but the change in the position loop was not used as feedback in real time. Shakev et al. [14] applied the linear feedback method to achieve the steady control of the quadrotor aircraft but did not consider aerodynamic interference. Courbon et al. [15] used novel navigation and positioning to control the quadrotor aircraft in position and attitude control.
The quadrotor UAV was chosen in this study as the research object. We attached importance to the UAV model and the control algorithm to improve the robustness and stability of the system. Considering uncertainty and random disturbance in the process of aircraft flight, we used the iterative learning control (ILC) method to improve system robustness. The ILC [16,17,18] method has a simple and clear form, and can also compensate for uncertainty, nonlinearity, coupling, modeling error, and other factors through the online learning process. The advantage of using ILC is that there is no need for accurate knowledge of the quadrotor aircraft or physical parameters of the system. However, there has been relatively little focus on the ILC of quadrotor aircraft. Angela et al. [19] applied ILC to the trajectory tracking of a quadrotor. Ma et al. [20] combined the ILC and PD algorithm for the attitude tracking control of a reference attitude trajectory. We think it will be extended to include the PID-ILC scheme for quadrotor systems in order to improve the tracking performance and vibration control.
Our proposed PID algorithm, which differs from the common PID algorithm [21,22,23] in the literature, uses the integral and differential of the derivative of the current error to improve the tracking performance of the system. Juan et al. [24] proposed a nonlinear robust PID controller for attitude regulation of the quadrotor. Ahmet et al. [25] presented a fault-tolerant PID control scheme for nonlinear quadcopter system to guarantee the stability of attitude and path control. Meanwhile, fuzzy control was added to the proposed algorithm. Fuzzy control [26,27,28] is fast and highly stable and can adjust the gain of the control algorithm according to the needs of the ILC to improve the convergence speed and tracking the accuracy of the ILC. The proposed scheme combines the PID-ILC with fuzzy control, and fuzzy control optimizes the parameters of the ILC law to find the optimal gain so that the algorithm can learn faster, and the system can accurately converge to the desired path with fewer iterations.
The paper is structured as follows: Section 2 depicts the complete model of the quadrotor UAV. Section 3 presents the fuzzy PID-ILC algorithm used to control the UAV. Section 4 presents the convergence analysis of the proposed algorithm. In Section 5, the Gazebo simulation results are provided. Finally, our conclusion is presented in Section 6.

2. Model for The Quadrotor UAV

The quadrotor model is described in this section. E = { X e , Y e , Z e } is the inertial coordinate system, B = { X b , Y b , Z b } is the body coordinate system, Φ = [ φ , θ , ψ ] T represents the Euler angle, and the rotation matrix from the inertial frame to the body frame is:
R = [ cos ψ cos θ cos ψ sin φ sin θ + cos φ sin ψ sin φ sin ψ cos ψ cos φ sin θ cos θ sin ψ cos φ cos ψ sin ψ sin φ sin θ sin ψ cos φ sin θ + sin φ cos ψ sin θ cos θ sin φ cos θ cos φ ]
According to Newton’s law of motion and the Euler equation, the dynamic equation of the quadrotor can be expressed as
F = m P ¨
M = d H / d t
where F is the external force on the quadrotor, m is the mass of the quadrotor, M is the rotational torque of the airframe, H is the angular momentum of the body under the inertial coordinate system, l represents the distance from the motor shaft to the center of the body, J r represents the inertia of the motor, f i ( i = 1 , 2 , 3 , 4 ) represents the lift provided by the i -th rotor, and b and d represent the lift and drag coefficients of the rotors, respectively. J represents the inertia matrix of the airframe, K dm represents the coefficient of rotational resistance moment, and K dt represents the coefficient of translational resistance. According to the structural characteristics of the quadrotor UAV, J , K dm , and K dt can be expressed as diagonal arrays:
J = [ I x 0 0 0 I y 0 0 0 I z ] , K dm = [ K dm x 0 0 0 K dm y 0 0 0 K dm z ] , K dt = [ K dt x 0 0 0 K dt y 0 0 0 K dt z ]
P = [ x , y , z ] T represents the position of the quadrotor centroid in the inertial coordinate system and Ω = [ p , q , r ] T represents the rotational angular velocity around three axes in the body coordinate system, expressed as
x ¨ = ( cos φ cos ψ sin θ + sin φ sin ψ ) m i = 1 4 f i K dt x m x ˙ y ¨ = ( cos φ sin ψ sin θ sin φ cos ψ ) m i = 1 4 f i K dt y m y ˙ z ¨ = cos φ cos θ m i = 1 4 f i K dt z m z ˙ g
p ˙ = [ q r ( I y I z ) + l b ( ω 4 2 ω 2 2 ) K dm x p + J r q ( ω 1 + ω 3 ω 2 ω 4 ) ] / I x q ˙ = [ p r ( I z I x ) + l b ( ω 3 2 ω 1 2 ) K dm y q + J r p ( ω 2 + ω 4 ω 1 ω 3 ) ] / I y r ˙ = [ q p ( I x I y ) + d ( ω 1 2 + ω 3 2 ω 4 2 ω 2 2 ) K dm z r ] / I z
where f i = b ω i 2 , ω = ω 1 ω 2 + ω 3 ω 4 , and ω i is the rotational angular velocity of the rotor of the i -th rotor. I x , I y , I z represent the axial inertial moment of the aircraft in the x, y, and z directions, respectively. Equations (5) and (6) describe the centroid translational motion and the body rotation motion of the quadrotor UAV, respectively. The following relationship exists between the Euler angular velocity and angular velocity in the body coordinate system:
[ φ ˙ θ ˙ ψ ˙ ] = [ 1 sin φ tan θ cos φ tan θ 0 cos φ sin φ 0 sin φ / cos θ cos φ / cos θ ] [ p q r ]
When the quadrotor is hovering or flying at low speeds indoors, we define vectors as U = [ u 1 u 2 u 3 u 4 ] T . u 1 , u 2 , u 3 , u 4 represent the lift torque, roll torque, pitch torque, and yaw torque of the aircraft, respectively, and are defined as:
u 1 = b ( ω 1 2 + ω 2 2 + ω 3 2 + ω 4 2 ) u 2 = b ( ω 2 2 ω 4 2 ) u 3 = b ( ω 1 2 ω 3 2 ) u 4 = d ( ω 1 2 ω 2 2 + ω 3 2 ω 4 2 )
The following simplified model of the quadrotor UAV can be obtained:
{ x ¨ = u 1 m ( sin ψ sin φ + cos ψ sin θ cos φ ) y ¨ = u 1 m ( cos ψ sin φ + sin ψ sin θ cos φ ) z ¨ = u 1 m cos θ cos φ + g φ ¨ = I y I z I x θ ˙ ψ ˙ J r I x θ ˙ ω + u 2 I x θ ¨ = I z I x I y φ ˙ ψ ˙ J r I y φ ˙ ω + u 3 I y ψ ¨ = I x I y I z φ ˙ θ ˙ + u 4 I z
where x , y , z , φ , θ , ψ represent the longitudinal displacement, lateral displacement, height, roll angle, pitch angle, and yaw angle of the aircraft, respectively, and g is the gravitational acceleration. The physical parameters for the quadrotor are provided in Table 1.
The quadrotor aircraft relies on the four rotors to generate lift and torque, enabling lifting, yaw, roll, pitch, lateral, and transverse movements. Its four propeller crosses are driven by four direct current (DC) motors, and motion in space is achieved by changing the speed of the four DC motors. The structure diagram of the quadrotor aircraft is shown in Figure 1.
To facilitate the formula derivation, we simplified the aircraft model. The state variable is x = ( x x ˙ y y ˙ z z ˙ ψ ψ ˙ θ θ ˙ φ φ ˙ ) , and the virtual input is U = ( U 1 U 2 U 3 U 4 U 5 U 6 ) . The mathematical model of the quadrotor was rewritten into an equation of the state format:
{ x ˙ 1 = x 2 x ˙ 2 = U 5 U 1 m x ˙ 3 = x 4 x ˙ 4 = U 6 U 1 m x ˙ 5 = x 6 x ˙ 6 = cos x 11 cos x 9 U 1 m g x ˙ 7 = x 8 x ˙ 8 = x 10 x 12 ( I x I y ) I z + U 4 I z x ˙ 9 = x 10 x ˙ 10 = x 8 x 12 ( I z I x ) I y + J r x 12 Ω I y + U 3 I y x ˙ 11 = x 12 x ˙ 12 = x 8 x 10 ( I y I z ) I x + J r x 10 Ω I x + U 2 I x
where U 5 = ( cos ϕ sin θ cos ψ + sin ϕ sin ψ ) and U 6 = ( cos ϕ sin θ cos ψ sin ϕ cos ψ ) . We divided the whole system into six relatively independent channels: height control, horizontal X-axis control, horizontal Y-axis control, roll control, pitch control, and yaw control.
The mathematical model of the height channel can be obtained by Equation (10):
{ x ˙ 5 = x 6 x ˙ 6 = cos x 11 cos x 9 U 1 m g
The desired height is z d = x 5 d and the tracking error is e 5 = x 5 d x 5 . We defined the Lyapunov function as V 5 = e 5 2 / 2 , and the derivative of the Lyapunov function is:
V ˙ 5 = e 5 e ˙ 5 = e 5 ( x ˙ 5 d x 6 )
Set x 6 = α 5 + e 6 , α 5 = x ˙ 5 d + k 5 e 5 , k 5 > 0 is parameter of control system and α 5 is the virtual control input. Equation (12) can be simplified as:
V ˙ 5 = e 5 e 6 k 5 e 5 2
We defined the new Lyapunov function as V 6 = V 5 + e 6 2 / 2 , and the derivative of this formula can be written as:
V ˙ 6 = V ˙ 5 + e 6 e ˙ 6 = k 5 e 5 2 + e 6 ( e ˙ 6 e 5 ) = k 5 e 5 2 + e 6 ( x ˙ 6 x ¨ 5 d k 5 e ˙ 5 e 5 ) = k 5 e 5 2 + e 6 ( cos x 11 cos x 9 U 1 m g x ¨ 5 d k 5 e ˙ 5 e 5 ) < k 5 e 5 2 k 6 e 6 2 < 0
So, we obtained this formula where U 1 = ( x ¨ 5 d + g ( k 5 + k 6 ) e 6 + ( 1 k 5 2 ) e 5 ) m cos x 11 cos x 9 , and the same is true for the other control channels, all k > 0 are parameters of control system.
U 2 = ( x ¨ 11 d ( k 11 + k 12 ) e 12 + ( 1 k 11 2 ) e 11 ) I x x 8 x 10 ( I y I z ) J r x 10 Ω U 3 = ( x ¨ 9 d ( k 9 + k 10 ) e 10 + ( 1 k 9 2 ) e 9 ) I y x 8 x 12 ( I z I x ) J r x 12 Ω U 4 = ( x ¨ 7 d ( k 7 + k 8 ) e 8 + ( 1 k 7 2 ) e 7 ) I z x 10 x 12 ( I x I y ) U 5 = ( x ¨ 1 d ( k 1 + k 2 ) e 2 + ( 1 k 1 2 ) e 1 ) m / U 1 U 6 = ( x ¨ 3 d ( k 3 + k 4 ) e 4 + ( 1 k 3 2 ) e 3 ) m / U 1
Substituting Equation (15) into Equation (10), the new mathematical system model of the quadrotor aircraft is:
{ x ˙ 1 = x 2 x ˙ 2 = ( k 1 + k 2 ) x 2 ( k 1 k 2 + 1 ) x 1 + x ¨ 1 d + ( k 1 + k 2 ) x ˙ 1 d + ( k 1 k 2 + 1 ) x 1 d x ˙ 3 = x 4 x ˙ 4 = ( k 3 + k 4 ) x 4 ( k 3 k 4 + 1 ) x 3 + x ¨ 3 d + ( k 3 + k 4 ) x ˙ 3 d + ( k 3 k 4 + 1 ) x 3 d x ˙ 5 = x 6 x ˙ 6 = ( k 5 + k 6 ) x 6 ( k 5 k 6 + 1 ) x 5 + x ¨ 5 d + ( k 5 + k 6 ) x ˙ 5 d + ( k 5 k 6 + 1 ) x 5 d x ˙ 7 = x 8 x ˙ 8 = ( k 7 + k 8 ) x 8 ( k 7 k 8 + 1 ) x 7 + x ¨ 7 d + ( k 7 + k 8 ) x ˙ 7 d + ( k 7 k 8 + 1 ) x 7 d x ˙ 9 = x 10 x ˙ 10 = ( k 9 + k 10 ) x 10 ( k 9 k 10 + 1 ) x 9 + x ¨ 9 d + ( k 9 + k 10 ) x ˙ 9 d + ( k 9 k 10 + 1 ) x 9 d x ˙ 11 = x 12 x ˙ 12 = ( k 11 + k 12 ) x 12 ( k 11 k 12 + 1 ) x 11 + x ¨ 11 d + ( k 11 + k 12 ) x ˙ 11 d + ( k 11 k 12 + 1 ) x 11 d
The system model of the quadrotor aircraft is simplified as:
{ x ˙ = A x + B u y = C x
where x = [ x x ˙ y y ˙ z z ˙ ψ ψ ˙ θ θ ˙ φ φ ˙ ] T , y = [ x y z ψ θ φ ] T , A is the system matrix, B is the input matrix, and C is the output matrix.

3. Controller Design for Quadrotor UAV

The designed iterative learning control algorithm in Figure 2 is
u k + 1 = u k + ς e k + γ e ˙ k + η e ¨ k
where e = [ e x e y e z e ψ e θ e φ ] T , e ˙ = [ e ˙ x e ˙ y e ˙ z e ˙ ψ e ˙ θ e ˙ φ ] T , e ¨ = [ e ¨ x e ¨ y e ¨ z e ¨ ψ e ¨ θ e ¨ φ ] T , and u = [ u x u y u z u ψ u θ u φ ] T . The three iterative learning gain matrices are expressed as ς = ς 0 + ς m , γ = γ 0 + γ m , η = η 0 + η m . ς 0 , γ 0 , and η 0 are the initial given values, and the fuzzy controller is used to adjust ς m , γ m , and η m .
The fuzzy controller in this paper has three parameters ς m , γ m , and η m as the output. e ( t ) = [ e x ( t ) e y ( t ) e z ( t ) e ψ ( t ) e θ ( t ) e φ ( t ) ] , e x ( t ) = x d ( t ) x k ( t ) , e y ( t ) = y d ( t ) y k ( t ) , e z ( t ) = z d ( t ) z k ( t ) , e ψ ( t ) = ψ d ( t ) ψ k ( t ) , e θ ( t ) = θ d ( t ) θ k ( t ) , and e φ ( t ) = φ d ( t ) φ k ( t ) . x d ( t ) , y d ( t ) , z d ( t ) and x k ( t ) , y k ( t ) , z k ( t ) represent the expected position coordinates and the actual position coordinates of the quadrotor aircraft of the k -th iteration, respectively. ψ d ( t ) , θ d ( t ) , φ d ( t ) and ψ k ( t ) , θ k ( t ) , φ k ( t ) represent the desired attitude angle and the actual attitude angle of the quadrotor aircraft in the k -th iteration, respectively. The fuzzy rules table is shown in Table 2. In these figures, PB is positive big, PM is positive middle, PS is positive small, NB is negative big, and ZO is zero. The rules of the controllers are expressed in Table 2 with all the possible combinations. Based on the control experience of the four-rotor aircraft, the fuzzy rules were established according to the output error of the system and the adjustment of the parameters. The membership function of the fuzzy controller is shown in Figure 3.

4. Convergence Analysis

In this section, the convergence condition of the controllers for the quadrotor aircraft system is given and proved.
Theorem 1.
The quadrotor aircraft system in Equation (17) meets the conditions:
( 1 )   I C B ( η 0 + η m ) ρ ¯ < 1
( 2 )   x k ( 0 ) = x 0 ,   e k ( 0 ) = 0 ,   e ˙ k ( 0 ) = 0 ,   k = 0 , 1 , 2 ,
Moreover, an approximation to the value of y k ( t ) y d ( t ) , obtained long before exact termination should occur, is often sufficient. Therefore, the following iteration termination criterion is chosen:
y d ( t ) y k ( t ) ε
where ε > 0 is a strict accuracy bound. After k iterations, it is possible to obtain an approximation y k ( t ) to y d ( t ) from the iteration procedure. Under the action of the proposed algorithm in Equation (18), when k , we obtained the conclusion of this theorem y k ( t ) y d ( t ) , t [ 0 , T ] .
Proof. 
The error variables are e ˙ k ( t ) = y ˙ d ( t ) y ˙ k ( t )
e ˙ k + 1 ( t ) = e ˙ k ( t ) 0 t C Φ ( t , τ ) B ( u k + 1 ( τ ) u k ( τ ) ) d τ = e ˙ k ( t ) 0 t C Φ ( t , τ ) B ( ( ς 0 + ς m ) 0 τ e ˙ k ( σ ) d σ + ( γ 0 + γ m ) e ˙ k ( τ ) + ( η 0 + η m ) e ¨ k ( τ ) ) d τ
By integration by parts, the formula can be obtained:
0 t G ( t , τ ) e ¨ k ( τ ) d τ = G ( t , τ ) e ˙ k ( τ ) | 0 t 0 t G ( t , τ ) t e ˙ k ( τ ) d τ = C ( t ) B ( t ) ( η 0 + η m ) e ˙ k ( t ) 0 t G ( t , τ ) t e ˙ k ( τ ) d τ
where G ( t , τ ) = C Φ ( t , τ ) B ( η 0 + η m ) .
Substitute Equation (23) into Equation (22)
e ˙ k + 1 ( t ) = [ I C ( t ) B ( t ) ( η 0 + η m ) ] e ˙ k ( t ) + 0 t G ( t , τ ) t e ˙ k ( τ ) d τ 0 t C Φ ( t , τ ) B ( τ ) ( γ 0 + γ m ) e ˙ k ( τ ) d τ 0 t 0 τ C Φ ( t , τ ) B ( τ ) ( ς 0 + ς m ) e ˙ k ( σ ) d σ d τ
Then, the norm of both sides of Equation (24) can be obtained:
e ˙ k + 1 ( t ) I C ( t ) B ( t ) ( η 0 + η m ) e ˙ k ( t ) + 0 t G ( t , τ ) t e ˙ k ( τ ) d τ + 0 t C Φ ( t , τ ) B ( τ ) ( γ 0 + γ m ) e ˙ k ( τ ) d τ + 0 t 0 τ C Φ ( t , τ ) B ( τ ) ( ς 0 + ς m ) e ˙ k ( σ ) d σ d τ I C ( t ) B ( t ) ( η 0 + η m ) e ˙ k ( t ) + 0 t b 1 e ˙ k ( τ ) d τ + 0 t 0 τ b 2 e ˙ k ( σ ) d σ d τ
where b 1 = max { sup t , τ [ 0 , T ] G ( t , τ ) t , sup t , τ [ 0 , T ] C Φ ( T , τ ) B ( τ ) ( γ 0 + γ m ) } and b 2 = sup t , τ [ 0 , T ] C Φ ( t , τ ) B ( τ ) ( ς 0 + ς m ) .
Multiplying both sides of Equation (14) by e λ t to compute the λ -norm, we obtain:
e ˙ k + 1 λ ρ ˜ e ˙ k λ
where ρ ˜ = ρ ¯ + b 1 ( 1 e λ t ) / λ + b 2 ( 1 e λ t ) 2 / λ 2 . We found a sufficiently large positive number λ , so we obtained ρ ˜ < 1 . Therefore, we could reasonably choose a group control parameter in order to reach the conclusion of this theorem lim k e ˙ k λ = 0 . □

5. Gazebo Environment Simulation

To demonstrate the tracking performance and robustness of the proposed ILC law, the overall system was tested using Gazebo simulations. The modeling of the Gazebo simulation does not depend on the mathematical model of the quadrotor itself or any special graphics package and can simulate various dynamic relationships between spatial objects in virtual space, which has the advantages of other simulation software. The physical parameters of the whole quadrotor system are shown in Table 1. The parameters of the fuzzy control laws are listed in Table 2. The simulation time is 45 s. The desired helical trajectory is P d = [ t / 2 cos ( t / 2 ) t / 2 sin ( t / 2 ) t / 10 ] . The external aerodynamic interference during the quadrotor flight is: d f = [ 0.1 sin ( 0.1 π t ) 0.15 cos ( 0.1 π t ) 0.12 cos ( 0.1 π t ) ] .
Figure 4 presents the model of the quadrotor aircraft in the Gazebo simulation environment. Figure 5 and Figure 6 show the three-dimensional (3D) trajectory tracking the result of the quadrotor. We can see almost asymptotic convergence toward the actual tracking trajectory after 10 iterations. Simulation results for each direction of the reference trajectories and initial conditions showed better tracking results. The fuzzy PID-ILC demonstrated remarkable performance in terms of control and stability of the system compared with the conventional PID-ILC algorithm. The maximum tracking errors in the x , y , z , φ , θ   and   ψ directions from iteration to iteration are depicted in Figure 7. Figure 8 shows the tracking errors in the last iteration controlled by both fuzzy PID-ILC and traditional PID-ILC. The fuzzy PID-ILC performed much better than the PID-ILC in terms of the convergence speed and tracking error reductions. In the presence of wind disturbances, there are smaller errors for the motions in all three directions controlled by the fuzzy PID-ILC. These results show the importance of fuzzy control. Therefore, the fuzzy PID-ILC algorithm has indicated its capability to solve the trajectory-tracking control problem experienced by quadrotor UAVs.

6. Conclusions

The novel fuzzy PID-ILC algorithm was successfully applied to the trajectory tracking of a quadrotor UAV. A simple fuzzy law to tune the PID-ILC gains was developed. The PID-ILC algorithm adjusts and produces a group of the optimal input compensation for each iteration so that the overall error is reduced and converges to a minimized tracking error. By comparing the results of the Gazebo simulation, fuzzy PID-ILC demonstrated its remarkable capability to not only maintain the stability of the system and reduce the shaking and concussion of the system but also to achieve perfect tracking of the trajectory. Future research directions will include applications of the fuzzy iterative learning algorithm for the selection of the controller parameters.

Author Contributions

J.D. conceived the model and algorithm, completed the simulation, and verified the validation of the algorithm; B.H. conducted the experiments.

Funding

This work was supported by the National Natural Science Foundation of China (Grant no. 61801330).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Xia, D.; Cheng, L.; Yao, Y. A Robust Inner and Outer Loop Control Method for Trajectory Tracking of a Quadrotor. Sensors 2017, 9, 2147. [Google Scholar] [CrossRef] [PubMed]
  2. Ryll, M.; Buelthoff, H.H.; Giordano, P.R. A Novel Overactuated Quadrotor Unmanned Aerial Vehicle: Modeling, Control, and Experimental Validation. IEEE Trans. Control Syst. Technol. 2015, 23, 540–556. [Google Scholar] [CrossRef] [Green Version]
  3. Park, J.; Kim, Y.; Kim, S. Landing Site Searching and Selection Algorithm Development Using Vision System and Its Application to Quadrotor. IEEE Trans. Control Syst. Technol. 2015, 23, 488–503. [Google Scholar] [CrossRef]
  4. Abdolhosseini, M.; Zhang, Y.M.; Rabbath, C.A. An Efficient Model Predictive Control Scheme for an Unmanned Quadrotor Helicopter. J. Intell. Robot. Syst. Theory Appl. 2013, 70, 27–38. [Google Scholar] [CrossRef]
  5. Alexis, K.; Nikolakopoulos, G.; Tzes, A. On trajectory tracking model predictive control of an unmanned quadrotor helicopter subject to aerodynamic disturbances. Asian J. Control 2014, 16, 209–224. [Google Scholar] [CrossRef]
  6. Kostas, A.; George, N.; Anthony, T. Switching model predictive attitude control for a quadrotor helicopter subject to atmospheric disturbances. Control Eng. Pract. 2011, 19, 1195–1207. [Google Scholar] [Green Version]
  7. Jaffery, M.H.; Shead, L.; Forshaw, J.L. Experimental quadrotor flight performance using computationally efficient and recursively feasible linear model predictive control. Int. J. Control 2013, 86, 2189–2202. [Google Scholar] [CrossRef]
  8. Moreno-Valenzuela, J.; Pérez-Alcocer, R.; Guerrero-Medina, M.; Dzul, A. Nonlinear PID-Type Controller for Quadrotor Trajectory Tracking. IEEE/ASME Trans. Mechatron. 2018, 23, 2436–2447. [Google Scholar] [CrossRef]
  9. Zhao, B.; Xian, B.; Zhang, Y. Nonlinear Robust Adaptive Tracking Control of a Quadrotor UAV Via Immersion and Invariance Methodology. IEEE Trans. Ind. Electron. 2015, 62, 2891–2902. [Google Scholar] [CrossRef]
  10. Basri, M.A.M.; Husain, A.R.; Danapalasingam, K.A. A hybrid optimal backstepping and adaptive fuzzy control for autonomous quadrotor helicopter with time-varying disturbance. Proceedings of the Institution of Mechanical Engineers, Part G. J. Aerosp. Eng. 2015, 229, 2178–2195. [Google Scholar]
  11. Basri, M.A.M.; Husain, A.R.; Danapalasingam, K.A. GSA-based optimal backstepping controller with a fuzzy compensator for robust control of an autonomous quadrotor UAV. Aircr. Eng. Aerosp. Technol. 2015, 87, 493–505. [Google Scholar] [CrossRef]
  12. Tnunay, H.; Abdurrohman, M.Q.; Nugroho, Y. Auto-tuning quadcopter using Loop Shaping. In Proceedings of the 2013 International Conference on Computer, Control, Informatics and Its Applications (IC3INA), Jakarta, Indonesia, 19–21 November 2013; pp. 111–115. [Google Scholar]
  13. Bouadi, H.; Bouchoucha, M.; Tadjine, M. Sliding m ode control based on backstep pin g approach for an UAV type-quadrotor. Int. J. Appl. Math. Comput. Sci. 2008, 4, 12. [Google Scholar]
  14. Shakev, N.G.; Topalov, A.V.; Kaynak, O. Comparative Results on Stabilization of the Quad-rotor Rotorcraft Using Bounded Feedback Controllers. J. Intell. Robot. Syst. 2012, 65, 389–408. [Google Scholar] [CrossRef]
  15. Courbon, J.; Mezouar, Y.; Guénard, N. Vision-based navigation of unmanned aerial vehicles. Control Eng. Pract. 2010, 18, 789–799. [Google Scholar] [CrossRef]
  16. Bolder, J.; Oomen, T. Rational Basis Functions in Iterative Learning Control-With Experimental Verification on a Motion System. IEEE Trans. Control Syst. Technol. 2015, 23, 722–729. [Google Scholar] [CrossRef]
  17. De Best, J.; Liu, L.; van de Molengraft, R. Second-Order Iterative Learning Control for Scaled Setpoints. IEEE Trans. Control Syst. Technol. 2015, 23, 805–812. [Google Scholar] [CrossRef] [Green Version]
  18. Zhu, Q.; Hu, G.-D.; Liu, W.-Q. Iterative learning control design method for linear discrete-time uncertain systems with iteratively periodic factors. IET Control Theory Appl. 2015, 9, 2305–2311. [Google Scholar] [CrossRef]
  19. Schoellig, A.P.; Mueller, F.L.; D’Andrea, R. Optimization-based iterative learning for precise quadrocopter trajectory tracking. Auton. Robot. 2012, 33, 103–127. [Google Scholar] [CrossRef]
  20. Ma, Z.; Hu, T.; Shen, L.; Kong, W.; Zhao, B.; Yao, K. An Iterative Learning Controller for Quadrotor UAV Path Following at a Constant Altitude. In Proceedings of the 34th Chinese Control Conference, Tokyo, Japan, 28–30 July 2015; pp. 4406–4411. [Google Scholar]
  21. Chen, Y.; He, Y.; Zhou, M. Decentralized PID neural network control for a quadrotor helicopter subjected to wind disturbance. J. Cent. South Univ. 2015, 22, 168–179. [Google Scholar] [CrossRef]
  22. Tao, Y.; Xie, G.; Chen, Y. A PID and fuzzy logic based method for Quadrotor aircraft control motion. J. Intel. Fuzzy Syst. Appl. Eng. Technol. 2016, 31, 2975–2983. [Google Scholar] [CrossRef]
  23. Qiao, J.; Liu, Z.; Zhang, Y. Modeling and GS-PID Control of the Quad-Rotor UAV. In Proceedings of the 2018 10th International Conference on Computer and Automation Engineering, Brisbane, Australia, 24–26 February 2018; pp. 221–226. [Google Scholar]
  24. Ortiz, J.P.; Minchala, L.I.; Reinoso, M.J. Nonlinear Robust H-Infinity PID Controller for the Multivariable System Quadrotor. IEEE Lat. Am. Trans. 2016, 14, 1176–1183. [Google Scholar] [CrossRef]
  25. Ermeydan, A.; Kiyak, E. Fault tolerant control against actuator faults based on enhanced PID controller for a quadrotor. Aircr. Eng. Aerosp. Technol. 2017, 89, 468–476. [Google Scholar] [CrossRef]
  26. Chang, W.-J.; Chen, P.-H.; Ku, C.-C. Mixed sliding mode fuzzy control for discrete-time non-linear stochastic systems subject to variance and passivity constraints. IET Control Theory Appl. 2015, 9, 2369–2376. [Google Scholar] [CrossRef]
  27. Jafari, R.; Yu, W. Fuzzy control for uncertainty nonlinear systems with dual fuzzy equations. J. Intell. Fuzzy Syst. Appl. Eng. Technol. 2015, 29, 1229–1240. [Google Scholar] [CrossRef]
  28. Cherrat, N.; Boubertakh, H.; Arioui, H. Adaptive fuzzy PID control for a quadrotor stabilisation. In Proceedings of the IOP Conference Series: Materials Science and Engineering, Bangkok, Thailand, 24–26 February 2018. [Google Scholar]
Figure 1. Quadrotor structure.
Figure 1. Quadrotor structure.
Sensors 19 00024 g001
Figure 2. System architecture of the fuzzy PID-ILC for the quadrotor.
Figure 2. System architecture of the fuzzy PID-ILC for the quadrotor.
Sensors 19 00024 g002
Figure 3. Fuzzy membership functions.
Figure 3. Fuzzy membership functions.
Sensors 19 00024 g003
Figure 4. The model of quadrotor aircraft in the Gazebo simulation environment.
Figure 4. The model of quadrotor aircraft in the Gazebo simulation environment.
Sensors 19 00024 g004
Figure 5. The flying process of the quadrotor aircraft in the Gazebo simulation environment.
Figure 5. The flying process of the quadrotor aircraft in the Gazebo simulation environment.
Sensors 19 00024 g005
Figure 6. Trajectory of the quadrotor flight.
Figure 6. Trajectory of the quadrotor flight.
Sensors 19 00024 g006
Figure 7. Maximum absolute values of the tracking error.
Figure 7. Maximum absolute values of the tracking error.
Sensors 19 00024 g007
Figure 8. The changing curves of the tracking errors in the final iteration.
Figure 8. The changing curves of the tracking errors in the final iteration.
Sensors 19 00024 g008
Table 1. Parameters of the quadrotor unmanned aerial vehicle (UAV).
Table 1. Parameters of the quadrotor unmanned aerial vehicle (UAV).
ParameterDescriptionValueUnit
mTotal quadrotor mass1kg
lQuadrotor radius length0.25m
IxMoment of inertia about X-axis4 × 10−3Kg·m2
IyMoment of inertia about Y-axis4 × 10−3kg·m2
IzMoment of inertia about Z-axis8 × 10−3kg·m2
ωmaxMaximum rotor speed200rad/s
gGravitational acceleration9.81ms2
Table 2. Fuzzy rules.
Table 2. Fuzzy rules.
ς m / γ m / η m e
NBZOPB
e θ NBPB/PS/PMPB/PS/PSPB/PS/PS
ZOPM/PM/PBPS/PB/PMPM/PM/PB
PBPB/PS/PSPB/PS/PSPB/PS/PM

Share and Cite

MDPI and ACS Style

Dong, J.; He, B. Novel Fuzzy PID-Type Iterative Learning Control for Quadrotor UAV. Sensors 2019, 19, 24. https://doi.org/10.3390/s19010024

AMA Style

Dong J, He B. Novel Fuzzy PID-Type Iterative Learning Control for Quadrotor UAV. Sensors. 2019; 19(1):24. https://doi.org/10.3390/s19010024

Chicago/Turabian Style

Dong, Jian, and Bin He. 2019. "Novel Fuzzy PID-Type Iterative Learning Control for Quadrotor UAV" Sensors 19, no. 1: 24. https://doi.org/10.3390/s19010024

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