In this section, a new nonlinear attitude control law considering the maximum angular rate for fixed-wing UAVs is presented. To employ this unique approach, the sliding mode control (SMC) technology concept is utilized.
3.1. Sliding Mode Control
Let us first consider the baseline SMC. The first step in this technique is to reach the designed sliding surface. Then, the second step is the sliding stage, in which the sliding variable reaching the sliding surface goes to zero, which means that state errors converge to zero. For attitude control using the sliding control approach, the representative sliding surface
is chosen as
and a simple reaching law
is written as
where
is the vector part of quaternion error defined as
and
is the quaternion command, and the operator ⊗ refers to the quaternion multiplication. Furthermore,
a and
k are positive design parameters. Note that
is the signum function, defined as
To compute the control output from the sliding surface, the time derivative of sliding surface in Equation (
25) is expressed as
Inserting the angular acceleration,
, in Equation (5) into the above equation leads to
In terms of
from the above equation, the control input is expressed as
It is known that the discontinuity in the reaching law introduces the chattering problem. To release the burden of chattering, the alternative reaching law is given by
where
is a design parameter ranging from 0 to 1, and
is a matrix function defined as
and
is the
diagonal matrix in this case. By inserting the above reaching law into Equation (
30) to mitigate the chattering problem, the control input is rewritten as
Note that the final form of the control input is the attitude sliding mode control law for UAVs, overcoming the inherently introduced chattering problem.
Lemma 1. Once the sliding manifold is satisfied with properly chosen parameters, then the desired attitude maneuver can be achieved, i.e., the variable and will converge to zero. That is, Proof. Assume that the sliding surface in Equation (
25) is zero, and
, then it can be expressed as
Substituting
into Equation (4) and setting
introduces
Due to the norm constraint of the quaternion given by
, the right-hand side of the equation is rewritten as
The closed-form solution of the differential equation for a given time is
. As a sufficient time has elapsed, it can be seen that
converges to 1:
With
converging to one, this means that
converges to the zero vector due to the norm constraint of the quaternion after a sufficient time has elapsed. Consequently, the sliding surface
approaches zero, which means that
converges to zero independently. Furthermore,
also converges to zero according to Equation (
36). Thus, Lemma 1 is proven. □
3.2. Angular-Rate-Constrained Sliding Mode Control
In this subsection, a modified control law based on SMC is introduced by defining a sliding surface proposed in this work. Let us first assume that the fixed-wing UAV has limited maneuverability to prevent structural failure or cracks or to operate various missions safely. Without the loss of generality, the angular rate is directly linked with the magnitude of the centrifugal force according to the given airspeed of the UAV. Thus, it is natural that the maneuverability constraint can be converted to the angular rate limitation of the UAV. That is,
where
is the angular rate of UAV for each body axis, and
is the allowable maximum angular speed of UAV to meet the maneuverability constraints. Now, to satisfy the angular rate constraint, the new sliding surface suggested in this work is written as
where the saturation vector function is defined as
and the saturation scalar function can be given by
Furthermore,
L is the limiting parameter, obtained by dividing the maximum angular rate
by the design parameter
a. The function
compares two components and selects a smaller value so that the saturation function selects a smaller value via the comparison between the component of the quaternion absolute error
and the limiter
L. From the inherent representation of the new sliding surface, there are two equilibrium points, setting
. That is,
and
. The first equilibrium point is related to the attitude control purpose, and the second equilibrium point is deeply related to the angular rate limitation by forcing the UAV not to exceed the given limitation. Let us consider for the second equilibrium point that the quaternion absolute error
is larger than the limiter
L. Then,
will be
L according to Equation (
43). Since
, the saturation function can be the allowable maximum angular rate, that is,
. Thus, the second equilibrium point is related with the allowable maximum angular rate such that
.
For the angular rate constrained control law design, the time derivative of the sliding surface in Equation (
41) is given by
where
D is the diagonal matrix with the element
defined as
Note that
is differentiation of the scalar
function, and it becomes 0 or 1 according to the algebraic comparison of
L and
. Thus, by substituting Equations (5) and (
31) into (
45), the constrained sliding mode control (CSMC) input can be expressed as
It is noted that the control input induced from the suggested sliding surface is the angular-rate constrained attitude control law for fixed-wing UAVs based on the sliding mode control. As seen in Equation (
48), the control law is dedicated to the magnitude of attitude errors. If the attitude error
for each axis is larger than the reference value of
L, the term of
is eliminated to improve the maneuverability. Otherwise, the term is activated, and the control law in Equation (
48) supports both
and
to approach zero. In other words, it can be interpreted that the control law plays two important roles, since there are two equilibrium points. The first equilibrium point of the sliding surface,
, is related to the case of
. In this case, the control law allows us to reach the allowable maximum angular speed of the UAV in order to improve the maneuverability. This strategy is made possible by approaching the first equilibrium point. Next, for the second equilibrium point,
, connected with the case of
, the control input causes the attitude error and angular velocity to converge to zero by controlling the sliding surface to reach the second equilibrium point. This property can be regarded as the unique characteristic of the constrained sliding mode control approach suggested in this paper.
3.3. Stability Analysis
Before verifying the stability of the control law, let us first inspect the overall process of the control law to ensure that the sliding surface works appropriately to achieve the control objective. As mentioned previously, there are two equilibrium points in the sliding surface. This means that the structure of the proposed control law can vary depending on the amount of attitude errors and the allowable maximum angular rate.
Suppose that a large attitude command is generated for the UAV in a steady state so that a large amount of attitude errors are applied to CSMC. It is matched with the case of . That is, the first step to achieve the goal is to adjust the angular rate to converge to the allowable maximum angular rate . This can done by sliding at the first equilibrium point. It is noted that approaching the first equilibrium point is deeply related with the maneuverability, since the angular rate increases quickly to the allowable maximum angular rate of the UAV. Consequently, due to the consistent angular rate applied to the UAV at the first equilibrium point, the magnitude of the attitude errors gradually decreases below the given reference L. This is the reason the control law can naturally move on to the second step, . As seen previously, the second step is to approach the second equilibrium point, which is a step for controlling both the quaternion error and the angular rate , causing them to converge to zero.
Let us carefully investigate the sliding surface in detail. According to the attitude error, the sliding surface defined in Equation (
41) can be divided by two forms given by
Equation (
49) is the sliding surface in the case of large attitude errors
enough to be larger than
L, so that the point satisfying
is the equilibrium point. Furthermore, it is obvious that the variable of
in Equation (47) becomes 0. Let us substitute the control law in Equation (
48) into the governing equations of motion of UAVs in Equation (5). Then, it is found that the relationship between
and
s is given by
From the above equation, it can be seen that the angular acceleration
is opposite to the sign of the sliding surface
in Equation (
49).
Assuming that the UAV is initially in a steady state, the angular rate of the UAV is zero. It holds
from Equation (
49) so that the sign of
is identical with the quaternion error,
. This property is still valid, whereas
is approaching to zero. In other words, It is valid before the angular rate of UAV,
, is identical with the allowable maximum angular speed,
. From Equation (
51), it is obvious due to the fact that the signs of the quaternion error and the angular acceleration are opposite. That is, the angular rate increases while the quaternion error decreases. Consequently,
becomes
so that the sliding surface goes to zero,
. Then the angular acceleration in Equation (
51) becomes zero. Finally, it is noted that the angular rate reaching the allowable maximum angular rate remains unchanged, whereas the quaternion error decreases continuously to be smaller than
L. Once the quaternion error becomes small after a sufficient time has elapsed, then the variable
is switched to one. This is when the sliding surface of Equation (
49) turns into Equation (50). It can be also seen that the sliding surface is the same as that of the conventional SMC in Equation (
25). Therefore, the point where
and
become zero is the equilibrium point.
Now, let us investigate the stability of the closed-loop attitude control system utilizing CSMC to ensure that the motion of the sliding surfaces work correctly. Stability analysis is required for each sliding surface. For the stability of the closed-loop system, the representative Lyapunov candidate by the first sliding surface in Equation (
49), is defined as
Inserting Equation (
45) into the time derivative of the Lyapunov candidate leads to
Then, let us substitute Equation (5) into the above equation, and replace the control input with Equation (
48). Then, the time derivative of the Lyapunov candidate is rewritten as
Note that D is zero in this case.
Moreover, the second term of the right-hand side of the above equation is always positive. That is,
Thus, the time derivative of the Lyapunov candidate is given by
where
denotes the two-norm of
. Since the time derivative of the Lyapunov candidate is always negative, the closed-loop system is asymptotically stable. This means that for a given initial condition of
and
, the sliding surface,
, in Equation (
49) will converge to the first equilibrium point,
.
Once again, for the closed-loop system stability by the second equilibrium point, the identical Lyapunov candidate by the sliding surface in Equation (50) is also defined as
By proceeding identically with the previous case, the time derivative of the Lyapunov candidate is also written as
Note that the variable
D does not disappear in this case. However, applying the control input in Equation (
48), the remaining procedure is identical with that of the previous case. Since the closed-loop system is asymptotically stable for the given condition of
, the sliding surface,
, in Equation (50) will converge to the second equilibrium point, that is,
, which is proven by Lemma 1.