Next Article in Journal
Efficient Fire Detection with E-EFNet: A Lightweight Deep Learning-Based Approach for Edge Devices
Next Article in Special Issue
A Model-Free Online Learning Control for Attitude Tracking of Quadrotors
Previous Article in Journal
Wear Characteristics of (Al/B4C and Al/TiC) Nanocomposites Synthesized via Powder Metallurgy Method
Previous Article in Special Issue
Dynamics and Control of Satellite Formations Invariant under the Zonal Harmonic Perturbation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Development of Adaptive Control System for Aerial Vehicles

Faculty of Electrical and Environmental Engineering, Institute of Industrial Electronics and Electrical Engineering, Riga Technical University, 12/1 Azenes Street, LV-1048 Riga, Latvia
*
Author to whom correspondence should be addressed.
Appl. Sci. 2023, 13(23), 12940; https://doi.org/10.3390/app132312940
Submission received: 26 October 2023 / Revised: 28 November 2023 / Accepted: 29 November 2023 / Published: 4 December 2023
(This article belongs to the Special Issue Autonomous Formation Systems: Guidance, Dynamics and Control)

Abstract

:
This article represents and compares two control systems for a vertical takeoff and landing (VTOL) unmanned aerial vehicle (UAV): a sliding proportional–integral–derivative (PID) controller and an adaptive L1 controller. The goal is to design a high-performing and stable control system for a specific VTOL drone. The mathematical model of the unique VTOL drone is presented as a control object. The sliding PID and adaptive L1 controllers are then developed and simulated, and their performance is compared. Simulation results demonstrate that both control systems achieve stable and accurate flight of the VTOL drone, but the adaptive L1 controller outperforms the sliding PID controller in terms of robustness and adaptation to changing conditions. This research contributes to ongoing work on adaptive control systems for VTOL UAVs and highlights the potential benefits of using L1 adaptive control for this application.

1. Introduction

The importance of unmanned aerial vehicles (UAVs) for personal and professional use has increased rapidly over the last 2 years. UAV systems are used for a variety of applications, including aerial photography, surveying, and reconnaissance. There are many types and classes of UAVs; however, the most usable ones are the vertical takeoff and landing (VTOL) aircrafts, which combine efficient plane flight and multicopter hover ability. Control system design for this drone type is very challenging due to the complex and nonlinear airframe dynamics. Existing control methods, such as PID or LQ controllers, have significant limitations including poor performance in the presence of disturbances and changing environmental conditions. The importance of this research is determined by the potential widening of the range of applications based on a high-performing and stable control system. During this research, the kinematics of the specific VTOL drone “FIXAR-007” are used for the design and simulation of the linear and adaptive control systems. This adaptive system design is the main focus of this paper, which presents a comparison of these systems. The motivation for the research was the drone’s simplistic design, which can be utilized with a universal control system to be used by a VTOL drone during all flight phases. The drone mentioned above is designed and manufactured by the FIXAR-Aero company [1], which owns the patent for autopilot, ground control stations and the aerodynamic scheme. Therefore, the paper considers the author’s personal ideas and assumptions about the control system design, without having access to the intellectual property of the company.

2. Materials and Methods

2.1. Object of Research

The object of the study is a unique drone known as FIXAR-007. This belongs to the VTOL class, although it has fundamental differences from other drones under this classification. As it can be seen in Figure 1, FIXAR-007 combines a multicopter scheme with an airplane scheme, using 4 motors, mounted at the fixed angles ϕ 1 ϕ 4 to the symmetry axis at distances r 1 r 4 . This ensures that the motors generate both x axis thrust and lift. The ratio of the lift force of the wings to that of the motors varies with speed and can be as high as 65% at cruising mode according to the model simulation. For hover mode, the aircraft changes its orientation, starting to bring the propellers to a horizontal position. In this mode, the aerodynamic surfaces operate at extreme angles of attack, creating significant drag that requires compensation from the control system.
The system described above eliminates all actuators except the motors. This, according to the manufacturer, increases the reliability of the system because of its simplicity. The manufacturer also indicates that using the motors in conjunction with the wing increases maneuverability and payload capacity. This is supported by the fact that the manufacturer of FIXAR-007 declares a flight speed of up to 20 m/s in winds of 12–15 m/s and a payload of up to 2 kg (28% of maximum takeoff weight) with a climb rate of 4 m/s, for a maximum takeoff weight of 7 kg and wingspan of 1.6 m. The system’s parameters are described in Table 1. The values in this table, as well as the diagram shown in Figure 1, are approximate and are based on the author’s assumptions about the components that could be applied to the described system.
The object has a very wide range of nonlinear disturbances, mostly caused by aerodynamic forces. In [2], G. Flores provides detailed analysis of the forces disturbing the VTOL drone of similar characteristics. The paper indicates that aerodynamic forces increase significantly at extreme angles of attack. In the system studied by G. Flores, this occurs during the transition processes between flight and hovering. In the case of FIXAR-007, operation at extreme angles of attack is expected during the entire hover due to the specific design.
Thus, the object of study is a system with a kinematically simple basis and a nonlinear disturbance varying over a wide range as a function of several variables. The objective of the design is to develop a control system that will control the object over the entire range of disturbances.
For accurate control of the drone, a control system with precise and controllable characteristics is required. It is necessary to guarantee the consistency and dependability of flight results, which in turn enable the work to be completed with the highest level of accuracy and to ensure the safety of those nearby. It should also be noted that the VTOL FIXAR-007 described in the paper has special properties, including the absence of a distinct mechanical separation between the fast “airplane” and “position-hold” flight modes. Autopilot systems are typically embedded software for microcontrollers. Examples include the Ardupilot [3] and the PX4 [4], which are the most popular software in the hobbyist and civilian professional environments. Autopilots interact with the user via a control station, which can be either an onboard computer performing complicated functions like SLAM or a ground computer performing as a user interface.

2.2. Technical Novelty and State of the Art in VTOL UAV Control Systems

The current state of the art in drone control systems, especially for vertical take-off and landing (VTOL) unmanned aerial vehicles (UAVs), is rapidly being regulated. VTOL aircraft pose additional challenges to control systems because they are capable of operating in a wide range of environments and require switching between position hold and high-speed flight modes. Traditional drone control systems are often split into these modes first, with one set optimized for airplane flight and the other for fixed-wing flight. However, this separation can increase complexity, cost and transition time.
For example, the work of G. Flores, already mentioned above, also separates hovering and forward flight. It also uses a nonlinear control strategy, while hovering using a feedback-linearizable input for altitude control and a hierarchical control, as well as a backstepping control law, for the vehicle in forward flight mode.
Liu in [5] also compare the use of various controllers of various types for tilted-rotor drones. In his work, he compares the use of PID controllers, Eigenvalue assignment, optimum control, robust control, and model predictive control (MPC). Ultimately, for its experimental TRUAV platform, Liu develops a system using a proportional derivative–double derivative (PD-dD) controller in combination with an MPC controller. At the same time, Liu notes significant problems in modeling the behavior of tilting rotors. In the case of working with FIXAR, there is no such problem due to the absence of this node. This simplifies the model and provides higher system reliability.
The research of S. Saeed [6] provides classification and models of the VTOL drones, as well as features of their modeling. The author compares the use of different control systems for hybrid drones, focusing on linear quadratic regulator (LQR) controller, backstepping and gain-scheduling methods. Saeed also mentions the nonlinear dynamic inversion (NDI) method as a solution that can be generalized for the MIMO solution.
The research presented in this paper introduces a new VTOL UAV control system specifically suited to the FIXAR 007 drone. This drone is a hybrid between a quadcopter and an airplane. It both uses motor controls and also deals with greater aerodynamic disturbances. The innovation lies in the development of a unified controller capable of successfully controlling both aircraft and aircraft system modes. This unified system aims to provide a simple control architecture needed to control and improve UAV operational efficiency and response time.
The FIXAR 007 is a unique concept in VTOL UAVs, and prior to this study there was no known work on this particular design. The drone’s ability to withstand aerodynamic disturbances while maintaining precise control demonstrates the effectiveness of the newly developed control system. FIXAR 007 can reliably operate in a wide range of situations thanks to its adaptive control navigation system. It can transition from stable guidance operations to cooperative maneuvering in aircraft mode. This shows how adaptive systems can be used to make UAVs more robust and flexible.
In line with the European Innovation Strategy, projects like COMP4DRONES, coordinated by Indra, are essential. COMP4DRONES is an ECSEL JU project that aims to create the basic technology for safe and autonomous drones. The project covers a wide spectrum of considerations, from electronic components to application areas such as transportation and precision agriculture. This shows the importance of compositional architecture, customizable guarantees and solid communication in the development of the drone industry [7].
The holistic approach of COMP4DRONES and its alignment with EASA regulations and SESAR-JU studies is crucial. This represents a trend towards a coherent, interoperable and compositional drone architecture, which is essential for the future of civil drone services. Through these initiatives, we can expect to see an increase in innovative drone functionality, driving the continued growth of various industries, logistics and delivery. Thus, the work presented here not only contributes to the theoretical understanding of VTOL UAV control, but also aligns with broader European innovation goals, setting a precedent for further research and development in this area.

3. Model and Research

3.1. Coordinates System and Kinematics

The UAV kinematics model is designed to perform the simulation. The number of independent auxiliary relationships is equal to the difference between the number of coordinates in the set and six; all coordinate systems are Cartesian and right-handed NED coordinate systems. As a result, the primary vector of states looks like this:
P = X e O b = X Y Z φ θ ψ
where X e = X Y Z is the system coordinate in the earth frame, which is a vector of dimension 3 × 1, with dimension in meters. O b = φ θ ψ , representing the orientation of the body frame relative to the earth frame, is described using the Euler angles 3 × 1 in radians. The kinematic model from [8] is used with some assumptions as a basis for the model. It is important to note that, in his work, the author describes the kinematics and orientation control of the quadcopter. To describe the navigation, the position of the aircraft is added to the model. As a result, the complete kinematic model is summarized in (2) and expanded in (3).
F b ¯ = m ( V b ¯ ˙ + ω ¯ × V b ¯ ) T ¯ = I ω ¯ ˙ + ω ¯ × ( I ω ¯ )
where V b ¯ is a linear velocity vector, ω ¯ is angular rate vector, m is the mass of the aircraft and F denotes the force vector. There, I is an aircraft inertia matrix. When considering the vector V b ¯ defined for all components in the direction x, y and z and ω ¯ for roll φ, pitch θ and yaw ψ. The following system (3) describes the flight dynamics of aircraft.
V ˙ b x V ˙ b y V ˙ b z ω ˙ x ω ˙ y ω ˙ z = 1 m F b x + ( ω z V b y ω y V b z ) 1 m F b y + ( ω x V b z ω z V b x ) 1 m F b z + ( ω y V b x ω x V b y ) 1 I x T x + ( I z I y I x ) ω z ω y 1 I y T y + ( I x I z I y ) ω x ω z 1 I z T z + ( I y I x I z ) ω x ω y
The system (3) presents UAV kinematics in general form. The body forces and the torques are generated via three different sources, which are standard for all flying objects: gravity force, motor forces and aerodynamics. The last two sources are typical for the control of an aircraft, but the system under study uses only motors for this aim. The following Equation (4) presents the described above forces and torques in the system.
  F b ¯ = F m b ¯ + F a ¯ + G b ¯ T ¯ = T m b ¯ + T a ¯ ,
where F b ¯ is the sum of the forces acting on the object in the body frame, F m b ¯ represents motor force, F a ¯ indicates aerodynamic forces, and G b ¯ is the projection of gravity vector G e ¯ to body frame. T ¯ is the total torque from all the sources, coming from the motor torques T m b ¯ and aerodynamic T a ¯ . Aerodynamic analysis was performed using the XFLR5 aerodynamics simulation software. It was chosen because of its speed, flexibility and built-in stability analysis functionality. As shown in [9], XFLR5 produces results with a high degree of accuracy. In combination with everything mentioned above, this is a significant advantage of this software. As shown in [10], this software exports aerodynamic coefficients, which allow the use of aerodynamics as a form of nonlinear disturbance in the model.

3.2. Motor Forces and Aerodynamics

The motors in this aircraft are BLDC drives consisting of a three-phase synchronous electric machine controlled using a three-phase electronic speed controller (ESC). Such a propulsion group is typical for modern drones, as shown in [11]. The peculiarities of this system organization are high reliability, efficiency, and speed of the system operation, as well as small thermal and acoustic signatures, which are separately noted in [12]. The motor load is the propeller, the movement of which generates thrust in the motor shaft direction and gyroscopic torque, used to control the yaw in the system. Thus, for simplicity, the propulsion unit can be described using an aperiodic element. The use of 4 motors allows to create force on Ox and Oz axes, and torque on Ox, Oy and Oz axes. Due to the descriptions and assumptions above, motor forces and torques in body frame calculations are presented in the Simulink subsystem, presented in Figure 2.
There, Ca is axis command input in [−1, 1] range. The motor mixer matrix Mmm is multiplied with Ca resulting motor command vector Cm. The motor transfer function is applied and result is multiplied with nominal battery voltage VBAT = 23V resulting simulated motor speed ω in rad/s. The following operations result calculation of every motor thrust Fm, motor force in body axis Fmb and motor torque in body axis Tm, which are the block outputs.
    F a = C S ρ V s 2 2 T a = m a t S b ρ V s 2 2
The aerodynamic forces and torques are calculated from system (5), where S is wing area, Vs is airspeed, ρ is air density, and C and m a t are aerodynamic nonlinear coefficients depending on wing form and angles of attack α and slip β.

3.3. Low-Level Stabilisation Level

In the system under the study, control is provided by vector C = [CT CR CP CY]T. CR and CP are the axis angle targets used for roll and pitch, with CY representing yaw rate command in the same coordinate system and CT standing in for mean motor thrust. Consider the pitch angle stabilization system (Figure 3). This scheme is typical for the roll and pitch channels.
To control the research object at the lower level, an attitude controller for multicopter systems is introduced into the system. The principles of such a system are well developed and presented in various studies, e.g., [13,14]. In this paper, a dual-loop PID-based controller will be used, the general principle of which is shown in Figure 3. As can be seen, the pitch angle control system is a two-level control system with one nested loop. This is a typical multirotor stabilization system, described in detail in [15]. The inner loop controls the object angular velocity ω, which is represented here by the transfer function W(s), generally defined by the system kinematics. The system W(s) is controlled by the controller Wω(s) using the PID controller. The outer loop provides angle stabilization and is described by Wϑ(s) using the P controller. Similar loops are used for the roll and heading channels. A detailed analysis of the low-level stabilization system is not the purpose of the study, as this subsystem is an input for a high-level navigation controller, the synthesis of which is the focus of this paper.

3.4. Sliding PID for Navigation System

The UAV control systems are designed to execute navigation tasks. The navigation controllers are typically used as the outer loops for the attitude control system presented above. The structure of the high-level controllers may vary depending on airframe and actuator construction. The specifics of the modelling and control systems used are presented in [16]. Taking into account what is presented in the mentioned book, and operating on the basis of the study of approaches to design, the following systems are compiled. The typical (used in the most used civil autopilots) solution is the usage of the PID controller for a velocity loop and P or PI controller for an outer loop [17]. The other way of handling linear controllers of the aircraft is to provide the LQ controller for the trajectory that is presented in [18]. Although the research provided good results, the linear–quadratic system requires feedback linearization, for example [19]. This significantly complicates the problem and does not create a universal solution due to the fact that, in the case of VTOL drones such as FIXAR, the task is complicated by the wide range of disturbing influences. As a result, to simplify the system implementation, drones of this type use PID controllers to operate in “aircraft” and take-off and landing “copter” mode. The switching takes place either in sliding mode or under the control of an autopilot state machine. This section will discuss the application of such a system for the object under study.
During the “copter” mode, the aircraft holds its position in 3-dimensional space, with disturbance from aerodynamic forces. At the same time, the system is required to work with the maximum wind speed 2–3 times higher than the aircraft ground speed. A typical solution for such a system is a multicopter position control system [20] in which the aircraft throttle channel controls the altitude, and the inclination of the entire aircraft achieves horizontal movement. While the PID controller controls the internal velocity loops, the P controller is used for position control, the coefficient of which determines the final dynamics of the system. For tuning, we simplify the system (3) with cascaded loops to the form presented in (6) using the approximation detailed in [21].
W v x g = V x g C P = λ x g s ( 8 T m 2 s 3 + 4 T m s 2 + s + K ϑ ) W v y g = V y g C R = λ y g s ( 8 T m 2 s 3 + 4 T m s 2 + s + K φ ) W z g v s = C T V z g = 4 k m s
Parameter calculation resulted in the third-order oscillating link can being decomposed into an aperiodic link and a second-order oscillating link. Given this assumption, a PI controller tuned to a symmetric optimum is synthesized for all axes.
Flight in the “airplane” mode is performed at a speed 1.5–2 times higher than maximum possible wind speed. In this state, aerodynamic forces create a significant part of the lifting force of the aircraft and can be used to control the object. Required in order to move efficiently, stabilization is provided by the airspeed of the aircraft. A typical aircraft navigation system, as applied to the object under study, is presented in Figure 4. In this system, the motors are tilted to the horizon and the longitudinal motion is distributed through the throttle/yaw channels and controlled using aerodynamic forces. Then, given the wide requirements on the range of perturbing influences (the ratio of the maximum wind to the aircraft cruise speed is 0.6), we apply the Ziegler–Nichols [22,23] frequency method. The results of the tuning and control systems schemes are given in Table 2 below.
At the Figure 4a, Astgt is the airspeed command in m/s, defined by user in the simulation environment, As is airspeed data from sensor, Azcmd is desired heading in degrees, yaw variable defines current drone heading. Altitude contour is using Altcmd variable defines desired altitude, Z input is current altitude and Vz is current vertical speed of the simulated UAV. At the Figure 4b, Hdgcmd input is acting as desired heading command, yaw is current heading, Poscmd input is target position, Xe is current position and Vx, Vy and Vz are current drone velocities. Cmd variable is acting as block output for both systems.
Figure 4 shows the PID-controlled systems for high-speed flight (Figure 4a) position hold (Figure 4b). It has to be noted that this system requires an additional switch block to perform the mission, or it cannot be used for the navigation. Switching between these controllers is realized using the state machine described in the next section and result transition process for acceleration or deceleration. As a result, a coarse linear control system is obtained, capable of controlling the aircraft with the maximum allowed deviations. However, the system has a very small velocity range, within which the object is stable due to the limitations applied. Finally, changing the cruise speed would require a complete reconfiguration of the system, creating problems for operation with a real object.

3.5. Adaptive Control Navigation System

As was mentioned before, the FIXAR-007 aircraft undergoes no mechanical transition between the “position hold” and “airplane flight” controls. Theoretically, this means that the UAV under study can be fully controlled at any steady state required for the operation. The system designed above is unable to achieve that due to the sliding transition at the low-airspeed state. This section will investigate the application of adaptive controllers to achieve the goal of a universal control system capable of controlling an aircraft in any steady state required.
J. Kim in his paper [24] presents the most comprehensive study of the techniques used to control a multirotor system. In particular, he notes the positive aspects of the feedback linearization method also presented in [25]. Nevertheless, the most promising method for VTOL with a wide range of nonlinear perturbations is model reference adaptive control. Its variation, known as L1 adaptive controller, was well discussed in [26] and was the basis for this paper.
Figure 5 illustrates the adaptive L1 controller’s block diagram. The disturbance can represent any type of non-linear disturbance, such as changes in the plant caused by changes in parameter values or actuator failures. The insertion of the low-pass filter C(s) performs two critical functions. First and foremost, it restricts the bandwidth of the control signal before it is sent to the plant. This prevents the commanding of high-bandwidth oscillating control signals, which are commonly used by fast-adapting MRAC controllers. Second, the reference model M(s) only provides the high-frequency portion of the input signal [27]. This signal generally corresponds to the portion of the disturbance d(s) that cannot be canceled given the confined actuator bandwidth. As it is supplied into the reference model M(s) along with the reference signal, this implies that the output of M(s) is the achievable system output, a realistic aim that the system should be able to fulfill given its bandwidth restrictions [28].
The resulting control system block diagram is presented in Figure 6. The system inputs are the target position and heading (Xtgt, Vtgt, and Yawtgt). They are used to calculate the position and heading error and for the dynamic limiter block, which is used to limit target velocity to maintain cruise airspeed for efficient flight. Velocity control is provided using L1 adaptive controllers described below. L1 controller and dynamic limits subsystems are presented in Figure 7.
There, Xtgt is desired position, Xe is current position, Ebx, Eby and Ebz are current position error in body axis calculated from position error perr. Vx, Vy and Vz are the axis velocities and the targets are limited, using dynamic limits for x and y axis. Adaptive L1 controller is presented for every axis and shown at the Figure 7a. Dynamic limits block is described at the Figure 7b and is using distance to the point, current airspeed As and current ground speed Vc as inputs. The controller outputs are combined to the system output C = [CT CR CP CY] T, which is transferred to the low-level stabilization system.
At the Figure 7a the L1 controller model in Simulink is presented. The Tgt input is used as controller command input, same as r(t) at the Figure 5. Val input is used for current system state, named as x(t) at the Figure 5. Command output to the object u(t) is presented at the Out block. Figure 7b presents the dynamic limits block, which is used to set cruise speed Astgt from simulation environment. The airspeed integral controller calculates the X speed which is applied according to the drone ground speed. This results the drone flying at the cruise speed, controlled using both airspeed and ground speeds. Similar idea is presented for the y axis, limiting the target velocities during the high speed flight.
The L1 adaptive controller is presented to control the drone velocity. The idea is to consider all nonlinear forces (gravity and aerodynamics) as disturbing factors. Then, the control action remains linear, and the task is reduced to the implementation of a nonlinear system with a stability margin sufficient to operate over the entire range of disturbances. In this case, the difference between position holding and high-speed flight disappears in the system, and the system becomes completely controllable. Figure 8 represents its test and tuning results. Figure 8a depicts the time transient for the z axis with various coefficients m and c.
At the Figure 8 Vx is the drone velocity and Ax is the drone acceleration. The simulation results for different model dynamics coefficient m and filter coefficient c are presented in time (Figure 7a) and phase trajectory (Figure 7b) domains. As can be observed, the coefficient m is in charge of the system’s dynamics, while the coefficient c acts as a damping coefficient and influences its stability. The phase trajectory Figure 8b for the provided system is the “stable focus” type, allowing us to discuss the similarities of transients to linear systems. As a result of the comparison, the system with coefficients m = 10 and c = 7.5 produces the best outcomes. The final tuning is performed using parametric optimization. The optimization criterion is (7):
Q = K V 0 T ( V c t V c ) d t + K ψ 0 T ( ψ t ψ ) d t
where Q is the quality criteria, T is the simulation time, V c t is velocity target and ψ t is heading target. The resulting variables are: m t = 5.55 ,   c t = 18.15 ,   m p = 2.37 ,   c t = 47.84 ,   m r = 1.75 ,   c r = 24.45 ,   m y = 2.1515 ,   c y = 188.28 . The simulation with final settings will be shown below. As a result, an adaptive system for control of the aircraft is obtained and optimized. The resultant mechanism is universal and can be used for both fast flight and position holding.

4. Results

This part will consider a comparison of the systems given in Section 3. For comparison purposes, the simplest line-holding system and state machine required are added to the provided systems. The mission is a set of points, the lines between which the drone must follow.
To accomplish the mission, the drone must perform the following actions: launching from the initial position X 0 , flight through the series of points at the cruise speed, deceleration and landing at the specified position. During takeoff the drone must fly to point M 0 (transition point) and hover there for M p 0 seconds. Then, it is necessary to start acceleration to point 1, holding the line M 0  −  M 1 . The line is considered completed if the distance to the end point is less than M r . After that, the drone switches to moving to the next point. The simulation uses a mission of 7 points, and the final points are the landing. At point M 6 (deceleration point), the drone switches to holding position to ensure a vertical landing and then begins to descend to point M 7 . The mission is considered fully completed when the system reaches the landing point. For the mission flight, the state machine block is established. Its structure can be observed in Figure 9. It has point counter, point selector and heading target calculation subsystems.
At the states machine scheme (Figure 9) the input is distance to point d2p, plane position and seven points described below. The output is point coordinates, heading command and point change events. The landing event is used to stop the simulation.
To compare the performance of the developed systems, we choose a high-load operation mode. The simulation is performed for cargo delivery over a mountain as one of the most stressful yet most suitable route types for the VTOL drone. The UAV should take off, climb to the 500 m altitude, fly over a “mountain” at this height, descend with the turning maneuver, and then decelerate over the target at a height of 100 m and land at the specified point.
The evaluation criteria are the maximum horizontal and vertical deviations from the mission and the flight time. The performance metrics will include response time to control inputs, which should not exceed 5 s, and stability, characterized by less than 5% deviation from set altitude and trajectory during windy conditions. These parameters are crucial for real-world applications such as emergency medical deliveries, where rapid and precise navigation is paramount. The mission parameters, as well as the simulation parameters, are summarized in Table 3.
It should be noted that the maximum climb and descent speeds for the PID-based system are limited to [4, −3] m/s. This results in the mission having such a large climb and descent distance for a correct comparison, and the complexity of the system does not allow switching to the hold position during the flight. While the L1-based system has much higher speeds [6, −5] m/s and also allows switching to the hold position “on the fly”. Meaning, for the L1-based system, the same transportation task can be accomplished with a much smaller mission, which will reduce flight costs in practice.
Figure 10 presents the results of the mission flight simulation. There are 2 views shown: Figure 10a presents a 3D view, presenting both horizontal and vertical behavior. Figure 10b presents a 2D view, where the horizontal deviation can be observed. As can be seen, the linear PID-controlled system has significantly higher derivations from the mission route than the adaptive one. The highest horizontal derivations can be observed near mission point 3, where drone changes its heading and altitude with the wind in its back. Also, there is vertical steady-state error for the PID-based system near point 4, which occurred due to the long descent at high speed. It is obvious that the characteristics of the linear system are barely sufficient to accomplish the mission under the given conditions. Transient analysis of takeoff and landing transients is also necessary to compare the systems. For this purpose, the graphs of these transients are shown below in Figure 11.
The Figure 11 presents drone flight trajectory in 3D (x, y, z axis) at the Figure 10a and 2D (x, y axis) at the Figure 10b.
Comparing the response of the systems to the disturbance Vx, it can be noted that the transient process completes faster with the L1 controller: the setting time in this case is t s p = 4.1   s , whereas for a system with a PID controller t s p = 11.2   s , with significantly lower overshoot at vertical speeds: 54% for PID and 2% for L1. It has to be noted that adaptive L1 launch has worse characteristics—overshoot and setting time are higher. This means that the drone requires more distance for transition. Overall control system characteristics are presented in Table 4.
Based on data of Table 4, it can be determined that the adaptive control system, based on L1 controllers, significantly outperforms the sliding PID control system: the max horizontal error e h for L1 controller is almost 3.5 times lower, which might be very important in flight-area limited mountain-type missions. This deviation can be observed in Figure 10b at point 3 and is compensated by t s m seconds, which is 3.25 times lower. Taking into account lower vertical speeds, the high vertical error e v on descent and unacceptable stability error rate σ , it can be stated that a sliding PID control system has insufficient performance in terms of influencing high-speed flight compared to the adaptive system.
Comparing position holding, acceleration and deceleration, it can be observed that, although acceleration takes longer in the adaptive system, the overall quality of position holding is much better for the L1-based controller. This is confirmed by the setting time t s p being almost 2.5 times lower, and by the lower deviation of the velocity e p . It has to be noted that the vertical velocity controller has significantly lower overshoot in the L1-based system, which results in insignificantly more stable and faster transition, reducing final transition time t s d by 0.9 s.
All data were derived from ten simulation runs under varying wind conditions, with statistical significance evaluated at p < 0.05. This accuracy is acceptable for desktop calculations. To attain higher accuracy, an HPC system can be alpplied.

5. Discussion

The Section 3 and Section 4 presented and compared 2 different control systems for the system under study. The flight trajectories, presented at the Figure 10 show that PID-controlled system significantly deviates from the desired mission path. At the same time, the adaptive control system takes less time and follows a more ideal trajectory. Under heavy wind stress, the adaptive system provides relatively quick movement and good repeatability. We can also see that the L1-based adaptive control system has a quicker climb and descent and better braking than the sliding PID-controlled system. The latter occurs because the system utilizes the same controller to handle the whole route and hence does not lose time gaining stability like the sliding mode system does.
The presented system demonstrates that the adaptive system has superior features, such as rate of ascent, position hold precision, and speed maneuvering, in addition to being controllable over the whole spectrum of speeds and under the influence of disrupting effects. The actual traffic control system 1 [29,30,31], as a traffic control tool in cities, allows researchers to easily integrate VTOL. While the L1 controllers are involved more in terms of organization and tuning, the overall control system is easier to use since it does not require specific switch logic. Furthermore, the adaptive system outperforms the linear speed “airplane” controller in terms of speed control, which might be advantageous for maneuvering.
It should be also noted that the built adaptive system is less complex. Despite the enormous practical complexity of developing a separate controller, the linear system in sliding mode needs twice as many controllers, as well as the logic for switching between them. This places extra constraints on the flight job. At the same time, an adaptive system does not require this, and gives the user with greater freedom along with superior qualities.

6. Conclusions

We conducted a study of several techniques to design a control system for VTOL UAV aircraft in this work. We demonstrated that there are numerous strategies for their combination methods, a method comparison was performed, and a variant of model reference adaptive control (MRAC), known as the L1 adaptive controller, was selected as the most promising approach. This controller had the best performance and allowed the separation of performance and robustness by employing a low-pass filter to assure the signal’s limited bandwidth and to limit the adaptation rate. As a result, the L1 controller was much more resilient than ordinary linear systems, making it an appropriate choice for research. Two control systems performing the same navigational job were compared.
During the comparison between sliding PID and adaptive L1 controllers, it was found that the designed adaptive system significantly outperformed the linear system in terms of stability over the entire range of mass and wind speeds. The turning radius, and therefore the accuracy and flight time, were also significantly better for the adaptive system. Also, the adaptive system was capable of operating over large ranges of angular and vertical speeds.

Author Contributions

All authors have contributed to the study and writing of this research. The authors confirm contribution to the paper as follows: study conception and design: V.B. and N.K.; data collection: V.B. experiments: A.P. and V.B.; analysis and interpretation of results: V.B. and M.B.; draft manuscript preparation: V.B. and A.Z.; review and editing: M.B., A.Z. and R.G.; discussion: V.B., A.P., N.K. and R.G.; funding: N.K. and A.P. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the European Social Fund within the Project No 8.2.2.0/20/I/008 «Strengthening of PhD students and academic personnel of Riga Technical University and BA School of Business and Finance in the strategic fields of specialization» of the Specific Objective 8.2.2 «To Strengthen Academic Staff of Higher Education Institutions in Strategic Specialization Areas» of the Operational Programme «Growth and Employment».

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available on request from the corresponding author. The data are not publicly available due to commercial interest from research partner “FIXAR-Aero” company who contributed to the research with technical information.

Acknowledgments

This work has been implemented in collaboration with the Latvian aircraft design developer “FIXAR-Aero” SIA. Data on the aircraft design and characteristics have been provided by “FIXAR-Aero” SIA.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. FIXAR: Fully Autonomous UAV Platform. Available online: https://fixar.pro/ (accessed on 10 August 2023).
  2. Flores, G.R.; Colunga, F.; Escare, J.A.; Lozano, R.; Salazar, S. Four tilting rotor convertible MAV: Modeling and real-time hover flight control. J. Intell. Robot. Syst. 2012, 65, 457–471. [Google Scholar] [CrossRef]
  3. Ardupilot: Versatile, Trusted, Open. Available online: https://ardupilot.org/ (accessed on 14 August 2023).
  4. PX4 Autopilot: Open Source Autopilot for Drones. Available online: https://px4.io/ (accessed on 14 August 2023).
  5. Liu, Z.; He, Y.; Yang, L.; Han, J. Control techniques of tilt-rotor unmanned aerial vehicle systems: A review. Chin. J. Aeronaut. 2017, 30, 135–148. [Google Scholar] [CrossRef]
  6. Saeed, A.S.; Younes, A.B.; Islam, S.; Dias, J.; Seneviratne, L.; Cai, G. A review on the platform design, dynamic modeling and control of hybrid UAVs. In Proceedings of the 2015 International Conference on Unmanned Aircraft Systems (ICUAS), Denver, CO, USA, 9–12 June 2015; pp. 806–815. [Google Scholar]
  7. KDT JU: Key Digital Technologies Joint Undertaking: COMP4DRONES Project. Available online: https://www.comp4drones.eu/ (accessed on 16 November 2023).
  8. Bouabdallah, S.; Noth, A.; Siegwart, R. PID vs LQ control techniques applied to an indoor micro quadrotor. In Proceedings of the Intelligent Robots and Systems, Sendai, Japan, 28 September–2 October 2004. [Google Scholar]
  9. Ahmad, M.; Hussain, Z.L.; Shah, S.I.A.; Shams, T.A. Estimation of Stability Parameters for Wide Body Aircraft Using Computational Techniques. Appl. Sci. 2021, 11, 2087. [Google Scholar] [CrossRef]
  10. Evan, M.N. Evaluation of XFLR5 for Predicting Stability and Dynamics of a Ready-to-Fly Trainer Aircraft. Honors Capstone Projects and Theses. 2020, p. 158. Available online: https://louis.uah.edu/cgi/viewcontent.cgi?article=1157&context=honors-capstones (accessed on 26 October 2023).
  11. Amici, C.; Ceresoli, F.; Pasetti, M.; Saponi, M.; Tiboni, M.; Zanoni, S. Review of Propulsion System Design Strategies for Unmanned Aerial Vehicles. Appl. Sci. 2021, 11, 5209. [Google Scholar] [CrossRef]
  12. Joshi, D.; Deb, D.; Muyeen, S. Comprehensive review on electric propulsion system of unmanned aerial vehicles. Front. Energy Res. 2022, 10, 752012. [Google Scholar] [CrossRef]
  13. Hong, J.Y.; Chiu, P.J.; Pong, C.D.; Lan, C.Y. Attitude and Altitude Control Design and Implementation of Quadrotor Using NI myRIO. Electronics 2023, 12, 1526. [Google Scholar] [CrossRef]
  14. Rinaldi, M.; Primatesta, S.; Guglieri, G. A Comparative Study for Control of Quadrotor UAVs. Appl. Sci. 2023, 13, 3464. [Google Scholar] [CrossRef]
  15. Giernacki, S.S.W. Hybrid Quasi-Optimal PID-SDRE Quadrotor Control. Energies 2022, 15, 4312. [Google Scholar] [CrossRef]
  16. Sebbane, Y.B. Smart Autonomous Aircraft, 3rd ed.; CRC Press: Boca Raton, NW, USA, 2008; pp. 26–48, 105–117, 172–183. [Google Scholar]
  17. Reizenstein, A. Position and Trajectory Control of a Quadcopter Using PID and LQ Controllers. Master’s Thesis, Linköping University, Linköping, Sweden, 2017. [Google Scholar]
  18. Rinaldi, F.; Chiesa, S.; Quagliotti, F. Linear quadratic control forquadrotors uavs dynamics and formation flight. J. Intell. Robot. Syst. 2013, 70, 203–220. [Google Scholar] [CrossRef]
  19. Deng, J.; Becerra, V.M.; Stobart, R. Input Constraints Handling in an MPC/Feedback Linearization Scheme. Int. J. Appl. Math. Comput. Sci. 2009, 19, 219–232. [Google Scholar] [CrossRef]
  20. Noordin, A.; Mohd Basri, M.A.; Mohamed, Z. Real-Time Implementation of an Adaptive PID Controller for the Quadrotor MAV Embedded Flight Control System. Aerospace 2023, 10, 59. [Google Scholar] [CrossRef]
  21. Vu, T.N.L.; Chuong, V.L.; Truong, N.T.N.; Jung, J.H. Analytical Design of Fractional-Order PI Controller for Parallel Cascade Control Systems. Appl. Sci. 2022, 12, 2222. [Google Scholar] [CrossRef]
  22. Huba, M.; Chamraz, S.; Bistak, P.; Vrancic, D. Making the PI and PID Controller Tuning Inspired by Ziegler and Nichols Precise and Reliable. Sensors 2021, 21, 6157. [Google Scholar] [CrossRef] [PubMed]
  23. Bistak, P.; Huba, M.; Vrancic, D.; Chamraz, S. IPDT Model-Based Ziegler–Nichols Tuning Generalized to Controllers with Higher-Order Derivatives. Sensors 2023, 23, 3787. [Google Scholar] [CrossRef] [PubMed]
  24. Kim, J. A Comprehensive Survey of Control Strategies for Autonomous Quadrotors. Can. J. Electr. Comput. Eng. 2020, 43, 3–16. [Google Scholar] [CrossRef]
  25. Lee, D.; Jin Kim, H.; Sastry, S. Feedback linearization vs. adaptive sliding mode control for a quadrotor helicopter. Int. J. Control Autom. Syst. 2009, 7, 419–428. [Google Scholar] [CrossRef]
  26. Maruf, A.; Kadir, R.E.A.; Gamayanti, N.; Santoso, A.; Bilfaqih, Y.; Sahal, M.; Hidayat, Z. L1 adaptive controller for unmanned surface vehicle type monohull LSS01 autopilot system and guidance design. In Proceedings of the Sustainable Islands Development Initiatives, Surabaya, Indonesia, 2–3 September 2021. [Google Scholar]
  27. Thu, K.M.; Gavrilov, A.I. Designing and modeling of quadcopter control system using L1 adaptive control. Procedia Comput. Sci. 2017, 103, 528–535. [Google Scholar] [CrossRef]
  28. Michini, B.; How, J. L1 Adaptive Control for Indoor Autonomous Vehicles: Design Process and Flight Testing. In Proceedings of the GNC-15: Control of Autonomous Vehicles, Chicago, IL, USA, 10–13 August 2009; Aerospace Controls Laboratory Massachusetts Institute of Technology: Cambridge MA, USA, 2009. [Google Scholar]
  29. Patlins, A.; Kunicina, N. The new approach for passenger counting in public transport system. In Proceedings of the 2015 IEEE 8th International Conference on Intelligent Data Acquisition and Advanced Computing Systems: Technology and Applications (IDAACS), Warsaw, Poland, 24–26 September 2015; pp. 53–57. [Google Scholar] [CrossRef]
  30. Zabasta, A.; Kondratjevs, K.; Peksa, J.; Kunicina, N. MQTT enabled service broker for implementation arrowhead core systems for automation of control of utility’ systems. In Proceedings of the 2017 5th IEEE Workshop on Advances in Information, Electronic and Electrical Engineering (AIEEE), Riga, Latvia, 24–25 November 2017; pp. 1–6. [Google Scholar] [CrossRef]
  31. Zenina, N.; Merkuryev, Y.; Romanovs, A. TRIP-based Transport Travel Demand Model for Intelligent Transport System Measure Evaluation based on Micro Simulation. Int. J. Simul. Process Model. 2017, 12, 207–220. [Google Scholar] [CrossRef]
Figure 1. Motor forces kinematics scheme: (a) top projection; (b) side projection.
Figure 1. Motor forces kinematics scheme: (a) top projection; (b) side projection.
Applsci 13 12940 g001
Figure 2. Motor block Simulink model.
Figure 2. Motor block Simulink model.
Applsci 13 12940 g002
Figure 3. Pitch angle stabilization system.
Figure 3. Pitch angle stabilization system.
Applsci 13 12940 g003
Figure 4. Sliding control systems: (a) Plane flight controllers; (b) Copter position hold controllers.
Figure 4. Sliding control systems: (a) Plane flight controllers; (b) Copter position hold controllers.
Applsci 13 12940 g004
Figure 5. L1 adaptive controller block diagram.
Figure 5. L1 adaptive controller block diagram.
Applsci 13 12940 g005
Figure 6. Control system design.
Figure 6. Control system design.
Applsci 13 12940 g006
Figure 7. Control system elements: (a) L1 controller; (b) dynamic limits block.
Figure 7. Control system elements: (a) L1 controller; (b) dynamic limits block.
Applsci 13 12940 g007
Figure 8. Adaptive velocity control system tuning: (a) time domain; (b) phase trajectory.
Figure 8. Adaptive velocity control system tuning: (a) time domain; (b) phase trajectory.
Applsci 13 12940 g008
Figure 9. States machine model.
Figure 9. States machine model.
Applsci 13 12940 g009
Figure 10. Mission flight trajectory: (a) 3D graph; (b) 2D graph.
Figure 10. Mission flight trajectory: (a) 3D graph; (b) 2D graph.
Applsci 13 12940 g010
Figure 11. Transition process compared in the time domain: (a) launch and acceleration; (b) deceleration and landing.
Figure 11. Transition process compared in the time domain: (a) launch and acceleration; (b) deceleration and landing.
Applsci 13 12940 g011
Table 1. Model parameters.
Table 1. Model parameters.
CharacteristicDescriptionUnitValue
D w Wingspanm1.6
m m a x Maximum takeoff weightkg7
P d Propeller diameterin10
P p Propeller pitchin4.5
K ω Linear coefficient transferring from throttle command (range [0:1] to motor rate for specified voltage)rad/s/1V109.9
K f m Linear coefficient transferring from motor rate to motor thrustN/(rad/s)0.0181
K r Motor rate-to-yawing torque coefficientN∗m/(rad/s)5∗10−6
J m Motor inertiaKg∗m20.005
T s Motor time constants0.01
V Battery voltage (constant)volts23
ϕ 1 = ϕ 2 = ϕ 3 = ϕ 4 Motor inclination angledegree45
r 1 x = r 2 x = r 3 x = r 4 x Motor distance on x axism0.45
r 1 y = r 2 y = r 3 y = r 4 y Motor distance on y axism0.25
Where T s is the time constant of the motor aperiodic link, describing the motor dynamics, and K ω is the coefficient transferring motor command to the motor rate ω.
Table 2. PID based control system settings.
Table 2. PID based control system settings.
AxisOx (Poshold)Oy (Poshold)Oz (Poshold)Oz (Plane)As (Plane)Yaw (Plane)
K p o s 0.5121--
Tz12.5411.576.073.873.33512.44
Kpmax23.9219.44812.9711.3493.339
K P 10.7658.75365.845.10341.994.5
K I 1.03700.907472.271.58215.11-
Table 3. Simulation parameters.
Table 3. Simulation parameters.
ParameterDescriptionUnitValue
Simulation solver Ode3 (Bogacki-Shampine)
d T Simulation steps0.0001
m Drone masskg7
W d i r Wind directiondeg−30
W 6 Wind speed at 6 m altitudem/s7
W 500 Wind speed at 500 m altitudem/s13.6
A s t g t Target (cruise) airspeedm/s20
X 0 Initial positionm[0, 0, 0]
O 0 Initial orientation (roll, pitch, yaw)deg[0, 0, 0]
M 0 Mission point 0 (Takeoff point)m[0, 0, 25]
M 1 Mission point 1m[310, −80, 25]
M 2 Mission point 2m[1650, −610, 500]
M 3 Mission point 3m[2200, 3450, 500]
M 4 Mission point 4m[−300, 3000, 200]
M 5 Mission point 5m[−1400, 2300, 100]
M 6 Mission point 6 (Deceleration point)m[−1200, 1500, 100]
M 7 Mission point 7 (Landing point)m[−1200, 1500, 0]
M p 0 Launch pauses20
M r Point acceptance radiusm10
Table 4. Flight characteristics comparison.
Table 4. Flight characteristics comparison.
ParameterCharacteristicPIDL1
t f Flight time742.9 s679.14 s
σ Stability error rate7%1.4%
e h Max horizontal error250.8 m (point 3)71.13 m (point 3)
e v Max vertical error28.6 m (point 4)2.24 m (point 3)
t s m Linefollow setting time52.1 s16.53 s
O m Linefollow overshoot11.4 mNo overshoot
t s p Setting time (poshold)11.2 s4.1 s
e p Max deviation (poshold)5.2 m/s3.95 m/s
O p v Overshoot (poshold, vertical)54%2%
t s l Transition time (launch)3.62 s4.9 s
O l v Velocity overshoot (launch)9.8%33%
t s d Transition time (deceleration)6.7 s5.8 s
Computational loadHigh (due to multi-controller setup)Moderate (Integrated approach)
Robustness to disturbanceModerate (oscillations observed)High (minimal deviation)
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

Beliaev, V.; Kunicina, N.; Ziravecka, A.; Bisenieks, M.; Grants, R.; Patlins, A. Development of Adaptive Control System for Aerial Vehicles. Appl. Sci. 2023, 13, 12940. https://doi.org/10.3390/app132312940

AMA Style

Beliaev V, Kunicina N, Ziravecka A, Bisenieks M, Grants R, Patlins A. Development of Adaptive Control System for Aerial Vehicles. Applied Sciences. 2023; 13(23):12940. https://doi.org/10.3390/app132312940

Chicago/Turabian Style

Beliaev, Vladimir, Nadezhda Kunicina, Anastasija Ziravecka, Martins Bisenieks, Roberts Grants, and Antons Patlins. 2023. "Development of Adaptive Control System for Aerial Vehicles" Applied Sciences 13, no. 23: 12940. https://doi.org/10.3390/app132312940

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