Next Article in Journal
A Path-Planning Method Considering Environmental Disturbance Based on VPF-RRT*
Next Article in Special Issue
Drone Elevation Control Based on Python-Unity Integrated Framework for Reinforcement Learning Applications
Previous Article in Journal
Wheat Lodging Segmentation Based on Lstm_PSPNet Deep Learning Network
Previous Article in Special Issue
Fuzzy Gain-Scheduling Based Fault Tolerant Visual Servo Control of Quadrotors
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Comparative Study between NMPC and Baseline Feedback Controllers for UAV Trajectory Tracking

by
Bryan S. Guevara
1,2,†,
Luis F. Recalde
2,3,†,
José Varela-Aldás
1,3,*,†,
Victor H. Andaluz
3,4,
Daniel C. Gandolfo
2 and
Juan M. Toibero
2
1
Centro de Investigaciones de Ciencias Humanas y de la Educación (CICHE), Universidad Indoamérica, Ambato 180103, Ecuador
2
Instituto de Automática, Universidad Nacional de San Juan—CONICET, Av. San Martín Oeste 1109, San Juan J5400ARL, Argentina
3
SISAu Research Group, Facultad de Ingeniería, Industria y Producción, Universidad Indoamérica, Ambato 180103, Ecuador
4
Departamento de Eléctrica y Electrónica, Universidad de las Fuerzas Armadas—ESPE, Sangolquí 171103, Ecuador
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Drones 2023, 7(2), 144; https://doi.org/10.3390/drones7020144
Submission received: 31 January 2023 / Revised: 16 February 2023 / Accepted: 16 February 2023 / Published: 20 February 2023
(This article belongs to the Special Issue Conceptual Design, Modeling, and Control Strategies of Drones-II)

Abstract

:
Transport, rescue, search, surveillance, and disaster relief tasks are some applications that can be developed with unmanned aerial vehicles (UAVs), where accurate trajectory tracking is a crucial property to operate in a cluttered environment or under uncertainties. However, this is challenging due to high nonlinear dynamics, system constraints, and uncertainties presented in cluttered environments. Hence, uncertainties in the form of unmodeled dynamics, aerodynamic effects, and external disturbances such as wind can produce unstable feedback control schemes, introducing significant positional tracking errors. This work presents a detailed comparative study between controllers such as nonlinear model predictive control (NMPC) and non-predictive baseline feedback controllers, with particular attention to tracking accuracy and computational efficiency. The development of the non-predictive feedback controller schemes was divided into inverse differential kinematics and inverse dynamic compensation of the aerial vehicle. The design of the two controllers uses the mathematical model of UAV and nonlinear control theory, guaranteeing a low computational cost and an asymptotically stable algorithm. The NMPC formulation was developed considering system constraints, where the simplified dynamic model was included; additionally, the boundaries in control actions and a candidate Lyapunov function guarantees the stability of the control structure. Finally, this work uses the commercial simulator DJI brand and DJI Matrice 100 UAV in real-world experiments, where the NMPC shows a reduction in tracking error, indicating the advantages of this formulation.

1. Introduction

1.1. Motivation

Nowadays, unmanned aerial vehicles (UAVs) are applied in many fields due to recent technological advances and the ability to perform tasks that humans cannot do. Their fields of application can be industry, transportation, and agriculture [1]. Quadrotor platforms are a type of UAV widely adopted in aerial robotic applications and extensively used by the scientific community due to high maneuverability, vertical take-off, and landing (VTOL). Significant results have been published [2,3,4,5,6], where such systems were employed successfully in applications as remote sensing and environment interaction [7,8,9,10], autonomous delivery [11,12], and exploration in unknown environments [13,14,15,16].
The extreme agility of quadrotors can be used for critical missions such as rescue, search, and transportation; this kind of application requires a minimal execution time that is only possible at high-speed trajectories, where accurate trajectory tracking and robustness are critical features. These features are still challenging problems for the research community; furthermore, the ability to precisely control quadrotors during agile maneuvers would allow faster trajectories and a wider range of motion that enables the system to be safely closer to obstacles, where slight deviations from the reference trajectories can produce serious accidents. In response to this fact, various controller structures have been proposed. However, only some approaches can handle the issues presented during flights in cluttered environments, such as non-linear dynamics, uncertainties, and limitations in control actions.
This work considers that the problem of quadrotor control in cluttered environments can be divided into two groups: (i) Non-predictive Feedback Controllers, which use formulations of linear and nonlinear control exploiting system model structure to design control laws to guarantee the system stability and execution of the desired tasks. However, these techniques do not handle system constraints such as limitations presented in control actions, ignore future decisions, and formulations are not trivial for complex systems; (ii) Predictive Optimization Methods which uses the model of the system to generate the optimal control policy that guarantees the execution of the desired task minimizing an objective function considering the system and input constraints in a predictive manner. Furthermore, this formulation is capable of fully exploiting the capabilities of the quadrotor and taking advantage of the available computational power. Optimal control approaches have presented notorious developments; specifically, nonlinear model predictive control (NMPC) has experimented with outstanding attention for quadrotor applications due to the last advances in hardware and algorithms, allowing the execution of these formulations with high computational efficiency [17,18,19,20].
However, NMPC is computationally expensive compared to two of the baseline feedback controllers, such as inverse differential kinematics and inverse dynamic compensation, where these formulations have presented successful developments in the field of robotics [21,22,23]. Although these formulations have not achieved quadrotor control under agile trajectories as NMPC proposed in [19,24]; moreover, the high computational cost associated with NMPC could make its application questionable. Therefore, a comparative study of NMPC and Baseline Feedback Controllers is needed to provide insights for future developments, reporting benefits and drawbacks in terms of performance improvement, disturbance rejection, and computation effort applied in quadrotor control under cluttered environments.

1.2. Related Work

This work divides the trajectory tracking controllers into two big groups: (i) Non-Predictive Formulation, where this scheme only depends on a single reference set-point at the current time, (ii) Predictive Formulation which considers multiple future references into the control scheme at the moment the algorithm is being executed. In the following section, this work presents a short review of the scientific community’s latest contributions in trajectory tracking accuracy under these two formulations. For more detailed information about quadrotor controllers, refer to the following works [25,26].

1.2.1. Non-Predictive Controllers

Trajectory tracking controllers have been developed during the last decade by research institutes. The literature developed generally considers slight angle deviations, which guarantee hover or near hover along the execution of the trajectory. For formulations based on linear control methods, refer to the following works [27,28].
However, the usual hover assumptions are not enough for cluttered environments, where nonlinearities appear as one of the first problems to handle. Nonlinear control formulations are valuable tools that allow the design of algorithms capable of mitigating problems associated with cluttered environments, such as nonlinearities and robustness. For this reason, some works use nonlinear feedback control, such as backstepping formulations [29], feedback linearization [30,31], and robust nonlinear control [32,33,34]. In addition, quaternions are used to avoid singularities presented in the mathematical model using Euler angles formulation of aerial vehicles [35].
Moreover, intelligent control theory has been applied in a wide range of works, where the main formulations use concepts of artificial neural networks [36,37], fuzzy logic systems [38,39], and reinforcement learning techniques [40,41]. Generally, these formulations cannot handle states or control input constraints; furthermore, the reference trajectory needs to be selected carefully, which is not viable in cluttered environments.

1.2.2. Predictive Controllers

MPC has presented outstanding precision and robustness properties among the multiple approaches applied in quadrotor trajectory tracking, so this formulation has been considered in numerous articles to demonstrate some important properties in advanced UAV control. Due to the predictive nature of its formulation is possible to generate the control policy optimizing the reference states and the constraints at the same time, which is beneficial because the majority of systems present limitations in their states and control actions. In the same way, control commands could be generated by minimizing the tracking error in the predicted time horizon by solving constrained optimization problems, with successful results in applications, as shown in [17,18,42,43].
Nevertheless, MPC formulations can be computationally expensive, specifically nonlinear model predictive control NMPC [42,44]. For this reason, linear model predictive control is usually adopted in many works, where the nonlinearities are simplified using linear approximations under small angle variations assumptions [30,45]. Thanks to the recent advances in technology and the new optimization solvers [46], many works started using nonlinear dynamics, exploiting the capabilities of the quadrotors [17,18]. Although NMPC formulations are realizable on modern computers, the authors still require significantly more computational resources than non-predictive schemes such as inverse differential kinematics and inverse dynamic compensation. Hence, NMPC may experiment with numerical convergence problems associated with computational capabilities. Finally, it is necessary to compare these two formulations and realize which conditions present better performance or complications related to tracking accuracy and computational time.

1.3. Contribution of This Work

This work presents a comparative study between (i) Non-predictive Feedback Controllers, conformed by inverse differential kinematics and inverse dynamic compensation controllers and (ii) Predictive Optimization Methods with the Nonlinear Model Predictive Control formulation. To show the advantages and capabilities of each controller, this work reports comparative experiments considering a wide range of agile trajectories with a particular emphasis on tracking accuracy, computational efficiency, and robustness. The main contributions of this work are:
  • Differential Kinematics and Dynamic Formulation: this work develops the differential kinematics and dynamics formulation considering maneuverability velocities as the control input of the system because many commercial aerial vehicles are produced under this structure where the user does not have access to attitude control schemes. Thus, this formulation can be straightforwardly applied to another commercial platform with desired velocities as inputs of the system. To obtain the dynamic model of the system, this work used the formulation of Euler–Lagrange; additionally, to modify this model into the velocities space, it is necessary to introduce the concept of low-level PID in the mathematical formulation.
  • Nonlinear Feedback Formulations: are generated by inversion of differential kinematics and dynamic compensation techniques. The design of these control structures was developed using the theory of nonlinear control and linear algebra, guaranteeing minimal computational time with asymptotically and robust behavior.
  • NMPC Formulation: This work formulates the NMPC considering system and input constraints such as system dynamics, limits in control action, rate of change of control inputs, and a candidate Lyapunov function that guarantees the stability of the control structure. This work uses CasADI to solve the nonlinear optimization problem.
  • Comparative Study: The experiments are carried out in simulations and real-world environments. The simulation experiments were performed under the commercial simulator of the DJI brand. On the other hand, real-world experiments were conducted using the DJI Matrice 100 platform, which was equipped with all the necessary hardware to run the controllers on the onboard computer. The agile trajectory selected to compare the performances of the controllers is the Lissajous; additionally, to guarantee a good comparison, this work considers low and high velocities through the reference signal where the aerodynamics effects, latency, and uncertainties are inevitable. Finally, with the comparative results is possible to show the benefits of each controller considering their predictive and non-predictive structures; the comparative consider the following metrics: tracking accuracy and average computational time.
This work is organized as follows: Section 2 presents the preliminary materials, such as differential kinematics and dynamic models. The formulation of the quadrotor controllers is presented in Section 3 with a subsection describing the non-predictive (inverse differential kinetics and inverse dynamic compensation and predictive (NMPC) schemes. Section 4 shows the comparative results through simulations and real-world experiments. The discussions and conclusions of this work are presented in Section 5 and Section 6, respectively.

2. Preliminary Materials

This section presents the formal notations used throughout the paper and the model employed to describe the motions of the Quadrotor platform. First, an instantaneous kinematic model was derived, and then the simplified dynamic model was formulated using the Euler–Lagrange. Finally, identification and validation processes are necessary to employ the models in the controller formulations.

2.1. Kinematics Formulation

This work formulates the mathematical representation of the quadrotor, defining the world-fixed inertial frame as < I > and the frame attached to the body of the system as < B > , which is aligned with the center of mass (CoM), these notations are shown in Figure 1.
This work expresses the pose of the quadrotor using the following definition η = p ( η ) ϕ ( η ) , where p ( η ) = η x η y η z and ϕ ( η ) = η φ η υ η ψ are the position and the orientation respect < I > ; further, due to the low-level controllers based on PID formulations which guarantee the hover position, this work assumes rotations only through the vertical axis B z and slight angular deviation along the angles ( φ , υ ) roll and pitch respectively.
Thus, the minimum representation is defined as η = η x η y η z η ψ expressed with more detail by the following equation:
η x = η x 0 + d x cos ( ψ ) d y sin ( ψ ) η y = η y 0 + d x sin ( ψ ) + d y cos ( ψ ) η z = η z 0 + d z η ψ = ψ
where η = η x 0 η y 0 η z 0 is CoM position; additionally this work defines the point of interest of the system displacement from the CoM, which can be generally defined as ( d x , d y , d z ) .
To formulate the controller schemes is necessary to know the evolution of the system over time; in fact of this, the instantaneous kinematics model of the quadrotor is defined by the vector η ˙ = η ˙ x η ˙ y η ˙ z η ˙ ψ with the following matrix form representation:
η ˙ x η ˙ y η ˙ z η ˙ ψ = cos ( ψ ) sin ( ψ ) 0 ρ 1 sin ( ψ ) cos ( ψ ) 0 ρ 2 0 0 1 0 0 0 0 1 μ l μ m μ n ω
where linear and angular velocities are defined by μ = μ l μ m μ n ω , additionally ρ 1 = d x sin ( ψ ) + d y cos ( ψ ) and ρ 2 = d x cos ( ψ ) d y sin ( ψ ) represent the behavior generated by displacement of the point of interest. A compact formulation can be defined by the following equation:
η ˙ = J k ( ψ ) μ
where the linear mapping between the evolution of the point of interest η ˙ and the control maneuverability velocities μ can be defined by the analytical Jacobian matrix J k ( ψ ) .
For the simplified dynamic section based on maneuverability velocities [24], it is necessary to define the time derivative of (3) expressed in its compact form as:
η ¨ = J k ( ψ ) μ ˙ + J ˙ k ( ψ , ω ) μ
where μ ˙ = μ l ˙ μ m ˙ μ n ˙ ω ˙ is the acceleration vector of the quadrotor and J ˙ ( ψ , ω ) is the time derivative of the analytic Jacobian defined as
J ˙ ( ψ , ω ) = ω sin ( ψ ) ω cos ( ψ ) 0 ω ( d x cos ( ψ ) d y sin ( ψ ) ) ω cos ( ψ ) ω sin ( ψ ) 0 ω ( d x sin ( ψ ) + d y cos ( ψ ) ) 0 0 0 0 0 0 0 0

2.2. Quadrotor Dynamics

The formulation of a mathematical model that defines the precise behavior of the quadrotor flight is obtained through the Euler–Lagrange equations, which describe the evolution of a mechanical system subject to holonomic constraints. With these considerations, the Euler–Lagrange can be systematically defined using the total kinetic and potential energy present in the system. The Euler–Lagrange equations [47,48] are expressed as follows:
d d t L η ˙ L η = τ
where L = K U represents the Lagrangian as a difference between the kinetic energy and the potential energy and τ = f x I f y I f z I τ ψ I represents the forces and torques applied in each degree of freedom. The total kinetic energy of the system K = K v + K ω is defined as the sum of energies associated with translational and rotational velocities.
The translational term contributes to the translational kinetic energy of the system, defined as
K v = 1 2 m η ˙ η ˙
where m represents the mass of the quadrotor; additionally, the rotational kinetic energy is expressed:
K ω = 1 2 ω ˙ I ω ω ˙
where ω = ω x ω y ω z is the angular velocity and I ω is the inertia matrix expressed in a fixed coordinate system < I > . Then the angular velocity can be expressed as a function of the rotational velocity in ϕ as
ω = R ( ϕ ) J ω ( ϕ ) ϕ ˙
where R is a rotation matrix that transforms the vectors of the coordinate system in the body frame < B > to the absolute inertial coordinate system < I > ; J ω represents the geometric Jacobian which is related to the analytical Jacobian J ω by the following equation:
J ω ( ϕ ) = T A ( ϕ ) J k ( ψ )
where
T A ( ϕ ) = I 0 0 T ω ( ϕ ) T ω ( ϕ ) = 0 sin ( φ ) cos ( φ ) sin ( υ ) 0 cos ( φ ) sin ( φ ) sin ( υ ) 1 0 cos ( φ )
Similarly, we can formulate ω = T ω ( ϕ ) ϕ ˙ to formulate the total kinetic energy of the system as a function of generalized coordinates and the relationship between analytical and geometric Jacobian [47], fulfilling that:
K = 1 2 η ˙ m J k ( ψ ) J k ( ψ ) + J ω ( ϕ ) R ( ϕ ) I R ( ϕ ) J ω ( ϕ ) η ˙
Finally, with the assumptions presented above, the total kinetic energy of the system can be written compactly as
K = 1 2 η ˙ M ( η ) η ˙
where M ( η ) is the inertia matrix, which is symmetric and positive definite. The potential energy of the quadrotor arises only due to gravity defined by
U = m g η
where g = 0 0 g 0 is the vector of gravitational accelerations in the absolute coordinate system < I > . Thus, the Lagrangian for the quadrotor can be written as
L ( η , η ˙ ) = 1 2 η ˙ M ( η ) η ˙ m g η
Then applying the partial derivatives and Euler–Lagrange’s constraint (5), the dynamic model of the quadrotor can be written in matrix form as
f x I f y I f z I τ ψ I = m 0 0 m ( d y cos ( ψ ) + d x sin ( ψ ) ) 0 m 0 m ( d x cos ( ψ ) d y sin ( ψ ) ) 0 0 m 0 m ( d y cos ( ψ ) + d x sin ( ψ ) ) m ( d x cos ( ψ ) d y sin ( ψ ) ) 0 m d x 2 + m d y 2 + I η ¨ x η ¨ y η ¨ z η ψ ¨ + 0 0 0 m η ˙ ψ ( d x cos ( ψ ) d y sin ( ψ ) ) 0 0 0 m η ˙ ψ ( d y cos ( ψ ) + d x sin ( ψ ) ) 0 0 0 0 0 0 0 0 η ˙ x η ˙ y η ˙ z η ψ ˙ + 0 0 g m 0
Therefore, the dynamic model of the quadrotor can be written in compact form:
M ( η ) η ¨ + C ( η , η ˙ ) η ˙ + g ( η ) = τ
where, the Coriolis effects C ( η , η ˙ ) and gravitational forces g ( η ) can be represented by the following matrices: C ( η , η ˙ ) = M ˙ 1 2 η ˙ M η and g ( η ) = U η .

2.3. Simplified Dynamic Model Based on Maneuvering Velocities

This section presents the following premise; the quadrotor remains in a hover position performed by PD dynamic controller with gravity compensation. The forces f t B = f x B f y B τ ψ B govern the attitude PD controller of the quadrotor; furthermore these forces can be also defined as
f t B = K p t ( μ t r e f μ t ) + K d t ( μ ˙ t r e f μ ˙ t )
where μ t = μ l μ m ω is the velocity vector that defines the attitude of the quadrotor in the horizontal plane; μ t r e f = μ l r e f μ m r e f ω r e f is the reference horizontal attitude vector; ( μ ˙ t , μ ˙ t r e f ) are the time derivatives of μ t and μ t r e f , respectively; and K p t , K d t are diagonal positive definite gain matrices.
Furthermore, this work uses the following assumption μ ˙ t r e f = 0 if lim t f t B = 0 and lim t μ ˜ t = 0 , where μ ˜ t = μ t r e f μ t . Now, considering the vertical thrust force f l B = f z B + m g that opposes the force of gravity, the altitude PD controller is defined in (18) under the assumption that lim t f z I = 0 and lim t μ ˜ n = 0 if μ ˙ n r e f = 0 , considering that μ ˜ n = μ n r e f μ n .
f l B = k p l ( μ n r e f μ n ) + k d l ( μ ˙ n r e f μ ˙ n ) + m g
where μ n r e f is the reference vertical velocity; μ ˙ n and μ ˙ n r e f are the time derivatives of μ n and μ n r e f , respectively; and k p l , k d l are positive gain scalars that define the proportional and derivative gains of the PD controller.
Due to the above, the general structure of the hover controller based on altitude and attitude control is expressed as
f B = K p μ ref K p μ K d μ ˙ + g
where g = 0 0 g 0 ; K p R 4 × 4 is a diagonal matrix of proportional gains and K d R 4 × 4 is a diagonal matrix of derivative gains.
Finally, substitute Equations (3) and (4) into the expression resulting from equating the dynamic models (16) and (19), then the new simplified dynamic model of the quadrotor is obtained, which considers the manipulability velocities as input of the system:
μ l r e f μ m r e f μ n r e f ω r e f = π 1 0 0 d x ω π 2 0 π 3 0 d y ω π 4 0 0 π 5 0 d x ω π 6 d y ω π 7 0 π 8 μ ˙ l μ ˙ m μ ˙ n ω ˙ + π 9 0 0 d x ω π 10 0 π 11 0 d y ω π 12 0 0 π 13 0 d y ω 2 π 14 d x ω 2 π 15 0 d x 2 ω 2 π 16 + d y 2 ω 2 π 17 + π 18 μ l μ m μ n ω
This new simplified dynamic model can be applied to any commercial quadrotor UAV with maneuverability velocities defined as inputs of the system. The following equation expresses the simplified dynamic model expressed in a compact form:
μ ref = M ¯ ( μ , π ) μ ˙ + C ¯ ( μ , π ) μ
where M ¯ ( μ , π ) = ( RK p ) 1 ( ( M J + R K d ) is the new matrix of mass and inertia; C ¯ ( μ , π ) = ( RK p ) 1 ( M J ˙ + R K p + C J ) is the new matrix of centripetal and Coriolis forces; finally, π = π 1 π 2 . . π 18 is the vector of dynamic parameters that includes all the physical phenomena that change the quadrotor’s dynamics.

2.4. Identification and Validation

This section shows the identification and validation of the dynamic model presented in (21), which due to the important property of dynamic systems equation, can be formulated in a linear parameter representation [48] as μ ref ( t ) = Y ( μ ˙ , μ ) π , where Y ( μ ˙ , μ ) is a regressor matrix, and π is the vector of linear parameters.
The identification process establishes the relation between the mathematical formulation and the real-world system, allowing the use of the model in control structures. This process uses the measurements obtained from the aerial vehicle DJI Matrice 100, and due to the presence of noise during the flight measurements, this work applies a filter in the identification experiment defined by μ ¯ ref = λ ( s + λ ) μ ref and μ ¯ = λ ( s + λ ) μ . The identification process takes the filters signals and generates the following matrices:
Φ = Y 1 ( μ ¯ ˙ 1 , μ ¯ 1 ) Y s ( μ ¯ ˙ s , μ ¯ s ) Ω = μ ¯ ref 1 μ ¯ ref s
where s is the number of measurements used during the identification process, thus, the system can be written as follows:
Φ π = Ω
Finally, this work uses the method of least squares to identify the system parameters defining the following equation:
π = Φ Ω
where Φ is defined as ( Φ Φ ) 1 Φ .
Table 1 show the values of the parameters obtained using the least squares method,
Figure 2a shows the evolution of the velocities estimated by the dynamic model ( μ l m , μ m m , μ n m , ω m ) presented in (21) and developed by the fourth order Runge-Kutta method. Finally, Figure 2b compares the real velocities and the velocities generated by the dynamic model with a new set of reference velocities to verify the accuracy of the expected behavior.

3. Controllers Design

This work presents the formulation of the (i) Non-predictive Feedback Controllers, conformed by inverse differential kinematics and inverse dynamic compensation controllers [49] and (ii) Predictive Optimization Methods with the non-linear model predictive control formulation.

3.1. Kinematic Controller

The kinematic controller tries to calculate the instantaneous velocities of the quadrotor to track the desired trajectory at the same time that the error in the steady state converges asymptotically to zero. The general scheme of the kinematic controller implemented is shown in Figure 3.
The control law generates the desired velocities for trajectory tracking:
μ c = J k ( ψ ) η ˙ d + K 2 t a n h ( K 2 1 K 1 η ˜ )
where η ˙ d are the velocities associated with the desired trajectory; η ˜ = η d η are the position errors; additionally, tanh ( · ) is a saturation function where K 1 > 0 is a diagonal matrix defines the slopes of the saturation function and K 2 > 0 is a diagonal matrix that represents the maximum and minimum velocities generated by the controller. The use of tanh ( · ) in the control formulation enables the consideration of limits in control actions, which is a remarkable feature in developing a comparative study.

Kinematic Controller Stability Analysis

This work demonstrates the stability of the proposed controller considering that μ μ c ; thus, the closed-loop equation of the system is defined as
η ˜ ˙ = K 2 tanh ( K 2 1 K 1 η ˜ )
A Lyapunov candidate function based on the control errors is defined as follows:
V k = 1 2 η ˜ Λ η ˜
where Λ R 4 × 4 is a positive definite diagonal matrix. The time derivative of the candidate Lyapunov function along the trajectory of the system is defined by
V ˙ k ( η ˜ ) = η ˜ Λ K 2 tanh ( K 2 1 K 1 η ˜ )
According to the Lyapunov criterion, if K 1 > 0 and K 2 > 0 then the stability of the system is guaranteed because V ˙ k ( η ˜ ) < 0 , which means that the error converges to zero asymptotically η ˜ 0 since t .

3.2. Dynamic Controller

The quadrotor presents dynamic effects related to inertia movements; this generates velocities errors μ ˜ = μ c μ with respect to the instantaneous velocities generated by the kinematic controller. To reduce this effect, Figure 4 shows the general control scheme where the dynamic compensation generates reference velocities μ r e f that compensate for the effects generated by the inertia movements.
The implemented dynamic compensation control law is indicated in (29).
μ ref = M ¯ ( χ , a , b ) σ + C ¯ ( χ , μ ) μ
where σ defines the dynamic compensation auxiliary variable, which is defined as follows:
σ = μ ˙ c + K 4 tanh ( K 4 1 K 3 μ ˜ )
μ ˙ c defines the acceleration of the kinematic control reference μ c ; K 3 is a matrix that weight the convergence of the velocity control errors and K 4 is a diagonal matrix that delimits instantaneous velocities.

Dynamic Controller Stability Analysis

This work uses the Lyapunov criterion to guarantee the stability of the proposed dynamic compensation, combining Equations (29) and (21) is possible to obtain the following closed-loop expression:
μ ˜ ˙ = K 4 tanh ( K 4 1 K 3 μ ˜ )
Therefore, the Lyapunov candidate function is proposed as follows:
V d = 1 2 μ ˜ Γ μ ˜
where Γ R 4 x 4 is a positive definite diagonal matrix. The time derivative of the Lyapunov candidate function along the system’s trajectories can be defined as
V ˙ d ( μ ˜ ) = μ ˜ Γ K 4 tanh ( K 4 1 K 3 μ ˜ )
According to the Lyapunov stability criterion, the stability of the system is guaranteed because V ˙ d ( μ ˜ ) < 0 , that is, μ ˜ 0 since t as long as K 3 > 0 and K 4 > 0 .

3.3. NMPC Controller

This work formulates the NMPC modifying the cost function into nonlinear programming formulation (NLP) to generate the optimal velocities that keep the quadrotor on the desired trajectory considering the kinematics and dynamics constraints along the entire finite horizon of prediction; in addition, the kinematics, dynamics, and control actions that include the rate of change of the control velocities are defined as constraints. Finally, this work considers a Lyapunov candidate function as a hard constraint to guarantee the stability of the system. The general scheme of the proposed controller is shown in Figure 5.
The prediction of the generalized nonlinear kinematic-dynamical system is defined as
x ˙ ( l | t ) = f ( x ( t ) , μ ref ( t ) )
f ( x ( t ) , μ ref ( t ) ) : = A x ( l | t ) + B μ r e f ( l | t )
A = 0 4 × 4 J ( ψ ) 0 4 × 4 M ¯ 1 C ¯ , B = 0 4 x 4 M ¯ 1
where x ( l | t ) = η μ X and μ ref ( l | t ) U are the state and input of the system, and l [ t , t + T ] is the evolution of the instantaneous value throughout the finite prediction interval T considering the instant measure t. Thus, this work uses an intermediate cost function t defined as
t ( η ˜ ( l | t ) , μ ( l | t ) ) = 1 2 ( η ˜ ( l | t ) Q η ˜ ( l | t ) + μ ( l | t ) R μ ( l | t ) )
In the last instant of time, the final prediction cost function f is defined as
f ( η ˜ ( t + T ) ) = 1 2 η ˜ ( t + T ) Q η ˜ ( t + T )
where Q and R are an arbitrary positive definite gain matrix for error and input system, respectively. The MPC is defined as the solution to the nonlinear optimal control problem (NOCP):
min η ( . ) , μ ( . ) t t + T t ( η ˜ ( l | t ) , μ ( l | t ) ) d t + f ( η ˜ ( t + T ) )
subject to : x ˙ ( l | t ) = f ( x ( l | t ) , μ ref ( l | t ) )
x ( 0 ) = x 0
| μ ref ( i + 1 | t ) μ ref ( i | t ) | Δ μ ref
μ ref ( l | t ) [ μ ref m i n , μ ref m a x ]
μ ref ( l | t ) U t [ 0 , N 1 ]
x ( l | t ) X t [ 0 , N ]
h f ( μ ˜ ) 0
where the NOCP (37) is solved using the direct multiple shooting method and considering the initial conditions (39). Equation (38) defines the system dynamics considered as a constraint. Equations (40)–(42) define the inputs constraints, where Δ μ ref , μ ref m i n and μ ref m a x represents the rate of change, the maximum and minimum values of the control actions, respectively. Equation (43) defines the state constraints.
Finally, Equation (44) considers the time derivative of the Lyapunov candidate function (33) defined as the constraint h f ( μ ˜ ) = μ ˜ Γ K 4 tanh ( K 4 1 K 3 μ ˜ ) that guarantees the system’s stability.

4. Results

This section illustrates the simulation and real-world experimental results to compare each controller’s performance. The experiments were performed considering the following conditions: (i) Simulations Experiments, this section uses the simulation software provided by DJI with the nominal model without disturbances; (ii) Real World Experiments the considerations for this section include a the Lissajous trajectory with low and high velocities where aerodynamics effects, latency, and uncertainties are inevitable guaranteeing a fair comparative study; additionally, the aerial vehicle used during the experiments was DJI Matrice 100 by DJI. The comparative study considers the following metrics: tracking accuracy, computational time, and robustness. Throughout the experiments, this work uses η and η d to represent the movement of the DJI Matrice 100 aerial robot and the desired trajectory, respectively.

4.1. Simulation Experiments Results

This section illustrates the results of the controllers developed in Section 3; simulation experiments allow the user to tune the parameters presented in each controller and avoid problems in real-world experiments. The reference trajectory η d = η x d η y d η z d η ψ d , initial conditions η o = η x o η y o η z o η ψ o μ o = μ l o μ m o μ n o ω o conducted in these experiments are presented in Table 2. Finally, to measure the trajectory tracking performance, this work defined the control error as η ˜ = η d η considering only positional error; orientation errors were not considered.

4.1.1. Inverse Differential Kinematics

In this section, the inverse differential kinematics (25) is implemented, where the desired trajectory and initial conditions are shown in Table 2. Additionally, this control structure uses the controller parameters presented in Table 3. The control parameters were selected considering the limits in the control maneuverability velocities K 2 and the fair pondering of the control error K 1 .
The results of this experiment are illustrated in Figure 6a,b; the quadrotor follows the desired trajectory; furthermore, the evolution of the system has been associated with the Euclidean norm η ˜ of the control error, which is helpful to illustrate the deviation of the system during the execution of the desired trajectory.
However, this formulation shows a steady state error associated with the lack of dynamics in the control structure Figure 6c. A close-up of the control errors shows that these values are bounded, achieving a final characteristic error with a max value of η ˜ x < 0.6 [ m ] , η ˜ y < 1 [ m ] and η ˜ z < 0.1 [ m ] respectively for each axis.
Finally, the control actions ( μ l c , μ m c , μ n c ) are shown in Figure 6d, which were generated by the presented controller and guaranteed smooth values; however, these signals cannot ensure the convergence of the system to the reference trajectory.

4.1.2. Inverse Dynamic Compensation

The implementation of the inverse dynamic compensation (29) is presented in this section; moreover, to obtain fair comparative results, this work uses the same desired trajectory and initial condition defined in Table 2. Additionally, the parameters of this control structure are defined in Table 4. The control parameters of the dynamic compensation controller were selected as identity matrices; because of this, the control error values do not change, and we can ensure a fair comparison.
The results using the inverse dynamic compensation are presented in Figure 7a,b; this controller shows a better performance with more accuracy than the results presented in Figure 6 due to the controller can include the dynamics of the system in the control formulation. Additionally, the movement of the quadrotor platform based on measures of the system introduces the Euclidean norm showing the control error values along the trajectory.
A close-up of the control errors (see Figure 7c) shows boundaries with maximum values of η ˜ x < 0.3 [ m ] , η ˜ y < 0.5 [ m ] and η ˜ z < 0.1 [ m ] for each axis, respectively. The control signals generated by the controller ( μ l r e f , μ m r e f , μ n r e f ) are presented in Figure 7d; where these signals show a non-smooth behavior compared to the formulation presented before.

4.1.3. Nonlinear Model Predictive Control

This section presents the implementation of the NMPC controller proposed in (37); additionally, this work uses direct multiple shooting and nonlinear programming formulation to include the internal states η and the control actions μ ref as optimization variables guarantying computational efficiency. This work uses CasADI [46] to solve the optimization problem guaranteeing real-time solutions.
This work defines the values of the positive define matrices presented in Table 5; these values were obtained through experiments to improve the performance of the controller scheme. Additionally, the boundaries in the control actions ( μ ref m i n , μ ref m a x ) are similar to those considered in the inverse kinematic controllers; moreover, the matrices Q and R guarantee a fair comparison and smooth control variables under this control formulation.
The movements of the quadrotor using this formulation are shown in Figure 8a and Figure 8b; a close-up of the control errors (see Figure 8c) indicates boundaries with maximum values of η ˜ x < 0.3 [ m ] , η ˜ y < 0.2 [ m ] and η ˜ z < 0.1 [ m ] , guaranteeing that the aerial vehicle tracks the desired reference trajectory more accurately than the control schemes proposed in (25) and (29), demonstrating the advantages of the formulation compared with non-predictive formulations.
Finally, the control signals generated by the NMPC formulation ( μ l r e f , μ m r e f , μ n r e f ) are shown in Figure 8d; the control values are bounded considering the specifications in Table 5, this is one of an essential feature of this controller due to the systems incorporate limitation in control actions and internal system states.

4.2. Comparative of Simulations Experiments

This section presents comparative results where each controller was evaluated using the information presented in the previous section. In the simulation experiments, this work does not consider unmodeled dynamics and uncertainties to ensure that each controller has the accurate formulation to control the system.
In the following comparison, this work uses the root mean square error (RMSE) of the positional error as a metric to compare each controller; additionally, we use each controller’s average computational time to compare the required time of each formulation to generate the solution.
Figure 9a compares the Euclidean norm of each controller during the execution of the desired task, where η ˜ K i n e m a t i c , η ˜ D y n a m i c and η ˜ N M P C illustrated the evolution of the control error, demonstrating the better performance of the NMPC formulation. Figure 9b shows the RMSE of each controller, the NMPC has a better performance, especially in the Y axis, where the trajectory presents the more aggressive behavior.
Simulation experiments were carried out in the simulator provided by DJI; moreover, the desktop computer presents the following hardware features: Intel processor i7-7700HQ and CPU 2.80 GHzx8. The control structures were developed in the onboard computer of the aerial vehicle (Jetson nano 4 GB core), where the programming selected programming language is Python due to the famous general-purpose structure. Table 6 compares the average computational time for each controller. As expected, the NMPC formulation requires more time to compute the control signal; however, the excessive computational time compared with the other formulation does not mean that this controller cannot be implemented with a sufficiently high frequency.

4.3. Real-World Experiments Results

This work develops many experiments using the commercial aerial platform DJI Matrice 100 to compare the performance of each controller proposed in Section 3.
Each controller was implemented on the onboard computer; a more detailed explanation of the hardware in the aerial vehicle is presented in Figure 10 considering the onboard computer Jetson nano 4 GB core module.
The desired trajectory and initial conditions used during the experimental results are presented in Table 7; due to the extra hardware presented in the aerial vehicle, such as the on-board computer, the selected trajectory presents lower velocities than the trajectory in Table 2 to maintain the system’s integrity.

4.3.1. Inverse Differential Kinematics

This section presents the results using the controller proposed in Equation (25); we consider the same control parameters presented in Table 3 to present a fair comparison. Figure 11a,b show the evolution of the quadrotor during the experiment; furthermore, the control error is presented in Figure 11c with boundaries where the maximum values are η ˜ x < 0.2 [ m ] , η ˜ y < 0.5 [ m ] and η ˜ z < 0.5 [ m ] . Finally, the control actions ( μ l c , μ m c , μ n c ) are shown in Figure 11d, which present a smooth behavior.

4.3.2. Inverse Dynamic Compensation

The section presents the implementation of inverse dynamic compensation (29) in real-world experiments; additionally, to get fair comparative results, this work uses the same control parameters defined in Table 4.
The results using the inverse dynamic compensation are presented in Figure 12a,b; where the results show a better performance with more accuracy than those presented in Figure 11. Finally, Figure 12c shows the control error results, where these values present boundaries with maximum values of η ˜ x < 0.3 [ m ] , η ˜ y < 0.3 [ m ] and η ˜ z < 0.35 [ m ] , finally the control signals ( μ l r e f , μ m r e f , μ n r e f ) are presented in Figure 12d.

4.3.3. Nonlinear Model Predictive Control

This section presents the implementation of the proposed NMPC controller (37) in real-world experiments; due to uncertainties and model mismatch, this section demonstrates the robustness and precision of the NMPC.
The evolution of the quadrotor using NMPC is shown in Figure 13a,b; although of the better performance of this control scheme a close-up of the control errors (see Figure 13c) shows boundaries with maximum values of η ˜ x < 0.1 [ m ] , η ˜ y < 0.15 [ m ] and η ˜ z < 0.2 [ m ] . The predictive control formulation guarantees that the quadrotor tracks the desired reference trajectory more accurately than the control schemes proposed in (25) and (29). The NMPC formulation uses the same control parameters shown in Table 5.
Finally, the control signals generated by the optimal policy of the optimization problem ( μ l r e f , μ m r e f , μ n r e f ) are shown in Figure 13d; although of the disturbances and uncertainties the control values are still bounded from the disturbances and uncertainties, it is an essential characteristic of this controller that generates robustness properties in the system.

4.4. Comparative of Real-World Experiments

The metrics presented in Section 4.2 were analyzed in this Section considering the RMSE of the control error vector. To demonstrate the efficacy of each controller during the experiments, the system experimented with disturbances produced by external forces such as wind, a better representation of this external disturbance is shown in Figure 14. Finally, we use each controller’s average computational time to compare the required time of each formulation.
Figure 15a compares the Euclidean norm of each controller during the real-world experimental results; the NMPC presents a better performance associated with more accuracy than the non-predictive formulations.
Figure 15b shows the RMSE of each controller; due to the disturbances and model mismatch presented during the experiment, the performance of each controller was affected; however, NMPC remains a better performance specifically in the Y and X axis where the trajectory presents an aggressive behavior.
Real-world experiments were carried out using the aerial vehicle Matrice 100 by DJI, which incorporates the onboard computer Jetson nano 4GB with the following hardware features Quad-core ARM Cortex-A57 MPCore processor. Additionally, the optimization problem was solved through multiple shooting schemes and using IPOPT, short for "Interior Point Optimizer executed in CasADi [46].
As expected, the NMPC formulation requires more time to compute the control signal (see Table 8); however, this control formulation can be implemented with a sufficiently high frequency to achieve the agile trajectories used in this work.

5. Discussion

NMPC controllers have recently demonstrated their validity in multirotor air vehicles, but only some authors have presented their performance in simulation, and real experimentation [17]. In this work, an NMPC control has been selected as the best option based on trajectory tracking, where the NMPC is robust in positioning errors and works better at high velocities, and the small radius of curvature of the reference trajectories [50]. On the other hand, baseline controllers have always shown adequate performance for multirotor trajectory tracking control [26]. However, the contrast between these two controllers is still limited in the literature; in [51], the authors compare a predictive contour control for time-optimal with respect to state-of-the-art and with respect to a professional pilot, evidencing better performance for the predictive control.
Non-predictive baseline feedback controllers such as inverse differential kinematics and inverse dynamic compensation have demonstrated accuracy and computational efficiency [52]. This justifies the comparison of our NMPC proposal with this class of controllers that are widely used for UAVs. In this case, higher trajectory-following accuracy is achieved with the NMPC control, which is more evident in real-world experimentation than in simulation, possibly due to the effect of extrinsic components of the system. Regarding the UAV used in this study, the DJI Matrice 100 UAV has proven to be a viable option for evaluating advanced control algorithms [53]. This is because it allows testing both in simulation and experimentation.
Perturbations are an essential component in the modeling and control of a UAV system, and simulation results have demonstrated the efficiency and robustness of non-linear controllers [29,32]. However, only some works with experimental results analyze disturbances in NMPC controllers. In [45], the authors explore the performance of an MPC controller against aerodynamic disturbances in trajectory tracking. In [42], an NMPC control is used for trajectory tracking applied to micro aerial vehicles, demonstrating good disturbance rejection capacity, stepped response, tracking performance, and slightly less computational effort than the linear MPC control.
Although the mean computation times of our NMPC control are higher than the baseline controllers, with 17.54 ms in the simulation and 25.36 ms in experimentation, these times are lower than the results of [54], which present an NMPC which enables real-time solutions with a sampling time of 50 ms to avoid collisions with dynamic obstacles with UAVs. Some works have achieved similar times in manipulator control with NMPC but have only been evaluated in simulation environments, leaving the controller performance in real environments in doubt [55]. Other works have achieved shorter computation times in NMPC control of electric vehicles, but these results are based on hardware loop tests [56]. In any case, our findings contribute to applying NMPC controllers in UAVs with precision registration in trajectory tracking and computation times that examine the control system’s efficiency.

6. Conclusions

This work developed the instantaneous kinematics and simplified dynamic model of the aerial vehicle Matrice 100, based on linear and angular velocities as inputs of the aerial vehicle. Because of this, the non-predictive control formulations considered in this work are the inverse differential kinematics and the inverse dynamic compensation; on the other hand, the predictive formulation selected is the NMPC. This work compares the control structures presented before considering the tracking of agile trajectories; simulations and real-world experiments were performed to evaluate the performance in terms of accuracy and computational efficiency, which are helpful features that could benefit future works.
The trajectory used for the comparison is known as the Lissajous trajectory, which presented an aggressive behavior with velocity variations where the controllers needed to demonstrate accuracy and efficiency. The real-world experiments showed the accuracy properties of the NMPC against disturbances; specifically, at the time of the experimentation, the system presented an average wind the velocity of approximately 21.5 km/h; additionally, the comparative results showed the superiority of the NMPC formulation clearly expressed in the RMSE calculation. Therefore, this work reports the advantages and disadvantages of each formulation analyzing accuracy; because of this, this work suggests the NMPC as the best option based on the comparison under trajectory tracking, which mainly works better at high reference velocities. However, although the accuracy property demonstrated by the NMPC compared with the feedback control approaches, the computational time is highly demanding using the onboard computers. Because of this, it could be unfeasible for miniature air vehicles.
Future works will develop considering soft constraints and Sequential quadratic programming (SQP) to improve the computational time of the NMPC formulation.

Author Contributions

Conceptualization, L.F.R., B.S.G. and J.M.T.; methodology, L.F.R. and V.H.A.; software, L.F.R. and B.S.G.; validation, L.F.R., B.S.G. and J.V.-A.; formal analysis, L.F.R., J.V.-A. V.H.A., and D.C.G.; investigation, L.F.R., J.V.-A. and J.M.T.; resources, L.F.R., V.H.A. and J.V.-A.; data preparation D.C.G. and J.M.T.; writing—original draft preparation, L.F.R. and B.S.G.; writing—review and editing, J.V.-A., V.H.A. and D.C.G.; visualization, L.F.R. and B.S.G.; supervision, V.H.A., D.C.G. and J.V.-A.; project administration, V.H.A., J.M.T. and J.V.-A. All authors have read and agreed to the published version of the manuscript.

Funding

The APC was funded by Universidad Indoamérica (Ecuador), funding code INV-0014-013-002.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

If anyone wants to obtain the original data of this paper, please contact with Bryan S. Guevara.

Acknowledgments

The authors would like to thank the Universidad Indoamérica; Universidad de las Fuerzas Armadas ESPE; SISAu Research Group, and the Research Group ARSI for the support and development of this work. The results of this work are part of the research project Advanced Control of Unmanned Aerial Vehicles developed by Universidad de las Fuerzas Armadas ESPE, and of the project “Educación 4.0 aplicada a la enseñanza de competencias STEAM” developed by Universidad Indoamérica.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kendoul, F. Survey of advances in guidance, navigation, and control of unmanned rotorcraft systems. J. Field Robot. 2012, 29, 315–378. [Google Scholar] [CrossRef]
  2. Mu, B.; Zhang, K.; Shi, Y. Integral Sliding Mode Flight Controller Design for a Quadrotor and theA pplication in a Heterogeneous Multi-Agent System. IEEE Trans. Ind. Electron. 2017, 64, 9389–9398. [Google Scholar] [CrossRef]
  3. Liang, X.; Fang, Y.; Sun, N.; Lin, H. A novel energy-coupling-based hierarchical control approach for unmanned quadrotor transportation systems. IEEE ASME Trans. Mechatronics 2019, 24, 248–259. [Google Scholar] [CrossRef]
  4. Xu, L.X.; Ma, H.J.; Guo, D.; Xie, A.H.; Song, D.L. Backstepping Sliding-Mode and Cascade Active Disturbance Rejection Control for a Quadrotor UAV. IEEE ASME Trans. Mechatronics 2020, 25, 2743–2753. [Google Scholar] [CrossRef]
  5. Lu, Q.; Ren, B.; Parameswaran, S. Uncertainty and Disturbance Estimator-Based Global Trajectory Tracking Control for a Quadrotor. IEEE ASME Trans. Mechatronics 2020, 25, 1519–1530. [Google Scholar] [CrossRef]
  6. Serrano, M.E.; Gandolfo, D.C.; Scaglia, G.J. Trajectory tracking controller for unmanned helicopter under environmental disturbances. ISA Trans. 2020, 106, 171–180. [Google Scholar] [CrossRef]
  7. Ou, J.; Guo, X.; Lou, W.; Zhu, M. Quadrotor Autonomous Navigation in Semi-Known Environments Based on Deep Reinforcement Learning. Remote Sens. 2021, 13, 4330. [Google Scholar] [CrossRef]
  8. Xu, B.; Wang, W.; Falzon, G.; Kwan, P.; Guo, L.; Sun, Z.; Li, C. Livestock classification and counting in quadcopter aerial images using Mask R-CNN. Int. J. Remote Sens. 2020, 41, 8121–8142. [Google Scholar] [CrossRef] [Green Version]
  9. Bircher, A.; Kamel, M.; Alexis, K.; Burri, M.; Oettershagen, P.; Omari, S.; Mantel, T.; Siegwart, R. Three-dimensional coverage path planning via viewpoint resampling and tour optimization for aerial robots. Auton. Robot. 2016, 40, 1059–1078. [Google Scholar] [CrossRef]
  10. Bircher, A.; Kamel, M.; Alexis, K.; Oleynikova, H.; Siegwart, R. Receding horizon path planning for 3D exploration and surface inspection. Auton. Robot. 2018, 42, 291–306. [Google Scholar] [CrossRef]
  11. Loianno, G.; Scaramuzza, D. Special issue on future challenges and opportunities in vision-based drone navigation. J. Field Robot. 2020, 37, 495–496. [Google Scholar] [CrossRef]
  12. Rajendran, S.; Srinivas, S. Air taxi service for urban mobility: A critical review of recent developments, future challenges, and opportunities. Transp. Res. Part E Logist. Transp. Rev. 2020, 143, 102090. [Google Scholar] [CrossRef]
  13. Hanover, D.; Foehn, P.; Sun, S.; Kaufmann, E.; Scaramuzza, D. Performance, precision, and payloads: Adaptive nonlinear MPC for quadrotors. IEEE Robot. Autom. Lett. 2022, 7, 690–697. [Google Scholar] [CrossRef]
  14. Mohta, K.; Watterson, M.; Mulgaonkar, Y.; Liu, S.; Qu, C.; Makineni, A.; Saulnier, K.; Sun, K.; Zhu, A.; Delmerico, J.; et al. Fast, autonomous flight in GPS-denied and cluttered environments. J. Field Robot. 2018, 35, 101–120. [Google Scholar] [CrossRef]
  15. Foehn, P.; Kaufmann, E.; Romero, A.; Penicka, R.; Sun, S.; Bauersfeld, L.; Laengle, T.; Cioffi, G.; Song, Y.; Loquercio, A.; et al. Agilicious: Open-source and open-hardware agile quadrotor for vision-based flight. Sci. Robot. 2022, 7, 6259. [Google Scholar] [CrossRef] [PubMed]
  16. Loquercio, A.; Kaufmann, E.; Ranftl, R.; Müller, M.; Koltun, V.; Scaramuzza, D. Learning high-speed flight in the wild. Sci. Robot. 2021, 6. [Google Scholar] [CrossRef] [PubMed]
  17. Bicego, D.; Mazzetto, J.; Carli, R.; Farina, M.; Franchi, A. Nonlinear Model Predictive Control with Enhanced Actuator Model for Multi-Rotor Aerial Vehicles with Generic Designs. J. Intell. Robot. Syst. Theory Appl. 2020, 100, 1213–1247. [Google Scholar] [CrossRef]
  18. Foehn, P.; Romero, A.; Scaramuzza, D. Time-Optimal Planning for Quadrotor Waypoint Flight. Sci. Robot. 2021, 6. [Google Scholar] [CrossRef]
  19. Torrente, G.; Kaufmann, E.; Fohn, P.; Scaramuzza, D. Data-Driven MPC for Quadrotors. IEEE Robot. Autom. Lett. 2021, 6, 3769–3776. [Google Scholar] [CrossRef]
  20. Kamel, M.; Stastny, T.; Alexis, K.; Siegwart, R. Model predictive control for trajectory tracking of unmanned aerial vehicles using robot operating system. Stud. Comput. Intell. 2017, 707, 3–39. [Google Scholar] [CrossRef]
  21. Acosta Núñez, J.F.; Ortiz, V.H.A.; Peces, G.G.d.R.; Salas, J.G. Energy-Saver Mobile Manipulator Based on Numerical Methods. Electronics 2019, 8, 1100. [Google Scholar] [CrossRef] [Green Version]
  22. Ortiz, J.S.; Palacios-navarro, G.; Andaluz, V.H.; Recalde, L.F. Three-Dimensional Unified Motion Control of a Robotic Standing Wheelchair for Rehabilitation Purposes. Sensors 2021, 21, 3057. [Google Scholar] [CrossRef] [PubMed]
  23. Gandolfo, D.C.; Salinas, L.R.; Brandão, A.; Toibero, J.M. Stable Path-Following Control for a Quadrotor Helicopter Considering Energy Consumption. IEEE Trans. Control Syst. Technol. 2017, 25, 1423–1430. [Google Scholar] [CrossRef]
  24. Recalde, L.F.; Guevara, B.S.; Carvajal, C.P.; Andaluz, V.H.; Varela-Aldás, J.; Gandolfo, D.C. System Identification and Nonlinear Model Predictive Control with Collision Avoidance Applied in Hexacopters UAVs. Sensors 2022, 22, 4712. [Google Scholar] [CrossRef]
  25. Nascimento, T.P.; Saska, M. Position and attitude control of multi-rotor aerial vehicles: A survey. Annu. Rev. Control 2019, 48, 129–146. [Google Scholar] [CrossRef]
  26. Lee, H.; Kim, H.J. Trajectory tracking control of multirotors from modelling to experiments: A survey. Int. J. Control. Autom. Syst. 2017, 15, 281–292. [Google Scholar] [CrossRef]
  27. Martins, L.; Cardeira, C.; Oliveira, P. Linear Quadratic Regulator for Trajectory Tracking of a Quadrotor. IFAC-PapersOnLine 2019, 52, 176–181. [Google Scholar] [CrossRef]
  28. Shakeel, T.; Arshad, J.; Jaffery, M.H.; Rehman, A.U.; Eldin, E.T.; Ghamry, N.A.; Shafiq, M. A Comparative Study of Control Methods for X3D Quadrotor Feedback Trajectory Control. Appl. Sci. 2022, 12, 9254. [Google Scholar] [CrossRef]
  29. Chen, F.; Lei, W.; Zhang, K.; Tao, G.; Jiang, B. A novel nonlinear resilient control for a quadrotor UAV via backstepping control and nonlinear disturbance observer. Nonlinear Dyn. 2016, 2, 1281–1295. [Google Scholar] [CrossRef]
  30. Shen, Z.; Tsuchiya, T. Singular Zone in Quadrotor Yaw–Position Feedback Linearization. Drones 2022, 6, 84. [Google Scholar] [CrossRef]
  31. Martins, L.; Cardeira, C.; Oliveira, P. Feedback Linearization with Zero Dynamics Stabilization for Quadrotor Control. J. Intell. Robot. Syst. Theory Appl. 2021, 101, 1–17. [Google Scholar] [CrossRef]
  32. Kidambi, K.B.; Fermuller, C.; Aloimonos, Y.; Xu, H. Robust Nonlinear Control-Based Trajectory Tracking for Quadrotors under Uncertainty. IEEE Control Syst. Lett. 2021, 5, 2042–2047. [Google Scholar] [CrossRef]
  33. Bhargavapuri, M.; Sahoo, S.R.; Kothari, M.; Abhishek. Robust nonlinear control of a variable-pitch quadrotor with the flip maneuver. Control Eng. Pract. 2019, 87, 26–42. [Google Scholar] [CrossRef]
  34. Li, Z.; Ma, X.; Li, Y. Robust tracking control strategy for a quadrotor using RPD-SMC and RISE. Neurocomputing 2019, 331, 312–322. [Google Scholar] [CrossRef]
  35. Pliego-Jiménez, J. Quaternion-based adaptive control for trajectory tracking of quadrotor unmanned aerial vehicles. Int. J. Adapt. Control Signal Process. 2021, 35, 628–641. [Google Scholar] [CrossRef]
  36. Muthusamy, P.k.; Garratt, M.; Pota, H.R.; Muthusamy, R. Realtime Adaptive Intelligent Control System for Quadcopter UAV with Payload Uncertainties. IEEE Trans. Ind. Electron. 2021, 69, 1641–1653. [Google Scholar] [CrossRef]
  37. Guan, X.; Lou, S.; Li, H.; Tang, T. Intelligent control of quad-rotor aircrafts with a STM32 microcontroller using deep neural networks. Ind. Robot 2021, 48, 700–709. [Google Scholar] [CrossRef]
  38. Al-Mahturi, A.; Santoso, F.; Garratt, M.A.; Anavatti, S.G. Self-Learning in Aerial Robotics Using Type-2 Fuzzy Systems: Case Study in Hovering Quadrotor Flight Control. IEEE Access 2021, 9, 119520–119532. [Google Scholar] [CrossRef]
  39. Sun, C.; Liu, M.; Liu, C.; Feng, X.; Wu, H. An Industrial Quadrotor UAV Control Method Based on Fuzzy Adaptive Linear Active Disturbance Rejection Control. Electronics 2021, 10, 376. [Google Scholar] [CrossRef]
  40. Jiang, Z.; Lynch, A.F. Quadrotor motion control using deep reinforcement learning. J. Unmanned Veh. Syst. 2021, 9, 234–251. [Google Scholar] [CrossRef]
  41. Pi, C.H.; Ye, W.Y.; Cheng, S. Robust Quadrotor Control through Reinforcement Learning with Disturbance Compensation. Appl. Sci. 2021, 11, 3257. [Google Scholar] [CrossRef]
  42. Kamel, M.; Burri, M.; Siegwart, R. Linear vs Nonlinear MPC for Trajectory Tracking Applied to Rotary Wing Micro Aerial Vehicles. IFAC-PapersOnLine 2017, 50, 3463–3469. [Google Scholar] [CrossRef]
  43. Nguyen, H.; Kamel, M.; Alexis, K.; Siegwart, R. Model Predictive Control for Micro Aerial Vehicles: A Survey. In Proceedings of the 2021 European Control Conference, ECC 2021, Rotterdam, The Netherlands, 29 June–2 July 2020; pp. 1556–1563. [Google Scholar] [CrossRef]
  44. Gros, S.; Zanon, M.; Quirynen, R.; Bemporad, A.; Diehl, M. From linear to nonlinear MPC: Bridging the gap via the real-time iteration. Int. J. Control 2020, 93, 62–80. [Google Scholar] [CrossRef]
  45. 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]
  46. Andersson, J.A.; Gillis, J.; Horn, G.; Rawlings, J.B.; Diehl, M. CasADi: A software framework for nonlinear optimization and optimal control. Math. Program. Comput. 2019, 11, 1–36. [Google Scholar] [CrossRef]
  47. Kahn, M.E.; Roth, B. The Near-Minimum-Time Control Of Open-Loop Articulated Kinematic Chains. J. Dyn. Syst. Meas. Control 1971, 93, 164–172. [Google Scholar] [CrossRef]
  48. Lloyd, S.; Irani, R.; Ahmadi, M. A numeric derivation for fast regressive modeling of manipulator dynamics. Mech. Mach. Theory 2021, 156, 104149. [Google Scholar] [CrossRef]
  49. Herrera, D.; Roberti, F.; Carelli, R.; Andaluz, V.; Varela, J.; Ortiz, J.; Canseco, P. Modeling and Path-Following Control of a Wheelchair in Human-Shared Environments. Int. J. Humanoid Robot. 2018, 15, 1850010. [Google Scholar] [CrossRef]
  50. Bai, G.; Meng, Y.; Liu, L.; Luo, W.; Gu, Q.; Liu, L. Review and comparison of path tracking based on model predictive control. Electronics 2019, 8, 1077. [Google Scholar] [CrossRef] [Green Version]
  51. Romero, A.; Sun, S.; Foehn, P.; Scaramuzza, D. Model predictive contouring control for time-optimal quadrotor flight. IEEE Trans. Robot. 2022, 38, 3340–3356. [Google Scholar] [CrossRef]
  52. Amin, R.; Aijun, L.; Shamshirband, S. A review of quadrotor UAV: Control methodologies and performance evaluation. Int. J. Autom. Control 2016, 10, 87–103. [Google Scholar] [CrossRef]
  53. Tripathi, V.K.; Yogi, S.C.; Kamath, A.K.; Behera, L.; Verma, N.K.; Nahavandi, S. A Disturbance Observer-Based Intelligent Finite-Time Sliding Mode Flight Controller Design for an Autonomous Quadrotor. IEEE Syst. J. 2022, 16, 1649–1660. [Google Scholar] [CrossRef]
  54. Lindqvist, B.; Mansouri, S.S.; Agha-mohammadi, A.A.; Nikolakopoulos, G. Nonlinear MPC for collision avoidance and control of UAVs with dynamic obstacles. IEEE Robot. Autom. Lett. 2020, 5, 6001–6008. [Google Scholar] [CrossRef]
  55. Reinhold, J.; Baumann, H.; Meurer, T. Constrained-Differential-Kinematics-Decomposition-Based NMPC for Online Manipulator Control with Low Computational Costs. Robotics 2023, 12, 7. [Google Scholar] [CrossRef]
  56. Ju, F.; Zong, Y.; Zhuang, W.; Wang, Q.; Wang, L. Real-Time NMPC for Speed Planning of Connected Hybrid Electric Vehicles. Machines 2022, 10, 1129. [Google Scholar] [CrossRef]
Figure 1. DJI Matrice 100 UAV platform representation.
Figure 1. DJI Matrice 100 UAV platform representation.
Drones 07 00144 g001
Figure 2. Identification and validation, (a) shows the identification process under step signals, and (b) presents the validation of the proposed dynamic model considering smooth signals.
Figure 2. Identification and validation, (a) shows the identification process under step signals, and (b) presents the validation of the proposed dynamic model considering smooth signals.
Drones 07 00144 g002
Figure 3. General scheme of the kinematic controller.
Figure 3. General scheme of the kinematic controller.
Drones 07 00144 g003
Figure 4. General scheme of the dynamic controller.
Figure 4. General scheme of the dynamic controller.
Drones 07 00144 g004
Figure 5. General scheme of the NMPC.
Figure 5. General scheme of the NMPC.
Drones 07 00144 g005
Figure 6. Simulation tracking results considering a Lissajous trajectory using the inverse differential kinematic controller; where (a) shows the evolution of the system in the plane I x , I y and (b) considering the plane I x , I z ; finally (c,d) illustrate the control error and actions, respectively.
Figure 6. Simulation tracking results considering a Lissajous trajectory using the inverse differential kinematic controller; where (a) shows the evolution of the system in the plane I x , I y and (b) considering the plane I x , I z ; finally (c,d) illustrate the control error and actions, respectively.
Drones 07 00144 g006
Figure 7. Simulation tracking results considering a Lissajous trajectory using the inverse dynamic compensation controller; where (a) shows the evolution of the system in the plane I x , I y and (b) over the plane I x , I z ; finally (c,d) represent the control error and actions, respectively.
Figure 7. Simulation tracking results considering a Lissajous trajectory using the inverse dynamic compensation controller; where (a) shows the evolution of the system in the plane I x , I y and (b) over the plane I x , I z ; finally (c,d) represent the control error and actions, respectively.
Drones 07 00144 g007
Figure 8. Simulation tracking results considering a Lissajous trajectory using the NMPC controller; where (a) shows the evolution of the system in the plane I x , I y and (b) over the plane I x , I z ; finally (c,d) represent the control error and actions, respectively.
Figure 8. Simulation tracking results considering a Lissajous trajectory using the NMPC controller; where (a) shows the evolution of the system in the plane I x , I y and (b) over the plane I x , I z ; finally (c,d) represent the control error and actions, respectively.
Drones 07 00144 g008
Figure 9. Comparative results of the proposed controllers during the simulation experiments; where (a) illustrates the norm of the control error during the simulation of each controller (b) shows the RMSE of each controller along the simulation.
Figure 9. Comparative results of the proposed controllers during the simulation experiments; where (a) illustrates the norm of the control error during the simulation of each controller (b) shows the RMSE of each controller along the simulation.
Drones 07 00144 g009
Figure 10. DJI Matrice 100 Experimental Platform.
Figure 10. DJI Matrice 100 Experimental Platform.
Drones 07 00144 g010
Figure 11. Real-world tracking results considering the inverse differential kinematic controller; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions, respectively.
Figure 11. Real-world tracking results considering the inverse differential kinematic controller; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions, respectively.
Drones 07 00144 g011
Figure 12. Real-world tracking results considering the inverse dynamic compensation; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions.
Figure 12. Real-world tracking results considering the inverse dynamic compensation; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions.
Drones 07 00144 g012
Figure 13. Real-world tracking results considering the NMPC controller; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions, respectively.
Figure 13. Real-world tracking results considering the NMPC controller; where (a,b) show the evolution of the system; finally (c,d) represent the control error and actions, respectively.
Drones 07 00144 g013
Figure 14. Wind velocity during the real-world experiments.
Figure 14. Wind velocity during the real-world experiments.
Drones 07 00144 g014
Figure 15. Comparative results of the proposed controllers during the real-world experiments; where (a) illustrates the Euclidean norm of the control error during the execution of each controller (b) shows the RMSE of each controller.
Figure 15. Comparative results of the proposed controllers during the real-world experiments; where (a) illustrates the Euclidean norm of the control error during the execution of each controller (b) shows the RMSE of each controller.
Drones 07 00144 g015
Table 1. Parameters of the aerial vehicle DJI Matrice 100.
Table 1. Parameters of the aerial vehicle DJI Matrice 100.
Parameters
π 1 = 2.11 π 2 = 0.005 π 3 = 1.8 π 4 = 3.17
π 5 = 1.78 π 6 = 0.39 π 7 = 0.003 π 8 = 0.03
π 9 = 0.006 π 10 = 0.02 π 11 = 0.002 π 12 = 0.06
π 13 = 0.70 π 14 = 0.02 π 15 = 0.05 π 16 = 0.01
π 17 = 0.005 π 18 = 0.01
Table 2. Reference trajectory and initial conditions used in simulation experiments.
Table 2. Reference trajectory and initial conditions used in simulation experiments.
Initial Positions [m]-[rad]Initial Velocities [m/s]-[rad/s]Reference Trajectory [m]-[rad]
η x o = 0 μ l o = 0 η x d = 3 sin ( 0.4 t ) + 3
η y o = 0 μ m o = 0 η y d = 3 sin ( 0.8 t )
η z o = 1 μ n o = 0 η z d = 1.5 sin ( 0.2 t ) + 8
η ψ o = 0 ω o = 0 η ψ d = 0
Table 3. Proposed values for the inverse differential kinematics controller.
Table 3. Proposed values for the inverse differential kinematics controller.
ParametersValuesParametersValues
K 1 d i a g ( 1 ) R 4 × 4 K 2 d i a g ( 2 2 2 10 ) R 4 × 4
Table 4. Proposed values for the inverse dynamic compensation controller.
Table 4. Proposed values for the inverse dynamic compensation controller.
ParametersValuesParametersValues
K 3 d i a g ( 1 ) R 4 × 4 K 4 d i a g ( 1 ) R 4 × 4
Table 5. Proposed values for the NMPC scheme.
Table 5. Proposed values for the NMPC scheme.
ParametersValuesParametersValues
Q d i a g ( 0.9 ) R 4 × 4 R d i a g ( 0.1 ) R 4 × 4
μ ref m i n [ 2.4 , 2.4 , 2.4 , 11.5 ] μ ref m a x [ 2.4 , 2.4 , 2.4 , 11.5 ]
T [ s ] 1
Table 6. Average computational time for each controller in simulations.
Table 6. Average computational time for each controller in simulations.
KinematicDynamicNMPC
Avg. dt [ms] 0.054 0.141 17.54
Table 7. Reference trajectory and initial conditions used in real-world conditions.
Table 7. Reference trajectory and initial conditions used in real-world conditions.
Initial Positions [m]-[rad]Initial Velocities [m/s]-[rad/s]Reference Trajectory [m]-[rad]
η x o = 2 μ l o = 0 η x d = 3 sin ( 0.16 t ) + 3
η y o = 0 μ m o = 0 η y d = 3 sin ( 0.32 t )
η z o = 1 μ n o = 0 η z d = 1.5 sin ( 0.2 t ) + 8
η ψ o = 0 ω o = 0 η ψ d = 0
Table 8. Average computational time for each controller.
Table 8. Average computational time for each controller.
KinematicDynamicNMPC
Avg. dt [ms] 0.075 0.26 25.36
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Guevara, B.S.; Recalde, L.F.; Varela-Aldás, J.; Andaluz, V.H.; Gandolfo, D.C.; Toibero, J.M. A Comparative Study between NMPC and Baseline Feedback Controllers for UAV Trajectory Tracking. Drones 2023, 7, 144. https://doi.org/10.3390/drones7020144

AMA Style

Guevara BS, Recalde LF, Varela-Aldás J, Andaluz VH, Gandolfo DC, Toibero JM. A Comparative Study between NMPC and Baseline Feedback Controllers for UAV Trajectory Tracking. Drones. 2023; 7(2):144. https://doi.org/10.3390/drones7020144

Chicago/Turabian Style

Guevara, Bryan S., Luis F. Recalde, José Varela-Aldás, Victor H. Andaluz, Daniel C. Gandolfo, and Juan M. Toibero. 2023. "A Comparative Study between NMPC and Baseline Feedback Controllers for UAV Trajectory Tracking" Drones 7, no. 2: 144. https://doi.org/10.3390/drones7020144

Article Metrics

Back to TopTop