10
0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information. This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEE Transactions on Industrial Electronics IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS Design, Implementation and Evaluation of a Neural Network Based Quadcopter UAV System Fan Jiang, Member, IEEE, Farhad Pourpanah, Member, IEEE, and Qi Hao, Member, IEEE Abstract —In this paper, a quadcopter UAV system based on neural network enhanced dynamic inversion control is proposed for multiple real-world application scenarios. A Sigma-Pi neural network (SPNN) is used as the compen- sator to reduce the model error and improve the system per- formance in the presence of uncertainties of UAV dynamics, payload and environment. Besides, we present a technical framework for fast and robust implementation of multi- purpose UAV systems, and develop a UAV control system evaluation testbed using a high-precision optical motion capture system. Both the simulation and experiment results demonstrate that the SPNN can reduce inversion errors related to UAV parameter uncertainties as well as tracking errors related to unknown disturbances and unmodeled dy- namics. With the help of an online NN learning mechanism, the entire system can achieve much higher accuracy in attitude and trajectory control than conventional PID-based control systems under varying flight conditions. Index Terms—Unmanned aerial vehicles, Control sys- tems, Neural network applications I. I NTRODUCTION U NMANNED Aerial Vehicles (UAVs) have been widely used in many applications, such as surveillance and reconnaissance, power-line inspection, precision agriculture, environment monitoring, as well as rescue and disaster man- agement. Recently, multirotor UAVs have attracted a lot of industrial attention. Main advantages of those UAVs include low cost, simple structure, high maneuverability, vertical take- off and landing ability, long loiter time, and easy maintenance [1] [2]. However, developing long-range, high-payload, all- weather, industrial grade multirotor UAVs requires extensive innovations in material, structure, motors and sensors, operat- ing system and, especially, flight control algorithms. To develop a robust flight controller, several issues must be taken into account such as external disturbances, delays in processing and communication, and actuator degradation Manuscript received Jun. 28, 2018; revised Oct. 31, 2018; accepted Feb. 14, 2019. This work is partly supported by National Natural Science Foundation of China (No. 61773197), the Science and Technology In- novation Commission of Shenzhen (No. CKFW2016041415372174 and No. GJHZ20170314114424152), and the Nanshan District Science and Technology Innovation Bureau (No. LHTD20170007). (Corresponding author: Qi Hao) Fan Jiang and Qi Hao are with the Department of Computer Science and Engineering, Southern University of Science and Technology, Shen- zhen China, 518055. (Email: {hao.q,jiangf}@sustc.edu.cn) Farhad Pourpanah is with the College of Mathematics and Statistics, Shenzhen University (SZU), China. [3]. Most quadcopters employ a two-stage controller scheme, with the inner loop controlling attitude and the outer loop controlling the position. This allows the stabilization of the aircraft without requiring a position feedback. Various control mechanisms have been developed for the position and atti- tude control of multirotor UAVs, from proportional integral- derivative (PID) control [4] to linear quadratic regulators (LQRs) [5], dynamic inversion [6], fuzzy control [7], back- stepping and sliding-mode control [8], just to name a few. To control the under-actuated, multi-inputs and strong coupling quadrotor UAV systems, conventional controllers have to be incorporated with intelligent tuning schemes to achieve the balance between robustness and adaptability of the system. For example, PID control algorithms have been extensively used in UAV control systems due to their simple implementation and flexible tuning. However, they suffer from many drawbacks, including: 1) the PID controller is a linear and low-bandwidth control system, which cannot adapt well to highly nonlinear systems with strong, high-frequency disturbances, while the multirotor UAV platform is nonlinear, and further complicated by flight tasks and the changing environment [9] [10]. 2) the dynamics of sensors and actuators are usually ne- glected in the control design [4], which causes problems in real world implementation, e.g., delay in response, inaccuracy in command following; 3) there are a variety of uncertainties such as loading varia- tions, external disturbances, and changing plant parame- ters, which classic PID control techniques cannot handle well. Dynamic inversion is an effective approach to control both linear and nonlinear systems by directly reducing the com- plexity of the system dynamics [6]. The method adapts well to the environmental changes, and hence is suitable for high maneuverability control problems [11]. However, due to its high sensitivity to the variations of plant parameters, a com- plementary feedback control mechanism is usually required to improve the system robustness and stability. The inclusion of Artificial Neural Networks (ANNs) can solve this problem [12] [13]. ANNs are able to reduce the inversion error [14], and compensate various uncertainties [10], despite many im- plementation issues. The integration of ANNs into multirotor UAV control systems can be classified into two groups: NN-based es-

Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

  • Upload
    others

  • View
    2

  • Download
    0

Embed Size (px)

Citation preview

Page 1: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

Design, Implementation and Evaluation of aNeural Network Based Quadcopter UAV System

Fan Jiang, Member, IEEE, Farhad Pourpanah, Member, IEEE,and Qi Hao, Member, IEEE

Abstract—In this paper, a quadcopter UAV system basedon neural network enhanced dynamic inversion control isproposed for multiple real-world application scenarios. ASigma-Pi neural network (SPNN) is used as the compen-sator to reduce the model error and improve the system per-formance in the presence of uncertainties of UAV dynamics,payload and environment. Besides, we present a technicalframework for fast and robust implementation of multi-purpose UAV systems, and develop a UAV control systemevaluation testbed using a high-precision optical motioncapture system. Both the simulation and experiment resultsdemonstrate that the SPNN can reduce inversion errorsrelated to UAV parameter uncertainties as well as trackingerrors related to unknown disturbances and unmodeled dy-namics. With the help of an online NN learning mechanism,the entire system can achieve much higher accuracy inattitude and trajectory control than conventional PID-basedcontrol systems under varying flight conditions.

Index Terms—Unmanned aerial vehicles, Control sys-tems, Neural network applications

I. INTRODUCTION

UNMANNED Aerial Vehicles (UAVs) have been widelyused in many applications, such as surveillance and

reconnaissance, power-line inspection, precision agriculture,environment monitoring, as well as rescue and disaster man-agement. Recently, multirotor UAVs have attracted a lot ofindustrial attention. Main advantages of those UAVs includelow cost, simple structure, high maneuverability, vertical take-off and landing ability, long loiter time, and easy maintenance[1] [2]. However, developing long-range, high-payload, all-weather, industrial grade multirotor UAVs requires extensiveinnovations in material, structure, motors and sensors, operat-ing system and, especially, flight control algorithms.

To develop a robust flight controller, several issues mustbe taken into account such as external disturbances, delaysin processing and communication, and actuator degradation

Manuscript received Jun. 28, 2018; revised Oct. 31, 2018; acceptedFeb. 14, 2019. This work is partly supported by National Natural ScienceFoundation of China (No. 61773197), the Science and Technology In-novation Commission of Shenzhen (No. CKFW2016041415372174 andNo. GJHZ20170314114424152), and the Nanshan District Science andTechnology Innovation Bureau (No. LHTD20170007). (Correspondingauthor: Qi Hao)

Fan Jiang and Qi Hao are with the Department of Computer Scienceand Engineering, Southern University of Science and Technology, Shen-zhen China, 518055. (Email: {hao.q,jiangf}@sustc.edu.cn)

Farhad Pourpanah is with the College of Mathematics and Statistics,Shenzhen University (SZU), China.

[3]. Most quadcopters employ a two-stage controller scheme,with the inner loop controlling attitude and the outer loopcontrolling the position. This allows the stabilization of theaircraft without requiring a position feedback. Various controlmechanisms have been developed for the position and atti-tude control of multirotor UAVs, from proportional integral-derivative (PID) control [4] to linear quadratic regulators(LQRs) [5], dynamic inversion [6], fuzzy control [7], back-stepping and sliding-mode control [8], just to name a few. Tocontrol the under-actuated, multi-inputs and strong couplingquadrotor UAV systems, conventional controllers have to beincorporated with intelligent tuning schemes to achieve thebalance between robustness and adaptability of the system. Forexample, PID control algorithms have been extensively used inUAV control systems due to their simple implementation andflexible tuning. However, they suffer from many drawbacks,including:

1) the PID controller is a linear and low-bandwidth controlsystem, which cannot adapt well to highly nonlinearsystems with strong, high-frequency disturbances, whilethe multirotor UAV platform is nonlinear, and furthercomplicated by flight tasks and the changing environment[9] [10].

2) the dynamics of sensors and actuators are usually ne-glected in the control design [4], which causes problemsin real world implementation, e.g., delay in response,inaccuracy in command following;

3) there are a variety of uncertainties such as loading varia-tions, external disturbances, and changing plant parame-ters, which classic PID control techniques cannot handlewell.

Dynamic inversion is an effective approach to control bothlinear and nonlinear systems by directly reducing the com-plexity of the system dynamics [6]. The method adapts wellto the environmental changes, and hence is suitable for highmaneuverability control problems [11]. However, due to itshigh sensitivity to the variations of plant parameters, a com-plementary feedback control mechanism is usually requiredto improve the system robustness and stability. The inclusionof Artificial Neural Networks (ANNs) can solve this problem[12] [13]. ANNs are able to reduce the inversion error [14],and compensate various uncertainties [10], despite many im-plementation issues.

The integration of ANNs into multirotor UAV controlsystems can be classified into two groups: NN-based es-

Page 2: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

TABLE ICOMPARISION OF CONTROL SCHEMES IN QUAD-ROTORS

Characteristics Robust Adaptive Precision DisturbanceRejection

ImplementationDifficulty Notes

PID Yes No + + - A low-order controller, model-free, easy to implement, incapable of dealing withhigh-order dynamics

LQR No No ++ - + A high-order controller, model-based, easy to design and hard to implement,incapable of dealing with uncertainties

H∞ Yes Yes ++ ++ ++ A robust high-order controller, model-based, hard to design and implement,incapable of adaptive tuning

Sliding Mode Yes Yes ++ +++ ++ A nonlinear robust controller, model-free, hard to design a suitable sliding mode

Backstepping Yes Yes* ++ ++ ++ A robust nonlinear controller, model-based, high computational-complexity toimplement, incapable of dealing with disturbances

MPC Cond. No +++ ++ +++ A high-order open-loop control, model-based, high computational-complexity;sensitive to uncertainties

Dynamic Inversion No No ++ - + A open-loop compensator, model-based, easy to design and implement,sensitivity to uncertainties and disturbances

DI with SPNN Yes Yes ++ ++ + A robust adaptive compensator, partly model-based, easy to design andimplement, capable of rejecting disturbances and model errors

timator/compensator [12] [15] [16] and NN-based (eitheradaptive or hierarchical) full-state feedback [17]. NN basedestimators/compensators work as an adaptive estimator, whichestimate strong disturbance models such as plant variations,gusts or periodical disturbances, and then utilize closed-loopfeedforward output to cancel these modeled disturbances. Sucha method does not change the stability of the control system,and improves the system performance without requiring labor-consuming parameter tuning process.

Due to the intrinsic multi-modalities of multirotor UAVs,Gaussian potential function networks (GPFNs) [10], fuzzyNNs (FNNs) [18], [19], and dual NNs [20] have been em-ployed to control the multi-variable nonlinear flight systems.Under these schemes, both global and local optimization areused to achieve the trade-off between stability margin andoptimal performance: the global search for optimal controlparameters can be performed by using offline random opti-mization methods such as Particle Swarm Optimization (PSO)[18]; local control parameter optimizations are performed byusing online gradient based methods to achieve fast conver-gence [10], [19].

Several types of ANNs have been used to adaptively com-pensate the dynamic inversion errors, such as single hiddenlayer neural networks (SHLNNs) [21], multi-layer perceptrons(MLPs) [22], fuzzy-based neural networks [23], and Sigma-Pi neural network (SPNNs) [24]. Among them, SPNNs arepopular owing to its simple structure and fast convergencefor online adaptation [3] [13] [25] [26]. A comparison ofexisting control methods with SPNN is presented in Table I.The SPNNs are advantageous in that they can compensatethe inversion errors and external disturbances by adjusting theweights in real time through a simple control law with a guar-anteed Lyapunov convergence for bounded inputs [14] [24].Despite the superior theoretical advantages, most of the worksin SPNN-based control of multirotors are of simulation, andfew work has been done with the real-world implementationand benchmarking for multirotor UAVs, due to the shortageof computing power of existing open-source controllers, thecomplexity associated with real-time neural network imple-mentations, and many other technical challenges.

In this paper, a SPNN-augmented dynamic inversion con-

troller is proposed to improve the UAV flight control per-formance. The robust performance of the proposed controlmethods are verified through Hardware-In-The-Loop (HITL)simulations and real-world experiments evaluated by a high-precision optical motion capture system. To further simplifythe computational complexity of the real-time implementationwithin the UAV, extensive software optimizations are em-ployed to the initialization of nonlinear base functions and thefeedback tuning of ANN weights, which turns out to achievesatisfactory performance in both simulations and experiments.

The major contributions of this research include1) developing an efficient SPNN-based approach to mini-

mize dynamic inversion error, and handle the externaldisturbances and uncertainties,

2) developing a systematic framework for adaptive flightcontrol of quadrotor UAVs,

3) developing a systematic framework for quadrotor UAVsystem implementations with real-world applications,

4) developing a set of hardware and software tools to helpimplement and fine-tune the control algorithm in low-cost, commercially-available platforms, and

5) developing a reliable multirotor UAV system evaluationenvironment for benchmarking performance metrics.

The remaining of this paper is organized as follows. Section IIsets up the whole control system and states the control prob-lem. Section III and IV gives details of the proposed NN-baseddynamic inversion control system. Section V provides bothsimulation and experimental results, and gives discussions.Section VI concludes the paper and suggests future work.

II. SYSTEM SETUP AND PROBLEM STATEMENT

In this section, the dynamics of quadrotor UAV is explainedfirst, and then the structure of conventional PID control isdescribed in detail, finally the problem statement is presented.

A. Quadrotor DynamicsAs shown in Fig. 1, a quadrotor UAV is an underactuated

system with six degrees of freedom (DOF) [27], where E ={xe, ye, ze} and B = {xb, yb, zb} indicate inertial and bodyframes, respectively. x = (x, y, z)T represents the position

Page 3: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

𝑥𝑏𝑦𝑏

𝑧𝑏

𝑂𝑏𝜙

𝑝

𝑢

𝑥𝑒 𝑦𝑒

𝑂𝑒

𝑧𝑒

𝑟

𝑞

𝑤

𝑣

𝜓

𝜃

Fig. 1. A basic model of quadrotor UAVs.

and V = (u, v, w)T represents the velocity of the quadrotor.Similarly, Θ = (φ, θ, ψ)T and ω = (p, q, r)T indicate theattitude and rotational velocity of the quadrotor, respectively.The rotation matrix, Ce

b , for transforming coordinates from Eto B is given as follows [28]:

Ceb =

cθcψ − sφsψsθ −cφsψ cψsθ + cθsφsψcθsψ + cψsφsθ cφcψ sψsθ − cψcθsφ−cφsθ sφ cφcθ

(1)

where s(.) and c(.) denote sin(.) and cos(.), respectively. Theangular velocity of the UAV in the body frame are related tothe derivatives of the roll, pitch, and yaw angles according to[28]: pq

r

=

cθ 0 −cφsθ0 1 sφsφ 0 cφcθ

φθψ

(2)

According to Newton’s second law, the transitional dynam-ics equation of the center of mass (CoM) of the UAV can bewritten as [28]:

d(mv)

dt=−→F (3)

where m is the mass of the UAV and−→F is the total force

which contains gravity (FG), drag force (FD) and forces fromall rotors (FT ). The drag force can be written as:

FD = −kdx (4)

where kd are the drag coefficients. The force of each rotorcan be described as:

Fi = kFw2i (5)

where wi is the angular speed of the i-th rotor and kF is acoefficient that can be adjusted by experiments or simulations.The total force from rotors, which is in -z direction, can bedetermined as follows:

F bT =[0 0 k(w2

1 + w22 + w2

3 + w24)]T

(6)

where k is lift coefficient of the rotor. In the inertial frame,the lift force can be written as:

FT = CebFbT (7)

And, the motion can be written as:

mx =[0 0 −mg

]T+ FT + FD (8)

where g is the gravitational acceleration constant. In additionto force, each rotor generates a vertical moment to the planerotation of propellers, which is:

Mi = kMw2i (9)

where kM is moment constant. Two rotors, i.e., 1 and 3, rotatein -zb direction, while other two rotors, i.e., 2 and 4, rotate in zbdirection. Thus, the angular acceleration using Euler equationscan be written as [28]:

I

pqr

= I

L(F2 − F4)L(F3 − F1)

M1 −M2 +M3 −M4

−pqr

× Ipqr

(10)

which can be written as [28]:

I

pqr

= I

0 L 0 −L−L 0 L 0γ −γ γ −γ

F1

F2

F3

F4

−pqr

×Ipqr

(11)

where γ = kMkF

and L is the distance between CoM androtors.

Note for quadcopter frames with alternative motor configu-rations (X-shaped, etc.), it is always possible to map the motorthrust to fit the form shown in Eq. 11.

B. Conventional PID controlAs shown in Fig. 2, the control system of UAV contains

two loops: (i) inner loop, and (ii) outer loop. These two loopsare described as follows:

Attitude controller (inner loop): this loop controls the at-titude of the UAV, and the relationship between the angularacceleration and the torque acting on the UAV can be describedas

Θ = Mτ/I (12)

The pseudo control can be written as [13]

Uτ = Kp(Θd−Θ)+Kd(Θd−Θ)+Ki

∫(Θd−Θ)dΘ (13)

where the attitude Θd is desired attitude angular, and Θ isthe output of the plant dynamics which can be measured bysensors.

Position controller (outer loop): this loop controls the po-sition of UAV. The relationship between acceleration of theCoM and the force acting on the UAV can be described as:

x = FT /m (14)

Similarly, the pseudo control can be written as [13]

UT = Kp(xd − x) + Kd(xd − x) + Ki

∫(xd − x)dx (15)

Then the desired value of φ and θ are:

φd = arcsin(mT (sψdUx − cψdUy))

θd = arcsin( (Uxm−Tsψdsφd)Tcψdcφd

)(16)

where:T = m

√U2x + U2

y + (Uz + g)2

Page 4: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

[xd, yd, zd] +

PositionControl(PID)

AttitudeControl

(Angle PI)

AttitudeControl

(Angular Speed PID)

++

[φ, θ, ψ, φ, θ, ψ][φ, θ, ψ]

[φd, θd, ψd]Mt

E−1

FT

Quad UAVDynamics

AttitudeObserver

PositionObserver

[x, y, z, x, y, z]

[φd, θd]

ψd

Attitude Control Loop(Inner Loop)

Fig. 2. The PID-based UAV attitude control loop.

[xd, yd, zd] +

PositionControl(PID)

AttitudeControl

(Angle PI)

AttitudeControl

(Angular Speed PID)

++

[φ, θ, ψ, φ, θ, ψ][φ, θ, ψ]

[φd, θd, ψd]Mt

E−1

FT

Quad UAVDynamics

AttitudeObserver

PositionObserver

[x, y, z, x, y, z]

[φd, θd]

ψd

Attitude Control Loop

(Inner Loop)

DynamicInversion

Upid

Ud

UNN

+

+ −

NeuralNetwork X

U

bias

U

−Γ(eTPb)β W

Fig. 3. The NN compensator based UAV attitude control loop.

C. Problem Statement

In this paper, to design and implement robust control sys-tems for quadrotor UAVs, the following technical challengeshave to be addressed:

1) How to design a dynamic inversion model to improve theperformance of PID controllers.

2) How to integrate a Sigma-Pi NN with the dynamic inver-sion model to enhance the performance of the controlleragainst unmodeled dynamics, parameter mismatch andwind perturbations.

3) How to implement the Sigma-Pi NN based dynamicinversion control system in real-world applications.

III. NEURAL NETWORK-BASED DYNAMIC INVERSIONFLIGHT CONTROL

In this section, structures of dynamic inversion, and pro-posed NN-based dynamic inversion models are described indetail.

A. Dynamic Inversion

Consider the UAV control system as a nonlinear controlsystem with n degrees of freedom (DOF), which can bedescribed as

x = f(x, x, δ) (17)

where x, x are state variables, δ is control variable, and f mapscontrol variable to state variables. It is convenient to define thepseudo control variable U = x. So

U = f(x, x, δ) (18)

If f is an invertible mapping with δ, then

δ = f−1(x, x, U) (19)

If f describes the model of the quadrotor, the inverse of f isprecisely equal to the control variable. In fact, f is an analyticalmodel for dynamics of quadrotor. To offset the analyticalmodel of the quadrotor, δ can be defined as

δ = f−1(x, x, U) (20)

Then the control system of quadrotor can be described as

x = U + ∆(x, x, δ) (21)

where∆(x, x, δ) = f(x, x, δ)− f−1(x, x, U)

and ∆ represents the inversion error.

B. Neural Network Augmented Dynamic Inversion

Since the approximate dynamic model of quadrotor hasbeen deduced in Section III, the inversion model can be usedto linearize the nonlinear system, and guarantee the stability

Page 5: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

and reliability of the system. Moreover, to eliminate the errorcaused by the dynamics model, a neural network is added toadaptively compensate the inversion error online (shown inFig. 3).

U = UPID + Ud − UNN (22)

where UPID is the PID pseudo control of the inner loop, Ud =xd is the desired acceleration vector and UNN is the outputof the NN to cancel the inversion error ∆.

UNN = WTβ(X,U) (23)

where W is the weights of the NN, and β is the basis function.By substituting Eq. 22 into Eq. 21, and setting KI = 0, thesystem can be described as:

˜x+KP (˜x) +KD(x) = UNN −∆ (24)

where ˜x = xd − x.The error vector in the pitch channel can be written as:

e = Ae+ b(UNN −∆θ) (25)

where b=[0 1]T , e=[θ ˙θ] and:

A =

[0 1−KP −KD

](26)

The corresponding weight error can be described as:

W = W −W ∗ (27)

where W ∗ is the ideal weight. The error vector can be writtenas:

e = Ae+ bWTβ + b(W ∗Tβ −∆θ) (28)

Similar results can be obtained for roll and yaw channelsusing the same approach.

C. Sigma-Pi Neural Network

The structure of the single-layer Sigma-Pi NN, shown inFig. 4, can be written as:

Unn =n∑i=1

wiβi(X, v) = WTβ(X, v) (29)

where X denotes the normalized states, w represent thenetwork weights, and β is a vector of the basis function whichis composed of a combination of the elements X1, X2, X3 bymeans of the Kronecker product, that is

β = kron(kron(X1, X2), X3) (30)

The update law for the NN can be written as:

˙W = W = −Γ(eTPb)β (31)

where the learning rate Γ = ΓT > 0 and

P =

[KD

KP+ 1

2KD

12KP

12KP

1+KP

2KPKD

](32)

, where P is the positive matrix in the Lyapunov equation forthe linear error system with the NN weights [12].

Note that the same NN is applied to each of the channels(roll, pitch and yaw) with different weights wT .

For parallel augmentation tasks, the initial weight vector isset to W0 = 0 + σ, where |σ| � |det(P )|.

The on-line learning process is illustrated in Algorithm 1,whose time complexity is O(N), where N =

∣∣X1

∣∣× ∣∣X2

∣∣×∣∣X3

∣∣ is the number of neurons.

Algorithm 1 The neural network adaptationInput: State X , Pseudo control U , Weights W , Set of bases

β(X,U)Output: NN output UNN

1: W = W0 = 0 + σ . Initialization2: while System is normal do3: Get next states X , U4: UNN = WTβ(X,U)5: W = −Γ(eTPb)β . Weight feedback6: W = W + W ·∆t . Adjust for step time7: end while

D. Tuning of Hyperparameters

Algorithm 2 Searching for the best learning rateInput: Upper bound of learning rate Γ, Precision σOutput: Optimal learning rate ΓRequire: Γ ≥ Γ, σ > 0

1: while Γ > σ do2: Γ = 1

2Γk3: if Γ is successful in HITL test then4: Γk+1 = Γ+Γk

25: else6: Γk+1 = Γ7: end if8: Γ = |Γk+1 − Γk|9: end while

10: Γ = Γk+1

The stability and performance of the Sigma-Pi neural net-work is closely tied with the learning rate Γ. However, Γ isonly a max-bounded arbitrary unit-less number that is depen-dent on hard-to-determine factors like the maximum allowedtracking error and PID coefficients [14], and we discoveredthat the system is unstable if we simply use the theoreticalmaximum bound. To tackle this problem, a parameter search isperformed using our HITL simulator to find the optimal valuefor Γ. Namely, the simulated system is asked to perform acomplex flight trajectory with a descending Γ, and the learningrate with the best flight envelope is chosen. The algorithm isshown in Algorithm 2.

IV. SYSTEM DESIGN AND IMPLEMENTATION

Many technical issues have to be solved for engineering aplatform that can run the proposed sophisticated algorithms inreal time. For a realistic flight control system, the followingengineering goals should be achieved:

Page 6: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

X1

X2

X3

1

1

1

X11

X21

X31

· · ·X12

X22

X32

X1n

X2n

X3n

· · ·

· · ·

×wT

X(t)

State Variables

Wind DistubanceModeling ErrorSensor Error

es(X, t)

Error System Dynamicses(X, U, t)

e(X, t)−Γ(eTPb)β

Estimated Dynamics

Approximation ErrorLyapunov -stableWeight Adaptation

w

Fig. 4. The structure of a Sigma-Pi neural network.

1) The ability to autonomously carry out missions in the realworld with real-time telemetry;

2) The ability to work in dense formations with stablecommunication links;

3) The ability to agilely adapt to both indoor and outdoorenvironments;

4) Size, Weight, Power and Cost (SWaP-C).As an example, we designed a fully customizable industrialgrade UAV system, whose system specifications and designparameters are shown in Table II. Besides, we developed asingle-chip integrated flight controller system (FCS), calledBFLIGHT, shown in Fig. 5.

The design of the UAV itself involves many aspects thatcontradicts each other. In fact, the algorithms, hardware andsoftware developed in this paper are all for furfilling thedesign specifications. For example, the reason to develop aCOTS SoC-based single-chip flight controller is that we needto minimize the cost and the weight to make space for thepayload.

The structural stability is an important factor in the designof a quadcopter UAV. It depends on both the mechanicaldesign and the material used. In our design process, we usedFinite Element Analysis (FEA) to simulate the UAV structureunder different motor power to insure the integrity of thevehicle framework. However, FEA cannot replace real-worldexperiments as commercially-available materials usually havedifferent properties than those used in the simulation. Forexample, the FEA-validated body thickness of 3mm is provedto be invalid in our flight tests.

TABLE IIDESIGN GOALS AND CHOSEN PARAMETERS THE QUADCOPTER

Specifications Design ParametersMax Speed 30km/h Motor Power 300W

Max Payload 1kg Weight 360gOutdoor Range 2km Supply Voltage 12VDiagonal Size 260mm Flight Controller Single-chip

Max Swarm Size 30 Local Mesh Comm AP6255Max Angular Error 0.05 rad Long Range Comm RT3572

Cost $60 Body Thickness 6mm

Conventionally, the design of UAVs usually employs aloosely-coupled approach, i.e., the flight controller and theperception computer are separate. Meanwhile in our system,the two systems are tightly-coupled, running simultaneouslyin the same processor. This significantly reduced the hard-ware complexity and production costs of the system. It alsoallows all software components to communicate with thesame protocol and middleware, like the Robotics Operating

PREEMPT/RT Kernel

I/O Drivers

SPI I2C GPIO ADC

Peripheral Drivers

802.11 USB Serial

Flight Controller

Consistency Check

LPF Sensor Driver WDGReal-time

Scheduler

Position Control

Attitude Control

ConfigStorage

Perception & Planning

Stereo Vision Mapping Object

Detection

Path Planning Trajectory Planning

RT Processes Non-RT Processes

Fig. 5. The system block diagram of the multirotor UAV control and com-putation platform. RT: Real-time; LPF: Low-pass filter; WDG: Watchdog.

System (ROS), which makes application software developmentmuch easier. However, this approach also imposes stringentrequirements on the system timing and task scheduling.

To resolve the timing issue, we separated the system tasksinto two categories: real-time (RT) and non-real-time (Non-RT) (shown in Fig. 5). We also ported the PREEMPT/RT real-time Linux operating system to our platform, which allowsa scheduling latency of ≤ 100µs. For the RT tasks, we putthem at real-time priority, allowing them to preempt the Linuxkernel to minimize latency. For Non-RT tasks, we carefullytweak the process priorities to prioritize more critical taskslike object detection and avoidance.

It is also worthwhile to remark that commonly availableconsumer-oriented application processors, like the AllwinnerH3 we chose, have a Dynamic Voltage and Frequency Scaling(DVFS) system to save power, which is useful for manyconsumer electronics applications but not for our case. TheDVFS function must be turned off as the kernel will lock allcores when switching frequency, causing large unpredictablelatencies.

An overview of the hardware architecture is shown in Fig.6. The FCS is implemented on an Allwinner Technology H3SoC, which has 4 ARM Cortex-A7 cores running at 1.2GHz,with a total power consumption of 2W. The onboard IMU isan Invensense MPU-9250, which has an internal Asahi KaseiAK8963 magnetometer. There is also a MEAS SwitzerlandMS5611 barometer onboard. The airframe is also in-housedesigned and manufactured using carbon fiber. The propulsionsystem is a set of DJI Snail quadcopter motor system.

MPU9250SPI

MS5611SPI

I2CMotor Driver

SDIO AP6255Local Mesh

ImageSensor

MIPIUSB RT3572

Long RangeH3 Core

Cortex-A7Cortex-A7Cortex-A7Cortex-A7

Mali-400 MP2

ISP

Encoder

PMU

AXI Bus

Clock

RTC

GPIO

H3 SoC

SPI

Smart BatteryUART

SysMonGPIO

Fig. 6. The system hardware architecture.

Thanks to the one-chip design, the flight software stack iswritten entirely with the ROS as middleware, enabling fullportability between simulation and the real world, greatlyreducing development and testing cost.

Page 7: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

Sophisticated software optimization has been employed tomeet the strict timing requirements of the flight control task.For example, the feedback tuning loop is written in pureC++ with ARM NEON intrinsics to fully utilize the vectorprocessing capability of the Cortex-A7 core, and minimizethe processing time. Before optimization, for each axis wehave about 2000 instructions for base generation, 1000 forcalculation of output, and 2000 for weight feedback. By opti-mization using SIMD, the number of instructions is reduced by10 times, total to about 500 instructions. All state variables areestimated using an EKF parallel to the control loop. Togetherwith other minor optimizations, the NN-based attitude controlloop is able to run at 1kHz with less than 1ms delay. Thisensures optimal performance in challenging conditions liketurbulence and heavy noise.

Besides, the task priorities in the flight controller arecarefully optimized to avoid catastrophic failures during testand development procedures. In other words, the “MinimalFlyable” form of the flight controller is always kept regardlessof the failure of other components. The optimized priorities ofthe tasks are shown in Table. III.

TABLE IIIPRIORITIES IN THE FLIGHT CONTROLLER SOFTWARE

Task Priority Real-time RemarksSensors +++ RT Minimal Flyable

EKF ++ RT Required for PrecisionSPNN +++ RT Minimal Flyable

Position Control ++ RT Required for AutonomyTelemetry + Required for Monitoring

Remote Control +++ RT Minimal FlyableHealth Check +

Visual Odometry + Best-effortVideo Downlink ++ Required for Long Range

As ROS is inherently flawed in real-time sensitive applica-tions with its lockup-prone design, no ROS functions are usedin the core flight controller code. Furthermore, thanks to ourone-stack architecture, all timing violations are checked andfixed with real-time tracing in HITL simulation before flight.

Real-time communication between drones and ground assetshas long been a difficult problem. Conventional telemetry sys-tems like ZigBee, 915/433MHz digital modem and normal Wi-Fi all have distinct strengths and limitations, such as limitedbandwidth, high interference, as well as regulatory issues.In our system, we designed a 802.11n based mesh networksystem to handle both indoor and outdoor communication,which has much more throughput and network capacity thanconventional systems. A detailed comparison is shown in TableIV.

V. RESULTS AND DISCUSSIONS

In order to validate the effectiveness of proposed SPNN-based dynamic inversion control systems, a set of performanceevaluations have been conducted. Two control schemes, bothconventional PID and proposed SPNN-based dynamic inver-sion control systems have been simulated with a simulatorand implemented in a real quadrotor UAV, respectively. Notethat because of the consistent software architecture, both the

Fig. 7. The UAV testbed system.

simulator and the real UAV hardware run exactly the samealgorithm.

A. Simulation Results

In this section, PID and two types of SPNN-augmented dy-namic inversion control systems, namely the raw unoptimizedversion in Q. Lin et al. [3] and our version, were implementedand simulated in software. The nominal parameters and theinitial conditions of the quadrotor for simulation is listed inTable V.

In the simulation, the vehicle were ordered to execute apreset flight plan (shown in Fig. 8). At each waypoint, thevehicle will stop for 5 seconds. The nominal airspeed is setto be 5 m/s. To reduce the disparity between simulation andreality, a Gaussian noise is added to the simulated sensorreadings. The flight trajectory is shown in Fig. 8. The trajectoryerror is calculated from the shortest distance between thevehicle positions and the preset flight trajectory. The calculatederror is shown in Fig. 9.

It can be clearly seen that our NN-based control systemoutperformed PID-based control system and the Q. Lin et al.system in trajectory accuracy. Also, our controller completesthe mission with the shortest mission time.

−40 −20 0 20 40 60 80 100

x (m)

−60

−40

−20

0

20

40

60

80

y(m

)

0.0 m

20.0 m20.0 m

20.0 m

20.0 m

20.0 m

2.0 m

PID

NN

Q. Lin

Desired

Fig. 8. The simulated flight trajectory. Labels indicate Above Sea-Level(ASL) altitude of the waypoint.

Page 8: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

TABLE IVCOMPARISON OF DIFFERENT UAV COMMUNICATION METHODS

Name Bandwidth Capacity Power In/Outdoor Mesh RemarksZigBee ˜100Kbps ˜100s ˜10mW Both Yes Susceptible to congestion915/433 ˜500Kbps ˜10s ˜200mW Outdoor No Most common in UAVWi-Fi >150Mbps ˜20s ˜500mW Indoor NoOurs >150Mbps ˜100s ˜500mW Both Yes Modified Wi-Fi

TABLE VPARAMETER SETTINGS

Name Parameter Value UnitBody Mass m 1.5 kgArm Length l 0.15 mRotor Inertia Jr 1.04 · 10−6 kg ·m2

Drag Coefficient d 1.1 · 10−6 Nms2

Thrust Coefficient d 5.42 · 10−5 Nms2

Inertia on X Axis Ix 1.0 · 10−2 kg ·m2

Inertia on Y Axis Iy 1.5 · 10−2 kg ·m2

Inertia on Z Axis Iz 1.8 · 10−2 kg ·m2

Rotational Air Resistance Factor Kr 1.0 · 10−2 Nms/radTranslational Air Resistance Factor Kt 5.0 · 10−4 Ns/m

60 80 100 120 140 160 180 200 220

Time (s)

0

1

2

3

4

Err

or(m

)

PID

NN

Q. Lin

Fig. 9. The simulated trajectory errors generated by the three controllersduring the flight.

B. Experiment Setting

In order to benchmark the real-world performance of theproposed control scheme with highly variable payload, thedrone is ordered to do a simple hovering task with a danglinglong, heavy tether. The tether we use is rated American WireGauge (AWG) 12 (29.9g/m), with a total weight of 104.7gat hovering altitude (1.5m). Note that the vehicle itself onlyweighs 360g. The test arena is indoor and does not have winddisturbance. The major source of disturbance here are a) Theoff-center, non-rigid tether and b) body vibration caused bythe motor and aerodynamics.

In both tests, the vehicle was brought to hovering at thesame altitude by Remote Control (RC), then the pilot releasesall the control to the vehicle. At t = 18s, we introduce acommand via RC link ordering the vehicle to rotate back andforth on the roll axis for 0.5 radians. All FCS parametersexcept NN engagement were untouched between the tests.Ground truth data were collected on an OptiTrack motioncapture system installed in our test field (shown in Fig. 7).

Cameras

Tether

Markers

Fig. 10. A snapshot of the experiment setup.

C. Experiment Results

0 5 10 15 20 25 30 35

Time (s)

�0.1

0.0

0.1

Pitch

Err

or(r

ad)

NN

PID

0 5 10 15 20 25 30 35

Time (s)

�0.5

0.0

0.5

Rol

lE

rror

(rad

)

NN

PID

Fig. 11. The attitude errors of the quadrotor generated by two con-trollers.

Fig. 11 shows the observed attitude values using the motioncapture system. Immediately we can see that the NN-basedcontroller yields smaller errors than its PID counterpart, espe-cially in the unbalanced roll axis. After the impulse at t = 18s,the NN-based controller returns to normal rapidly while thePID controller encounters stability issues.

We can further confirm this difference in the attitude errorspectrogram (shown in Fig. 12). In the pitch axis, the averageerror power ratio (NN:PID) is 0.250, while in the roll axis itis 0.692. Moreover, the NN-based controller is able to achievean error reduction of around 10 times over PID in frequencies≥ 0.5Hz. This significantly boosts vehicle stability and helpseliminating the errors induced by high-frequency noise ininertial guidance systems.

Fig. 13 shows the accumulated errors in both axes. It canbe seen that the cumulative errors of the NN-based controllerare less than those of the PID controller by more than half.

Page 9: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

0 10 20 30 40 50

Frequency (Hz)

10�10

10�6

Pitch

Err

orPow

er(r

ad2/H

z)

NN

PID

0 10 20 30 40 50

Frequency (Hz)

10�9

10�5

Rol

lE

rror

Pow

er(r

ad2/H

z)

NN

PID

Fig. 12. The power spectra of the attitude errors during the flight.

0 5 10 15 20 25 30 35

Time (s)

0

2

4

Pitch

Cum

.E

rror

(rad

2)

NN

PID

0 5 10 15 20 25 30 35

Time (s)

0

50

100

Rol

lC

um

.E

rror

(rad

2)

NN

PID

Fig. 13. The cumulative square attitude errors of the quadcopter.

Fig. 14 shows the open-loop position drift of the vehicleduring the flight. In a wind-less environment, total drift directlycorrelates to the vehicle’s ability to keep the thrust vertical.It can be observed that, thanks to reduced attitude errors, theNN-based controller greatly outperformed the PID controllerin the position drift test.

VI. CONCLUSION

In this paper, an adaptive control system combining a NNenhanced dynamic inversion control scheme with a conven-tional PID controller has been proposed for quadrotor UAVs.To improve the linear PID control system in challenging flightconditions, real-time SPNN-based dynamic inversion methodshave been developed to compensate the nonlinearity and ex-ternal uncertainty of the system and improve the performanceof quadrotor UAVs. To effectively implement and evaluatethe control system, a set of hardware and software platformshave also been developed accordingly. The simulation resultsshow that the proposed SPNN-based dynamic inversion controlscheme outperforms the previous SPNN method as well asthe conventional PID control in the presence of externaldisturbances. The experiment results demonstrate the superior

x(m)

−1.0 −0.50.0

0.51.0

1.52.0

y(m

)

−2.0

−1.5

−1.0

−0.5

0.0

0.51.0

z(m

)

−1.5

−1.0

−0.5

0.0

0.5

1.0

1.5

NN

PID

Fig. 14. The drift trajectory of the quadcopter. Dashed lines show thetrajectory projected on xy, xz, yz planes.

performance of the proposed NN-based compensators in termsof tracking errors and open-loop position drifts in real-worldscenarios. Our future work includes the enhancement of flightcontrol systems with reinforcement learning schemes in theposition planner to maximize the system adaptability in com-plex environments.

ACKNOWLEDGMENT

The authors would like to thank Jiaming Sun for hishelp in testing the drones and setting up the motion capturesystem, Chen Li for his help in the UAV’s mechanical design,and anonymous reviewers for their valuable comments andsuggestions.

REFERENCES

[1] S. Islam, P. X. Liu, and A. El Saddik, “Robust control of four-rotor un-manned aerial vehicle with disturbance uncertainty,” IEEE Transactionson Industrial Electronics, vol. 62, no. 3, pp. 1563–1571, 2015.

[2] F. Chen, R. Jiang, K. Zhang, B. Jiang, and G. Tao, “Robust backsteppingsliding-mode control and observer-based fault estimation for a quadrotorUAV,” IEEE Transactions on Industrial Electronics, vol. 63, no. 8, pp.5044–5056, 2016.

[3] Q. Lin, Z. Cai, Y. Wang, J. Yang, and L. Chen, “Adaptive flightcontrol design for quadrotor uav based on dynamic inversion and neuralnetworks,” in 2013 Third International Conference on Instrumentation,Measurement, Computer, Communication and Control, pp. 1461–1466,Sep. 2013.

[4] P. Poksawat, L. Wang, and A. Mohamed, “Automatic tuning of attitudecontrol system for fixed-wing unmanned aerial vehicles,” IET ControlTheory & Applications, vol. 10, no. 17, pp. 2233–2242, 2016.

[5] Z. Zhang and M. Cong, “Controlling quadrotors based on linearquadratic regulator,” Applied Science and Technology, vol. 5, pp. 38–42, 2011.

[6] L. S. Brian and L. L. Frank, “Aircraft control and simulation,” JohnWiley & Sons, Inc., Hoboken, New Jersey, 2003.

[7] H. Gao, C. Liu, D. Guo, and J. Liu, “Fuzzy adaptive PD control forquadrotor helicopter,” in 2015 IEEE International Conference on CyberTechnology in Automation, Control, and Intelligent Systems (CYBER),pp. 281–286, Jun. 2015.

Page 10: Design, Implementation and Evaluation of a Neural …static.tongtianta.site/paper_pdf/5726eafe-9036-11e9-9b63...tude control of multirotor UAVs, from proportional integral-derivative

0278-0046 (c) 2018 IEEE. Personal use is permitted, but republication/redistribution requires IEEE permission. See http://www.ieee.org/publications_standards/publications/rights/index.html for more information.

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIE.2019.2905808, IEEETransactions on Industrial Electronics

IEEE TRANSACTIONS ON INDUSTRIAL ELECTRONICS

[8] S. Bouabdallah and R. Siegwart, “Backstepping and sliding-mode tech-niques applied to an indoor micro quadrotor,” in Proceedings of the2005 IEEE International Conference on Robotics and Automation, pp.2247–2252, Apr. 2005.

[9] C. Li, G. Wang, Y. Fan, and Y. Li, “Adaptive rbf neural network con-troller design for srm drives,” in 2016 35th Chinese Control Conference(CCC), pp. 6092–6097, Jul. 2016.

[10] L. Liu, Q. Geng, Q. Fei, and Q. Hu, “The longitudinal attitude controlof uav based on gpfn neural network,” in International Conference onAutomatic Control and Artificial Intelligence (ACAI 2012), pp. 2146–2149, Mar. 2012.

[11] R. J. Adams and S. S. Banda, “Robust flight control design usingdynamic inversion and structured singular value synthesis,” IEEE Trans-actions on control systems technology, vol. 1, no. 2, pp. 80–92, 1993.

[12] B. S. Kim and A. J. Calise, “Nonlinear flight control using neuralnetworks,” Journal of Guidance, Control, and Dynamics, vol. 20, no. 1,pp. 26–33, 1997.

[13] J. V. R. Prasad, A. J. Calise, Y. Pei, and J. E. Corban, “Adaptivenonlinear controller synthesis and flight test evaluation on an unmannedhelicopter,” in Proceedings of the 1999 IEEE International Conferenceon Control Applications (Cat. No.99CH36328), vol. 1, pp. 137–142 vol.1, Aug. 1999.

[14] J. Leitner, A. Calise, and J. R. Prasad, “Analysis of adaptive neuralnetworks for helicopter flight control,” Journal of Guidance, Control,and Dynamics, vol. 20, no. 5, pp. 972–979, 1997.

[15] X. Yang and L. M. Alvarez, “A neural-network based flight controller foruass,” IFAC Proceedings Volumes, vol. 46, no. 10, pp. 164–171, 2013.

[16] M. Fatan, B. L. Sefidgari, and A. V. Barenji, “An adaptive neuro pid forcontrolling the altitude of quadcopter robot,” in 2013 18th InternationalConference on Methods Models in Automation Robotics (MMAR), pp.662–665, Aug. 2013.

[17] J. F. Shepherd III and K. Tumer, “Robust neuro-control for a microquadrotor,” in Proceedings of the 12th annual conference on Geneticand evolutionary computation, pp. 1131–1138. ACM, 2010.

[18] Y. Wang, Y. Chenxie, J. Tan, C. Wang, Y. Wang, and Y. Zhang, “Fuzzyradial basis function neural network PID control system for a quadrotorUAV based on particle swarm optimization,” in 2015 IEEE InternationalConference on Information and Automation, pp. 2580–2585, Aug. 2015.

[19] G. Shi and S. Yang, “Intelligent control of UAV with neuron-fuzzyapproach under hierarchical architecture,” in 2008 7th World Congresson Intelligent Control and Automation, pp. 5238–5243, Jun. 2008.

[20] V. R. Puttige, S. Anavatti, and M. K. Samal, “Real-time validation ofa dual neural network controller for a low-cost uav,” in 2009 IEEEInternational Conference on Industrial Technology, pp. 1–6, Feb. 2009.

[21] B. Tang, X. Fang, Z. Cai, and Y. Wang, “Reconfigurable flight controlfor uav with multiple control effectors based on neural network anddynamic inversion,” in 2011 2nd International Conference on ArtificialIntelligence, Management Science and Electronic Commerce (AIMSEC),pp. 2276–2281, Aug. 2011.

[22] Lili and Z. Hua-min, “Neural network based adaptive dynamic inversionflight control system design,” in 2011 2nd International Conference onIntelligent Control and Information Processing, vol. 1, pp. 135–137, Jul.2011.

[23] L. Wang, Y. Chen, S. Li, and C. Liu, “2dof manipulator trackingcontrol based on fuzzy cmac neural network dynamic inversion,” in2010 International Conference on Intelligent Computing and IntegratedSystems, pp. 315–318, Oct. 2010.

[24] T. Xiang, F. Jiang, Q. Hao, and W. Cong, “Adaptive flight control forquadrotor uavs with dynamic inversion and neural networks,” in 2016IEEE International Conference on Multisensor Fusion and Integrationfor Intelligent Systems (MFI), pp. 174–179, Sep. 2016.

[25] B. Lee, H. Lee, and M. Tahk, “Analysis of adaptive control using on-line neural networks for a quadrotor uav,” in 2013 13th InternationalConference on Control, Automation and Systems (ICCAS 2013), pp.1840–1844, Oct. 2013.

[26] M. G. Perhinschi, J. Burken, and G. Campa, “Comparison of differentneural augmentations for the fault tolerant control laws of the wvu yf-22model aircraft,” in 2006 14th Mediterranean Conference on Control andAutomation, pp. 1–6, Jun. 2006.

[27] T. Dierks and S. Jagannathan, “Output feedback control of a quadrotoruav using neural networks,” IEEE Transactions on Neural Networks,vol. 21, no. 1, pp. 50–66, Jan. 2010.

[28] C. Powers, D. Mellinger, and V. Kumar, “Quadrotor kinematics anddynamics,” in Handbook of Unmanned Aerial Vehicles, pp. 307–328.Springer, 2015.

Fan Jiang (M’19) received the B.S. degreein biomedical engineering from SouthernUniversity of Science and Technology(SUSTech), Shenzhen, China in 2017.

He is currently a Research Assistant withthe Department of Computer Science andEngineering, Southern University of Scienceand Technology (SUSTech), Shenzhen, China.

His research interests include intelligentsystems, robotics, and machine learning,especially in the design of robot simulation

systems.

Farhad Pourpanah (M’17) received his Ph.D.degree in computational intelligence from theUniversity Science Malaysia (USM) in 2015.

He is currently an associate researcher atthe College of Mathematics and Statistics,Shenzhen University (SZU), China. Beforejoining to SZU, he was a postdoctoral researchfellow with the Department of Computer Scienceand Engineering, Southern University ofScience and Technology (SUSTech), China. Hisresearch interests include pattern recognition,

evolutionary algorithms and condition monitoring.

Qi Hao (M’05) received the B.E. andM.E. degrees from Shanghai Jiao TongUniversity, Shanghai, China, in 1994 and 1997,respectively, and the Ph.D. degree from DukeUniversity, Durham, NC, USA, in 2006, allin electrical and computer engineering. Hereceived the postdoctoral training at the Centerfor Visualization and Virtual Environment,The University of Kentucky, Lexington, KY,USA.

He was an Assistant Professor with theDepartment of Electrical and Computer Engineering, University ofAlabama, Tuscaloosa, AL, USA. He is currently an Associate Professorwith the Department of Computer Science and Engineering, SouthernUniversity of Science and Technology, Shenzhen, Guangdong, China.His research interests include intelligent sensing, machine learning andautonomous systems.