Next Article in Journal
Expressing Personalities of Conversational Agents through Visual and Verbal Feedback
Next Article in Special Issue
Choosing the Best Locomotion Mode in Reconfigurable Rovers
Previous Article in Journal
A Study of the Sulfidation Behavior on Palladium-Coated Copper Wire with a Flash-Gold Layer (PCA) after Wire Bonding
Previous Article in Special Issue
Q-Learning of Straightforward Gait Pattern for Humanoid Robot Based on Automatic Training Platform
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Embedded Flight Control Based on Adaptive Sliding Mode Strategy for a Quadrotor Micro Air Vehicle

by
Herman Castañeda
* and
J.L. Gordillo
Tecnologico de Monterrey, Escuela de Ingenieria y Ciencias, Monterrey, NL 64849, Mexico
*
Author to whom correspondence should be addressed.
Electronics 2019, 8(7), 793; https://doi.org/10.3390/electronics8070793
Submission received: 14 June 2019 / Revised: 5 July 2019 / Accepted: 8 July 2019 / Published: 16 July 2019
(This article belongs to the Special Issue Motion Planning and Control for Robotics)

Abstract

:
The design of an embedded flight controller for a quadrotor micro air vehicle, which is subject to uncertainties and perturbations, is addressed. In order to obtain robustness against bounded uncertainties and disturbances, an adaptive sliding mode controller is proposed. The control adaptive gains allow using only necessary control to satisfy the task, reducing the chattering effect and at the same time reject external perturbations. Furthermore, a stability analysis of the closed-loop system is given. Finally, simulations and experimental results carried out on a commercial micro air vehicle demonstrate the feasibility and advantages of the proposed flight controller.

1. Introduction

The study about Unmanned Aerial Vehicles (UAVs), particularly the quadrotor systems, has grown exponentially, such that many applications have been developed due to their advantages such as vertical take-off and landing, hovering, and maneuverability. Then, quad-rotors are employed in inspection-, mapping-, and surveillance-related tasks. Recently, Micro Air Vehicles (MAVs) (according to the definition in [1], these vehicles have a mass < 0 . 1 kg and a size < 0 . 15 m) have attracted attention because they can access confined and denied GPS spaces such as inside buildings, pipelines, halls, factories, schools, and more. Since MAVs are designed to operate in the above places, they require more advanced controllers to achieve the commanded tasks.
Many commercial quadrotors are available on the market. Nonetheless, we focus on the Parrot mini drone rolling spider, which due to its tiny size is classified as an MAV. These drones are safe and reliable, and they include sensors, such as an altimeter, an ultrasonic sensor, an Inertial Measurement Unit (IMU), and a camera. A remarkable advantage is that, it is possible to test low level control due to the recently open architecture for MATLAB by means of the Simulink Support Package for Parrot Minidrones [2] or by getting started with MIT’s Rolling Spider MATLAB Toolbox [3].
Regarding the small size of UAVs, uncertainties and external disturbances affect the performance of the vehicle. Hence, tasks conducted by these MAVs require control approaches able to provide accuracy, efficient consumption of energy, and robustness. In order to control a quadrotor MAV subject to uncertainties and external disturbances, adaptive control [4], robust control [5], optimal control [6], and intelligent control [7] have been developed. Nevertheless, the aforementioned results depend of the knowledge of the system or a training process for the last one. Even more, they show limited robustness under external perturbations.
Robust control techniques for UAVs, with some approaches such as [8], where a robust attitude control scheme subject to actuator faults and wind gust was investigated, require much information estimated via an extended state observer. On the other hand, sliding mode controllers appear as one of the most available approaches due to their advantages such as robustness as pointed out in [9,10,11,12,13,14,15]. Nonetheless, the controller parameters remain fixed, and the tuning of these gains could be complex.
The super twisting approach is a powerful sliding mode controller, which has been employed in flight control for quadrotors in [16,17,18]. The algorithm is robust to bounded and derivative bounded perturbations, but the magnitude of these bounds must be known in order to guarantee stability. On the other hand, adaptive strategies have arisen to deal with the control effort such as in [19,20]. However, the tuning of these algorithms is very difficult. Previous investigations were relative to standard size UAVs (more than 0 . 5 kg), and they proved their strategies on quadrotors of typically more than a kilogram of weight. Hence, it is clear that tiny vehicles such as micro air vehicles have more sensitivity to external perturbations compared with the standard size, demanding robust and adaptive controllers to guarantee the commanded task.

Contribution

An embedded flight controller for a quadrotor MAV subject to uncertainties and perturbations is the main contribution of this paper. An adaptive sliding mode technique is the core of the approach, where the advantages rely on not overestimating the magnitude of the gain and robustness against bounded disturbances. Due to adaptive gains, only necessary control is employed to satisfy the task, reducing the chattering effect and at the same time being able to reject external perturbations. Furthermore, a stability analysis of the closed-loop system is provided. Finally, simulations and experimental results carried out on a commercial rolling spider micro drone demonstrate the feasibility and advantages of the proposed flight controller.
The organization of this paper is as follows: Section 2 provides the modeling of the micro air vehicle, whereas the design of the embedded flight controller is detailed in Section 3. Experimental results are described in Section 4. At the end, some conclusions are given.

2. Mathematical Model

In this section, the mathematical model of the parrot rolling spider micro quadrotor is presented. The kinematics and dynamics of the MAV moving in space are described by the following state variables p = [ x , y , z ] T R 3 and Θ = [ ϕ , θ , ψ ] T { π , π } , which are the linear and angular positions, respectively in the inertial reference frame, whereas ν = [ u , v , w ] T R 3 and ω = [ p , q , r ] T R 3 are velocities expressed in the body reference frame (see Figure 1).
Thus, following the Newton–Euler convention, the quad-rotor model is given by [21]:
p ˙ = R 1 ( Θ ) v
Θ ˙ = R 2 1 ( Θ ) ω
F = m ( v ˙ + ω × v )
τ = I ω ˙ + ω × I ω ,
where m is the aircraft mass and the rotation matrix R 1 ( Θ ) S O ( 3 ) and R 2 ( Θ ) R 3 × 3 transform the body frame to inertial frame. The matrices are denoted by:
R 1 ( Θ ) = c ψ c θ s ψ c ϕ + c ψ s θ s ϕ s ψ s ϕ + c ψ s θ c ϕ s ψ c θ c ψ c ϕ + s ψ s θ s ϕ c ψ s ϕ + s ψ s θ c ϕ s θ c θ s ϕ c θ c ϕ
and:
R 2 ( Θ ) = 1 s ϕ t θ c ϕ t θ 0 c ϕ s ϕ 0 s ϕ / c θ c ϕ / c θ
where s x , c y , and t z are s i n ( x ) , c o s ( y ) , and t a n ( z ) , respectively.
The inertia assuming that the vehicle is symmetric I R 3 × 3 is given by:
I = I x 0 0 0 I y 0 0 0 I z
The force and torque vectors are described by:
F = F g + F m
τ = τ m + τ g y
where,
F g = R 1 1 ( Θ ) 0 0 m g = m g S θ m g C θ S ϕ m g C θ C ϕ
is the gravity vector. On the other hand, the sum of each thrust produced by a motor-propeller represents the total thrust acting on the z-axis of the body frame, defined as:
F m = 0 0 ( T 1 + T 2 + T 3 + T 4 ) ,
where T i for i = 1 , 2 , 3 , 4 is the thrust provided by each motor. In contrast, torques are produced by differences in rotor speeds, obtaining roll, pitch, and yaw motions, which are defined according an “X” configuration:
τ m = l 2 ( T 2 + T 3 T 1 T 4 ) l 2 ( T 1 + T 2 T 3 T 4 ) Q 1 + Q 2 Q 3 + Q 4 ,
where l is an arm of the quadrotor. Q i for i = 1 , 2 , 3 , 4 is the rotor torque. The gyroscopic effects are denoted by:
τ g y = j r q ( Ω 1 Ω 2 + Ω 3 Ω 4 ) j r p ( Ω 1 Ω 2 + Ω 3 Ω 4 ) 0 ,
where j r is the rotor inertia, p , q are the angular velocities in the body frame, and Ω i for i = 1 , 2 , 3 , 4 is the angular rate of the i th rotor. However, assuming standard approximations of the thrust and torque, these are expressed as follows:
T i = k T Ω i 2
Q i = k Q Ω i 2 ,
where k T is a constant of thrust and k Q is a torque constant. Therefore, the actual torques, i.e., τ ϕ , τ θ , τ ψ , τ , which represent the roll, pitch, yaw, and throttle torques, respectively, are explicitly given by:
τ ϕ τ θ τ ψ τ = l 2 k T l 2 k T l 2 k T l 2 k T l 2 k T l 2 k T l 2 k T l 2 k T k Q k Q k Q k Q k T k T k T k T Ω 1 2 Ω 2 2 Ω 3 2 Ω 4 2 .
Finally, the parameters of the rolling spider micro drone are displayed in Table 1.

3. Embedded Flight Control Design

In this section, the proposed flight controller is addressed. The control objective was to stabilize the quadrotor MAV in spite of uncertainties and external perturbations. An adaptive sliding mode strategy was used as the core of the proposed method. Then, in order to design the controller, we used a simplified model under the following assumptions:
Assumption 1.
We considered that linear and angular accelerations in the body frame are equal to the inertial frame, and this is based on the small angles theorem.
Assumption 2.
We separated the problem into the actuated system, which refers to the ϕ , θ , ψ and z dynamics and an underactuated system, corresponding to the x and y dynamics. Hence, the model for control design purposes is given by:
A c t u a t e d ϕ ¨ = ( I y I z ) I x θ ˙ ψ ˙ j r I x Ω a θ ˙ + τ ϕ I x + d ϕ θ ¨ = ( I z I x ) I y ϕ ˙ ψ ˙ + j r I y Ω a ϕ ˙ + τ θ I y + d θ ψ ¨ = ( I x I y ) I z θ ˙ ϕ ˙ + τ ψ I z + d ψ z ¨ = τ m ( C ϕ C θ ) + g + d z
U n d e r a c t u a t e d x ¨ = τ m ( C ψ S θ C ψ + S ϕ S ψ ) + d x y ¨ = τ m ( C ψ S θ S ψ + S ϕ C ψ ) + d y
Thus, we proposed two controllers, one in order to control the actuated system, where an adaptive sliding mode control is adopted, and a virtual control concept used to solve the underactuated dynamics.

3.1. Actuated System

Consider the uncertain and disturbed actuated dynamics as:
ζ ¨ = f ( ζ , t ) + g ( ζ ) u + d ( t )
y = h ( ζ )
where the state is denoted by ζ = [ ϕ , θ , ψ , z ] T , and:
f ( ζ , t ) = f 0 ( ζ , t ) + f u ( ζ , t )
g ( ζ ) = g 0 ( ζ ) + g u ( ζ )
u = [ τ ϕ , τ θ , τ ψ , T t ] T
d ( t ) = [ d ϕ , d θ , d ψ , d z ] T ,
where f 0 ( t , x ) = [ a 1 , a 2 , a 3 , a 4 ] T and g 0 ( x ) = [ b 1 , b 2 , b 3 , b 4 ] are the nominal model, whereas f u ( x , t ) = Δ [ a 1 , a 2 , a 3 , a 4 ] T and g u ( x ) = Δ [ b 1 , b 2 , b 3 , b 4 ] are parametric uncertainties. Furthermore, a 1 = ( I y I z ) I x θ ˙ ψ ˙ j r I x θ ˙ Ω a , a 2 = ( I z I x ) I y ϕ ˙ ψ ˙ + j r I y ϕ ˙ Ω a , a 3 = ( I x I y ) I z θ ˙ ϕ ˙ , a 4 = g , b 1 = 1 I x , b 2 = 1 I y , b 3 = 1 I z , b 4 = 1 m ( c ϕ c θ ) , and d ( t ) includes uncertainties and perturbations satisfying | d ( t ) | L , where L > 0 is an upper bound of the perturbation. Hence, by defining the error as:
e = ζ 1 d ζ 1 , e ˙ = ζ 2 d ζ 2 ,
where ζ 1 d = [ ϕ d , θ d , ψ d , z ] T and ζ 2 d = [ ϕ ˙ d , θ ˙ d , ψ ˙ d , z ˙ d ] T are the tracking references. Now, we define the following sliding surface:
s = e ˙ + λ e
where λ > 0 . Then, deriving Equation (26), one gets:
s ˙ = e ¨ + λ e ˙ = ξ ¨ 1 d f ( ξ , t ) + g ( ξ ) u + λ ξ ˙ 1 d ξ ˙ 1
Thus, considering a feedback controller:
u = g ( ξ ) 1 f ( ζ , t ) ζ ¨ 1 d λ ( ζ ˙ 1 d ζ ˙ 1 ) + u a
where the auxiliary control u a is given by the following adaptive sliding mode strategy:
u a = K a ( t ) | s | 1 / 2 s i g n ( s ) k 2 s
where K a ( t ) is the control gain, which adapts according to:
K ˙ a ( t ) = k sign ( | s | μ ) , if K a > K m i n , K m i n , if K a K m i n ,
and k 2 * > 0 is a design fixed gain. This controller Equation (29) adapts one of its gains Equation (30) in order to establish minimal control effort according to K m i n and maintain stability, where k regulates the rate of adaptation; as a consequence, this parameter regulates how fast the controller responds to perturbations. μ is a parameter to detect the loss of the sliding mode and thus increase the gain if required. As has already been presented, this control method is robust against bounded perturbations/uncertainties, and the control gain is not overestimated, reducing the chattering effect.

3.2. Underactuated System

In order to control the x and y coordinates, the virtual control strategy is followed, where the objective is to achieve x d , y d desired coordinates. Then, by defining now the error as:
e = ξ d ξ = x d x y d y
with time derivative:
e ˙ = ξ ˙ d ξ ˙ = x ˙ d x ˙ y ˙ d y ˙
Now, given a desired trajectory x d , y d , ψ d , the x , y positions can be reached via desired roll and pitch angles ϕ d , θ d . From Equation (18), the following virtual control is obtained:
ϕ d = s i n 1 m T t ( s ψ d u v 1 c ψ d u v 2 )
θ d = s i n 1 m T t u v 1 s ψ d s ϕ d c ψ d c ϕ d .
where:
u v = u v 1 u v 2 = K p e + K d e ˙ ,
where K p > 0 and K d > 0 .

3.3. Closed-Loop Stability

The closed-loop stability of the the fully-actuated system Equation (19) in a closed loop with the controller Equation (28) is analyzed. First, let us express the system in a closed loop as:
s ˙ = Δ ( t ) + d ( t ) + u a ,
where Δ ( t ) lumps all uncertainties of the model relative to f u ( x , t ) and g u ( x ) satisfying | g u ( x ) | | g 0 ( x ) | γ 2 < < 1 , x with t > 0 , respectively. Therefore, we define a new variable:
φ ( t ) = ( t ) + d ( t ) ,
which includes all uncertainties and external disturbances, which is supposed to be globally bounded by:
| φ ( t ) | L , L > 0 .
Thus, Equation (36) becomes:
s ˙ = K a ( t ) | s | 1 / 2 s i g n ( s ) k 2 s + φ ( t ) ,
Now, in order to verify the stability, we propose the following candidate Lyapunov function:
V ( t ) = s T s
with V ( 0 ) = 0 and V ( t ) > 0 for s 0 . A sufficient condition to guarantee that the trajectory of the error from reaching the phase to sliding mode is to choose a control approach such that it fulfills:
V ˙ ( t ) = s s ˙ < 0 , s 0 .
By substituting Equation (39) into Equation (41), one gets:
V ˙ ( t ) = s K a i ( t ) | s | 1 / 2 s i g n ( s ) k 2 s + φ ( t ) = | s | K a i ( t ) | s | 1 / 2 k 2 s 2 + s φ ( t ) | s | K a ( t ) | s | 1 / 2 k 2 s 2 + | s | L
stability under the bounded uncertainties/perturbations. φ i ( t ) is guaranteed if:
0 > | s | K a ( t ) | s | 1 / 2 k 2 s 2 + | s | L L < K a ( t ) | s | 1 / 2 + k 2 | s |
is fulfilled, i.e., the control signal is greater than the uncertainty/perturbation, leading to the following constraint on the adaptive gain:
K a ( t ) > 1 | s | 1 / 2 L k 2 | s | .
The stability of the under-actuated part, i.e., the x and y dynamics, is analyzed as follows: recalling that the calculation of the desired roll and pitch angles ϕ d , θ d and ψ d via the virtual controller strategy and due to the attitude control ensures convergence from [ ϕ , θ , ψ ] T to [ ϕ d , θ d , ψ d ] T in spite of the uncertainties/perturbations.

4. Simulation and Experimental Results

In this section, with the aim to verify the performance of the proposed embedded flight controller, simulation and experimental tests are carried out.

4.1. Simulation Results

The simulation scheme consists of the controller Equation (28) in closed loop with the quadrotor MAV dynamics Equations (1)–(4). Simulations were conducted through MATLAB Simulink. A second order solver with a sample time of 0 . 005 s was implemented. The case of regulation of the actuated system, i.e., ϕ , θ , ψ , z dynamics was evaluated. On the other hand, the presence of persistent disturbances was considered as well, which is a constant vector of force defined as d ( t ) = [ d ϕ , d θ , d ψ , d z ] T = [ 0.0005 , 0.0005 , 0.00005 , 0.01 ] T N at time interval d ( t ) > 8 s. This value stands and an excitation of 30 % of the energy required for flight. Now, to evaluate the advantages of our adaptive controller, a comparison versus standard nonlinear feedback linearization, represented by Equation (28) with:
u a = K p e + K d e ˙
with K p > 0 and K d > 0 , and also versus the proportional integral derivative with gravity compensation controller, expressed as:
u = K p e + k i e + K d e ˙ + [ 0 , 0 , 0 , m g ] T ,
where e and e ˙ are defined in Equation (25), K p > 0 , K i > 0 , and K d > 0 . Notice that the x and y controllers were not verified due to them being the same for each controller. Figure 2 displays the stabilization of state variables. It is clear that all controllers work properly to convergence to zero, where adaptive sliding mode control presented a better response. Also, the robustness of the controllers to reject external perturbations can be appreciated, where our proposed control rejected better than feedback linearization, which needed information of the perturbations to mitigate them, and than PID control, which due to the integral action, can deal with this problem.
In Figure 3, the control input signals are presented. A similar energy consumption is shown, where adaptive sliding mode control (asmc) spent more energy; this is related to the rejection of perturbations. In the end, adaptive gains are illustrated; its behavior verified the design mechanics due to the increase toward convergence and when disturbances appeared.

4.2. Experimental Results

The proposed embedded flight control was implemented in the rolling spider micro quadrotor by Parrot depicted in Figure 1. This experimental platform allowed designing and building flight control algorithms for the Parrot rolling spider. The algorithms were deployed over Bluetooth. Moreover, state information was obtained via sensor fusion from on-board sensors such as the ultrasonic sensor, IMU, air pressure, and the downward-facing camera through Kalman filters, which are defined by the rolling spider toolbox package.
The adaptive sliding mode controller was applied via MATLAB/Simulink, and we used the following control parameters: k = d i a g [ 0 . 7 , 0 . 7 , 0 . 7 , 0 . 7 ] , k 2 = d i a g [ 0 . 1 , 0 . 1 , 0 . 1 , 0 . 2 ] , λ = d i a g [ 1 , 1 , 1 , 0 . 3 ] , μ = d i a g [ 0 . 05 , 0 . 05 , 0 . 05 , 0 . 02 ] , K m i n = d i a g [ 0 . 01 , 0 . 01 , 0 . 01 , 0 . 01 ] . For the position controller, the gains were: k p = d i a g [ 0 . 24 , 0 . 24 ] and K d = d i a g [ 0 . 1 , 0 . 1 ] . Two scenarios were tested. The first one considered the uncertainties of modeling without external perturbation.

4.2.1. Case without Perturbations

In Figure 4, linear and angular responses are plotted, where the roll, pitch, yaw, x, and y variables were forced to converge to zero, while z was commanded to achieve 1 . 1 m. Notice that a transition phase is clearly shown; this was always different because of the initial conditions of the experiments differed. Furthermore, the controller was based on the nominal model. Therefore, uncertainties such as parametric variations (the vehicle had external wheels, which increased the weight and inertia moments), battery discharge, and electronic issues (response of the microcontroller, speed controllers of the motors, and more), affect the performance of the vehicle. However, due to the robustness properties of the control, stabilization was guaranteed.
The errors of the state variables with respect to references are illustrated in Figure 5. It is possible to note that the controlled variables by the adaptive sliding strategy, i.e., angles and altitude, kept a small error, less that 0.1 rad, regarding the x and y variables.
Figure 6 shows the applied angular velocities of the motors. Note that Motors 2 and 4 have a negative sign. This is because they spin in the opposite sense with respect to Motors 1 and 3. The adaptive gains of the controllers allow stabilizing once the MAV has achieved the proper altitude.
Figure 7 displays the evolution of the adaptive control gains. It is clear that at the start, the gains increased their values to reach the control objective, then they decreased until a defined minimal value, where stability was guaranteed.

4.2.2. Case with Perturbations

The second scenario considered model uncertainties, as well as external disturbances. Then, a perturbation, which consisted of a force induced by hand, was applied to the vehicle approximately in t = 10 s. Recalling that this quadrotor MAV is tiny, external disturbances notably affect its performance. Figure 8 displays the state response, where the stabilization was clearly more difficult. Nevertheless, the adaptive flight control could achieve and keep stability even in the presence of such uncertainties and external perturbations.
Figure 9 shows the error response subject to external disturbances.
In Figure 10 as well, the corresponding angular velocities, which are the control inputs of the systems, are depicted. Again, due to its adaptive controller gains, the vehicle achieved and kept stability against uncertainties and external perturbations.
Finally, Figure 11 shows the adaptive control gains’ behavior under a perturbed environment; such a picture demonstrates that gains increase or decrease their values to reject such disturbances.

5. Conclusions

An embedded flight control for a quadrotor micro air vehicle subject to uncertainties and perturbations was designed and implemented. An adaptive sliding mode technique was the core of the approach, which was robust against bounded disturbances. Due to adaptive gains, necessary control was employed as the task requirement, reducing the chattering effect, and it was able to reject external perturbations. Even more, a stability analysis of the closed-loop system was provided. Finally, simulations and two experimental scenarios were conducted on a Parrot rolling spider micro drone, first with no perturbations and second disturbed, where the feasibility and advantages of the proposed control were demonstrated.

Author Contributions

Conceptualization, methodology, and formal analysis H.C.; supervision, J.L.G.

Funding

This research received no external funding.

Acknowledgments

The authors thank Sergio Lopez and Horacio Vorrath for their help in achieving the experiments and Laboratorio Nacional de Robotica del Centro y Norte de Mexico and Tecnologico de Monterrey for the facilities to carry out this research project.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
MAVMicro Air Vehicle
UAVUnmanned Aerial Vehicle
IMUInertial Measurement Unit

References

  1. Cai, G.; Dias, J.; Seneviratne, L. Survey of Small-Scale Unmanned Aerial Vehicles: Recent Advances and Future Development Trends. Unmanned Syst. 2014, 2, 175–199. [Google Scholar] [CrossRef]
  2. Mathworks. Parrot Minidrones Support from Simulink. Available online: https://la.mathworks.com/hardware-support/parrot-minidrones.html (accessed on 14 June 2019).
  3. Available online: https://github.com/Parrot-Developers/RollingSpiderEdu (accessed on 14 June 2019).
  4. Dydek, Z.T.; Annaswamy, M.A.; Lavretsky, E. Adaptive Control of Quadrotor UAVs: A Design Trade Study With Flight Evaluations. IEEE Trans. Control Syst. Technol. 2013, 4, 1400–1406. [Google Scholar] [CrossRef]
  5. Mohd Basri, M.A.; Husain, A.R.; Danapalasingam, K.A. Enhanced Backstepping Controller Design with Application to Autonomous Quadrotor Unmanned Aerial Vehicle. J. Intell. Robot. Syst. 2015, 79, 295–321. [Google Scholar] [CrossRef]
  6. Satici, A.C.; Poonawala, H.; Spong, M.W. Robust Optimal Control of Quadrotor UAVs. IEEE Access 2013, 1, 79–93. [Google Scholar] [CrossRef]
  7. Gautam, D.; Ha, C. Control of a quadrotor using a smart self-tuning fuzzy PID controller. Int. J. Adv. Robot. Syst. 2013, 10, 1–9. [Google Scholar] [CrossRef]
  8. Guo, Y.; Jiang, B.; Zhang, Y. A novel robuts attitude control for quadrotor aircraft subject to actuator faults and wind gusts. IEEE/CAA J. Autom. Sin. 2018, 1, 292–300. [Google Scholar] [CrossRef]
  9. Xiong, J.; Zhang, G. Global fast dynamical terminal sliding mode control for a quadrotor UAV. ISA Trans. 2017, 66, 233–240. [Google Scholar] [CrossRef]
  10. Xiong, J.; Zheng, E. Position and attitude tracking control for a quadrotor UAV. ISA Trans. 2014, 53, 725–731. [Google Scholar] [CrossRef]
  11. Zheng, E.; Xiong, J.; Luo, J. Second order sliding mode control for a quadrotor UAV. ISA Trans. 2014, 53, 1350–1356. [Google Scholar] [CrossRef]
  12. Besnard, L.; Shtessel, Y.; Landrum, B. Quadrotor vehicle control via sliding mode controller driven by sliding mode disturbance observer. J. Frankl. Inst. 2012, 349, 658–684. [Google Scholar] [CrossRef]
  13. Luque-Vega, L.; Castillo-Toledo, B.; Loukianov, A. Robust block second order sliding mode control for a quadrotor. J. Frankl. Inst. 2012, 349, 719–739. [Google Scholar] [CrossRef]
  14. Rida, M.; Cherki, B. A new robust control for minirotorcraft unmanned aerial vehicles. ISA Trans. 2014, 56, 86–101. [Google Scholar] [CrossRef]
  15. Ramirez-Rodriguez, H.; Parra-Vega, V.; Sanchez-Orta, A.; Garcia-Salazar, O. Robust Backstepping Control Based on Integral Sliding Modes for Tracking of Quadrotors. J. Intell. Robot. Syst. 2014, 73, 51–66. [Google Scholar] [CrossRef]
  16. Sumantri, B.; Uchiyama, N.; Sano, S. Generalized super-twisting sliding mode control with a nonlinear sliding surface for robust and energy-efficient controller of a quad-rotor helicopter. Proc. Inst. Mech. Eng. Part C J. Mech. Eng. Sci. 2017, 231, 2042–2053. [Google Scholar] [CrossRef]
  17. Villanueva, A.; Castillo-Toledo, B.; Bayro-Corrochano, E.; Luque-Vega, L.; González-Jiménez, L.E. Multi-mode flight sliding mode control system for a Quadrotor. In Proceedings of the 2015 International Conference on Unmanned Aircraft Systems (ICUAS), Denver, CO, USA, 9–12 June 2015. [Google Scholar]
  18. Derafa, L.; Benallegue, A.; Fridman, L. Super twisting control algorithm for the attitude tracking of a four rotors UAV. J. Frankl. Inst. 2012, 349, 685–689. [Google Scholar] [CrossRef]
  19. Rajappa, S.; Masone, C.; Bulthoff, H.H.; Stegagno, P. Adaptive Super Twisting Controller for a Quadrotor UAV. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016. [Google Scholar]
  20. Castañeda, H.; Gordillo, J.L. Spatial Modeling and Robust Flight Control Based on Adaptive Sliding Mode Approach for a Quadrotor MAV. Int. J. Intell. Robot. Syst. 2019, 93, 101–111. [Google Scholar] [CrossRef]
  21. Valavanis, K.P.; Vachtsevanos, G.V. Handbook of Unmanned Aerial Vehicles, 1st ed.; Springer: Dordrecht, The Netherlands, 2015. [Google Scholar]
  22. Haifeng, L. Multivariable Control of a Rolling Spider Drone. Master’s Thesis, University of Rhode Island, Kingston, RI, USA, 2017. Paper 1064. Available online: http://digitalcommons.uri.edu/theses/1064 (accessed on 14 June 2019).
Figure 1. Referential frames’ configuration.
Figure 1. Referential frames’ configuration.
Electronics 08 00793 g001
Figure 2. Regulation. Controllers comparison: adaptive sliding mode control (asmc), feedback linearization (fbl), and proportional integral derivative with gravity compensation control (PID).
Figure 2. Regulation. Controllers comparison: adaptive sliding mode control (asmc), feedback linearization (fbl), and proportional integral derivative with gravity compensation control (PID).
Electronics 08 00793 g002
Figure 3. Regulation. Control inputs of the controllers and adaptive gains of the asmc.
Figure 3. Regulation. Control inputs of the controllers and adaptive gains of the asmc.
Electronics 08 00793 g003
Figure 4. Hovering. Pose of the quadrotor MAV.
Figure 4. Hovering. Pose of the quadrotor MAV.
Electronics 08 00793 g004
Figure 5. Error, reference versus variable state.
Figure 5. Error, reference versus variable state.
Electronics 08 00793 g005
Figure 6. Hovering. Control inputs of the quadrotor MAV.
Figure 6. Hovering. Control inputs of the quadrotor MAV.
Electronics 08 00793 g006
Figure 7. Hovering. Adaptive control gains.
Figure 7. Hovering. Adaptive control gains.
Electronics 08 00793 g007
Figure 8. Hovering. Pose of the quadrotor MAV subject to external perturbations.
Figure 8. Hovering. Pose of the quadrotor MAV subject to external perturbations.
Electronics 08 00793 g008
Figure 9. Error. Reference versus variable state under perturbations.
Figure 9. Error. Reference versus variable state under perturbations.
Electronics 08 00793 g009
Figure 10. Hovering. Control inputs of the quadrotor MAV under external perturbations.
Figure 10. Hovering. Control inputs of the quadrotor MAV under external perturbations.
Electronics 08 00793 g010
Figure 11. Hovering. Adaptive control gains under external perturbations.
Figure 11. Hovering. Adaptive control gains under external perturbations.
Electronics 08 00793 g011
Table 1. Quadrotor MAV model parameters [22].
Table 1. Quadrotor MAV model parameters [22].
ParameterValueUnit
Weight m 0.068 kg
Arm length l 0.062 m
Gravity g 9.81 m/s 2
Inertia moment I x 6.86 × 10 5 kgm 2
Inertia moment I y 9.2 × 10 5 kgm 2
Inertia moment I z 1.366 × 10 4 kgm 2
Thrust coefficient K T 0.01 N/(rad 2 /s 2 )
Torque coefficient K Q 7.8263 × 10 4 Nm/(rad 2 /s 2 )

Share and Cite

MDPI and ACS Style

Castañeda, H.; Gordillo, J.L. Embedded Flight Control Based on Adaptive Sliding Mode Strategy for a Quadrotor Micro Air Vehicle. Electronics 2019, 8, 793. https://doi.org/10.3390/electronics8070793

AMA Style

Castañeda H, Gordillo JL. Embedded Flight Control Based on Adaptive Sliding Mode Strategy for a Quadrotor Micro Air Vehicle. Electronics. 2019; 8(7):793. https://doi.org/10.3390/electronics8070793

Chicago/Turabian Style

Castañeda, Herman, and J.L. Gordillo. 2019. "Embedded Flight Control Based on Adaptive Sliding Mode Strategy for a Quadrotor Micro Air Vehicle" Electronics 8, no. 7: 793. https://doi.org/10.3390/electronics8070793

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

Article Metrics

Back to TopTop