Open Access Paper
11 February 2020 Linear controller design with the use of PSO algorithm for UAV trajectory tracking
Author Affiliations +
Proceedings Volume 11442, Radioelectronic Systems Conference 2019; 114420Z (2020) https://doi.org/10.1117/12.2565129
Event: Radioelectronic Systems Conference 2019, 2019, Jachranka, Poland
Abstract
This paper uses the PSO (Particle Swarm Optimization) algorithm to linearly control a BSP unmanned aircraft, enabling accurate tracking of a predefined trajectory. In the process of control optimization, the PSO algorithm was implemented with a quadratic cost function. During the study, unstable algorithm behavior was observed, as a result of which a modification was made by introducing a coefficient suppressing the movement of particles in the search space. The main task of the coefficient is to ensure the convergence of the solution. The effect of the coefficient value on population behavior was tested. In the simulation research on tracking, the previously generated trajectory was used, which is a reference for the location, velocity, and course for the linear dynamic BSP model. The results of these tests were presented in the form of waveforms of control signals and waveforms of state variables. By selecting the appropriate parameters, the proposed algorithm enabled the repeatability of results, as well as the proper mapping of the trajectory at the time of the operation of the algorithm not exceeding 0.03 seconds.

1

INTRODUCTION

Due to the utility and growing popularity of unmanned aerial vehicles (UAV), especially in military field [1], various methods of control have been developed [2-5]. One important aspect of controlling these platforms is waypoint following, or trajectory tracking. The correct movement of a UAV to a designated destination [10] is one of the main requirements for its autonomy. On the other hand, trajectory tracking is a more detailed task, primarily focused on mapping individual flight parameters during its execution. Such tasks are carried out using appropriate controllers, the purpose of which is to select the right sequence of control signals so that the error resulting from the mismatch to the reference trajectory during the flight is as small as possible.

A classic approach in such control is the use of PID (Proportional Integral Derivative) linear controllers [6]. Their basic task is to regulate the control signal on the basis of the error resulting from the difference between the controlled value and reference value. The PID controller is a SISO (Single Input Single Output) system with feedback, which does not require knowledge of the controlled system model. Assuming a time-varying reference signal, one can implement a trajectory tracking problem [7] using, for example, a tracking system. In turn, works [7] and [8] present a method of trajectory tracking using an LQR – Linear Quadratic Regulator. The LQR controller implements optimal control (regulation) by minimizing the quadratic cost function [9]. Trajectory tracking, resulting from the difference between the target trajectory and the original state, can be obtained by converting the linear system into its equivalent in the error space, respectively. In [7], the authors present a direct comparison of PID and LQR controllers in the context of trajectory tracking, and demonstrate the superiority of the LQR controller. MPC (Model Predictive Control) is another widely used technique for designing controllers [10, 12]. It consists of determining an optimal sequence of control signals in parallel with the state prediction, minimizing the cost function determined by the designer (usually in a square form with selected weighting factors) in such a way that the UAV trajectory tends to the reference trajectory. The optimization takes place over a given time window, called the horizon. After performing the optimization at a given time, the system performs only the first step of the designated control sequence, then performs the optimization again. This process repeats continuously during system operation. MPC controllers are used with great success [13, 15-16], despite the requirements of significant computational load. Calculations are often carried out on separate platforms that send only designated optimization solutions to UAV platforms. Authors in [12] show MPC variants that can be used directly on UAVs.

This paper presents a method of suboptimal feedback control using PSO (Particle Swarm Optimization) [17]. PSO has many applications in various fields of science [14, 19], and also in controller design. The rest of the article presents the use of PSO to determine the suboptimal control that implements UAV trajectory tracking.

2

MATHEMATICAL MODEL

The paper assumes the UAV model as a rigid body with six degrees of freedom (6 DoF): three representing translational displacement, and three corresponding to spatial orientation. Movement is described in two coordinate systems: inertial Fe = {Xe, Ye, Ze} associated with Earth, and non-inertial Fb = {Xb, Yb, Zb} associated with the UAV (Fig. 1).

Fig 1.

Reference coordinate systems: inertial Earth and non-inertial UAV.

00484_psisdg11442_114420z_page_2_1.jpg

An UAV moves by regulating angular speeds ω1-4 of four engines assembled with propellers generating thrusts ft1-4. In the UAV design presented in Fig. 2, motors are located on opposite sides of the intersection of two perpendicular axes. These axes simultaneously coincide with the axes Xb, Yb. Due to the difference in forces between the pairs of engines, appropriate torques τx and τy are generated, allowing rotation around the corresponding axes – rotation ϕ around the Xb axis and rotation θ around the Yb axis (pitch). Propellers also cause torques τ1-4 acting in the plane [Xb Yb]. The resultant net torque τz causes rotation ψ around the axis Zb (yaw).

Figure 2.

Arrangement of UAV engines and action of forces.

00484_psisdg11442_114420z_page_2_2.jpg

A mathematical model of the UAV was built based on the following assumptions:

  • symmetric construction,

  • rigid structure,

  • the UAVs center of gravity gc coinciding with the beginning of coordinate system Fb.

2.1

System dynamics

For the simulation, a model derived from the Newton and Euler equations presented in [20] was used. Assuming the vector [x y z ϕ θ ψ]T as the position and orientation vector in the Fe system, as well as the vector [u v w p q r]T for the vector of linear and angular velocities in the Fb system, the dynamic UAV model takes the following form:

00484_psisdg11442_114420z_page_3_1.jpg

with the following definitions: s(α) := sin(α), c(α) := cos(α), t(α) := tan(α), and m as the UAV’s mass. Inertia matrix I, due to platform construction symmetry, takes the diagonal form of

00484_psisdg11442_114420z_page_3_5.jpg

Minor damping reflecting aerodynamic drag has been added to the model [22]. Diagonal matrices of displacement and rotation aerodynamic coefficients are expressed by the following relationships:

00484_psisdg11442_114420z_page_3_6.jpg
00484_psisdg11442_114420z_page_3_7.jpg

By organizing individual variables, a state vector is obtained:

00484_psisdg11442_114420z_page_3_8.jpg

along with the control input vector

00484_psisdg11442_114420z_page_3_9.jpg

This vector contains, respectively, the value of the resultant lift generated by the engines set ft, torques τx and τy in the Ox and Oy axes of the UAV platform, and torque τz in the Oz UAV axis. Finally, the form of a nonlinear dynamic system is expressed as

00484_psisdg11442_114420z_page_3_10.jpg

2.2

Linearization of nonlinear model

The four-rotor model is a highly non-linear system with many coupled variables. In order to enable linear analysis of the system, the model should be linearized, assuming an appropriate operation point. The most frequently chosen operation point is the equilibrium condition obtained when the four-rotor model hovers. This means no UAV movement, so its dynamics are described by the following differential equation:

00484_psisdg11442_114420z_page_3_11.jpg

where x* = [01×9 x y z] and u* = [mg 0 0 0] are nominal values for the given operation point. This condition occurs when all four engines generate a net thrust equal to the weight mg of the UAV in the opposite direction. Under ideal conditions, there are no other forces or moments present.

The system was linearized using the Control System Toolbox of MATLAB/Simulink software, thanks to which the LTI (Linear Time Invariant) state space system described by two vector-matrix equations was obtained:

00484_psisdg11442_114420z_page_4_1.jpg

where A∈ℜ12×12 is the system matrix, B∈ℜ4×12 is the control matrix, C∈ℜ12×12 is the output matrix, and D∈ℜ12×4 is the transmission matrix. For the calculations, the parameters contained in Table 1 were used and the following results were obtained:

00484_psisdg11442_114420z_page_4_2.jpg
00484_psisdg11442_114420z_page_4_3.jpg
00484_psisdg11442_114420z_page_4_4.jpg
00484_psisdg11442_114420z_page_4_5.jpg

Table 1.

Parameters used to create UAV model.

ParameterValue
Inertia matrixdeg(I) = [0,0196 0,0196 0,0264]
Aerodynamic coefficientstranslationdeg(Dt) = [0,5 0,5 0,5]
rotationdeg(Dr) = [0,1 0,1 0,1]
UAV massm = 0.4 kg

The parameters used for UAV modeling are presented in Table 1.

3

CONTROLER DESIGN

3.1

Model discretization

This application uses a discrete controller with a sampling time of Tc = 0.1s using the PSO algorithm for cost function minimalization. The task of the algorithm, considering the assumed quality indexes, is to select such a value of control vector u(k) at a given moment k that the difference between the predicted state x(k+1|k) and corresponding reference point xref(k+1) is minimal. Due to its discrete nature, the dynamic model (9-13) has also been transformed to the discrete form:

00484_psisdg11442_114420z_page_5_1.jpg

with c2d() command in MATLAB. For sampling time Ts = 0.05s, the following results were obtained:

00484_psisdg11442_114420z_page_5_2.jpg
00484_psisdg11442_114420z_page_5_3.jpg
00484_psisdg11442_114420z_page_5_4.jpg
00484_psisdg11442_114420z_page_5_5.jpg

3.2

PSO algorithm for control optimization

The PSO algorithm searches for solutions in the n-dimensional space of the function to be optimized [18]. This is accomplished by iteratively moving the population of p particles to find coordinates for which the value of a given cost function is minimal. Each i-th particle has the following known parameters:

  • position xi ∈ ℜn,

  • velocity vi ∈ ℜn,

  • actual best own positionp_besti ∈ ℜn.

Figure 3.

PSO algorithm block diagram.

00484_psisdg11442_114420z_page_6_1.jpg

The particle with best global value g_best ∈ ℜn is also determined for the entire population. The evolution of the algorithm is described by expressions:

00484_psisdg11442_114420z_page_6_2.jpg
00484_psisdg11442_114420z_page_6_3.jpg

where w is the inertia weight, c1 is the value of the so-called personal coefficient, c2 is the value of the social coefficient, and rand() is a pseudo-random function which selects a number from a range [0, 1]. The movement of each particle depends on its current velocity, its best own position so far, and the global best position for time (iteration) t. The c1 and c2 coefficients determine the tendency to choose the direction of particle movement. The rand() function gives the algorithm a pseudo-random character, while increasing its searching performance.

Due to its stochastic properties, the PSO is a metaheuristic algorithm [18, 23]. It does not guarantee an optimal solution, but only determines a sub-optimal variant that meets given assumptions, as close as possible to the optimal solution. This allows for the reduction of the computational load of the solution, at the expense of its accuracy. This is especially useful when reaction speed is more important than precision. The algorithm ends its execution after reaching the iteration limit or meeting the given criterion, returning the best solution so far g_best.

3.3

Search space and cost function optimization.

During the algorithm execution, particles explore the U⊂ℜ4 space of the control vector u values. At the beginning of each iteration (after the movement of the entire population), a cost function is calculated for each particle, considering its current position. In the proposed application, the function being optimized takes a quadratic form:

00484_psisdg11442_114420z_page_6_4.jpg

where Jti is the cost function value for the i-th particle in the iteration t, ui(k+1) means the coordinates of the i-th particle (selected values for control signals), xi means the state that the UAV would achieve by applying the control determined by the coordinates of the particle i, and unom is the nominal value of the control vector (for the equilibrium point). Disturbances and measurement errors are not considered [21]. For known initial values of the state vector, the values of xi(k+1) are determined directly from the expression (14).

Diagonal weighting matrices Q ≥ ℜ12×12 and R, RΔu ≥ 0∈ℜ4×4 determine the impact of each factor in total value of the cost function. The Q matrix is responsible for the influence of error magnitude between state variables and their reference values (fitness criterion). The R matrix determines the reaction to the difference between the nominal values of the control signals and the values selected in a given solution (energy criterion). The RΔn matrix is responsible for the impact of the difference between the selected control and the current signal level (signal dynamics criterion).

Figure 4.

a-d) PSO solution searching process.

00484_psisdg11442_114420z_page_7_1.jpg

The algorithm allows for the explicit limitation of the values of the control signals. By imposing a condition on the allowed positions of particles in the search space

00484_psisdg11442_114420z_page_7_2.jpg

it can be ensured that no control value outside the specified range is selected.

4

SIMULATION RESULTS

4.1

Initial parameter configuration

The following parameters for the PSO algorithm were adopted for the simulation tests: number of particles p = 40, iterations limit it_lim = 150, inertia coefficient w = 0.9298, and personal and social coefficients c1 = c2 = 1.4986. The diagonals of the weight matrices were selected as follows:

00484_psisdg11442_114420z_page_8_1.jpg
00484_psisdg11442_114420z_page_8_2.jpg
00484_psisdg11442_114420z_page_8_3.jpg

The search space of the PSO algorithm has been limited by the following ranges:

00484_psisdg11442_114420z_page_8_4.jpg

where this range refers to the nominal control unom in which the value of the first coordinate mg has been compensated, so unom = [0 0 0 0].

In order to perform the simulations, a test trajectory was generated containing references for position, velocity and course (Figs. 5-6).

Figure 5.

Reference values for state variables of UAV.

00484_psisdg11442_114420z_page_8_5.jpg

Other state variables, without reference values, were compared with their equilibrium values x*, so

00484_psisdg11442_114420z_page_8_6.jpg

Figure 6.

3D path profile (T): S – starting point, D – destination point.

00484_psisdg11442_114420z_page_9_1.jpg

4.2

PSO algorithm improvements

The first attempts showed unstable operation of the algorithm. Control signal waveforms generated by the algorithm were characterized by strong distortion (Fig. 7).

Figure 7.

Control signal waveforms generated in initial configuration.

00484_psisdg11442_114420z_page_9_2.jpg

Despite the occurrence of undesirable distortion of control signals, the algorithm showed the ability to track the given trajectories of individual state variables (Figs. 8-9). Therefore, an improvement in the process of determining signal values could be achieved by the additional modification and tuning of algorithm parameters.

Figure 8.

State variable waveforms [u, v, w] for initial configuration.

00484_psisdg11442_114420z_page_10_1.jpg

Figure 9.

State variables waveform [x, y, z, ψ] for initial configuration.

00484_psisdg11442_114420z_page_10_2.jpg

After observing the execution of the PSO algorithm, it was noticed that the problem with stability is due to the difficulty in achieving convergence. By design, each particle should gradually approach the global best solution, while reducing its velocity in subsequent iterations. Thus, it is possible to exploit more closely neighborhood of the best solution. This effect was not achieved in the basic algorithm configuration (Fig. 10). The velocities of the particles did not decrease sufficiently, resulting in long-distance motion. The end result was a large spread around the globally best solution. Let S ⊂ ℜ+ be a set of Euclidean distances si of all particles from the position g_best, so

00484_psisdg11442_114420z_page_10_3.jpg

The average distance between the particles and g_best in the last iteration was assumed as the measure of population spread:

00484_psisdg11442_114420z_page_10_4.jpg

In order to improve the convergence of the algorithm, expression (19) was modified by implementing a factor λ that scales the velocity of particles in each iteration:

00484_psisdg11442_114420z_page_11_1.jpg

Table 2 presents the simulation results for the factor λ in the range <0.3, 0.8>. Without considering λ, the algorithm obtained the following results: average value of the dispersion index εavr = 1.3944, minimum value εmin = 0.9380, maximum value εmax = 2.0023, and total path cost Jc1 = 8.5574e + 05.

Figure 10.

Values of ε for initial configuration.

00484_psisdg11442_114420z_page_11_2.jpg

Table 2.

Comparison of experiment results for different values of λ.

λεśrεminεmaxJc1 – Jcλ
0.31.6238e-119.3965e-192.8786e-093.4817e+03
0.356.1628e-105.8451e-182.6602e-081.5645e+03
0.48.0896e-096.2658e-176.9009e-085.4511e+03
0.451.7173e-086.8815e-159.4198e-081.2267e+04
0.51.9109e-084.4003e-118.4363e-081.3897e+04
0.552.1086e-083.8774e-119.8508e-081.3913e+04
0.62.4056e-085.0962e-111.1915e-071.3913e+04
0.652.7744e-084.7023e-111.6079e-071.3914e+04
0.73.4030e-088.8582e-112.0271e-071.3913e+04
0.756.1766e-084.1638e-096.8558e-071.3913e+04
0.85.1780e-063.5249e-079.3663e-041.3913e+04

Based on the simulation results, it can be concluded that the best variant is λ equal to 0.65. Fig. 11 shows a graph of changes in the index ε for the selected value λ. The difference can be clearly seen compared to the initial version of the algorithm – the magnitude order of the average value εavr is several times smaller, which coincides with the original assumptions.

The total cost Jc also improved, mainly due to the decrease in the cost of control signal dynamics, whose waveforms are shown in Fig. 12.

Figure 11.

Values of ε for λ = 0.65.

00484_psisdg11442_114420z_page_12_1.jpg

Figure 12.

Control signals generated for λ = 0.65.

00484_psisdg11442_114420z_page_12_2.jpg

After the stabilization of the control signals, the trajectories were smoothened (Figs. 13-14) but their shape and fitness changed only slightly. This indicates that the algorithm’s instability has no effect on its efficiency (in the context of matching to reference trajectories). The sum of squares of differences between real values and reference state variables [u, v, w, x, y, z, ψ] at all discrete moments k was taken as fitness criterion μe:

00484_psisdg11442_114420z_page_12_3.jpg
00484_psisdg11442_114420z_page_12_4.jpg

Table 3 compares the individual components of the indicator μe for λopt = 0.65 and λ0 = 1.

Table 3.

Comparison of error values for the basic and modified variants of the PSO algorithm

 euevewexerezμe
λ01.8193e031.0054e033.24052.4148e051.4808e0541.91075.2868e065.6792e06
λopt1.8307e031.0497e032.14362.1246e051.3312e0532.67425.0034e065.3519e06
eopt÷e01.00601.04410.66150.87980.89900.77960.94640.9424

Figure 13.

State variable waveforms [u, v, w] for λ = 0.65.

00484_psisdg11442_114420z_page_13_1.jpg

Figure 14.

State variable waveforms [x, y, z, ψ] for λ = 0.65.

00484_psisdg11442_114420z_page_13_2.jpg

4.3

Selection of weight matrices elements

Due to the lack of significant improvement in the adjustment of state variable trajectories to their reference values (despite the stabilization of the PSO algorithm), attempts have been made to improve the fitness indicator by changing the values of the weight matrices. Analyzing the results from Table 3, it can be seen that the largest errors are coupled with variables u, v, x, y, ψ with error eψ an order of magnitude greater than other errors. However, weighting factors for individual matrices were intuitively modified, considering that the weighting factor for eψ should be greater than the weighting factors corresponding to the remaining state variables being tracked. Finally, the weighting matrices took the following values:

00484_psisdg11442_114420z_page_13_3.jpg
00484_psisdg11442_114420z_page_13_4.jpg
00484_psisdg11442_114420z_page_13_5.jpg

The simulation results for the new values of the weight coefficients are presented in Figs. 15-17. Table 4 presents a comparison of individual components of the index μe for the modified values of Ropt and the unmodified R0.

Figure 15.

Control signal waveforms for modified weight matrices.

00484_psisdg11442_114420z_page_14_1.jpg

Figure 16.

State variable waveforms [u, v, w] for modified weight matrices.

00484_psisdg11442_114420z_page_14_2.jpg

Figure 17.

State variable waveforms [x, y, z, ψ] for modified weight matrices.

00484_psisdg11442_114420z_page_14_3.jpg

Table 4.

Comparison of error values for the basic and modified variants of the PSO algorithm.

 euevewexerezμe
R01.8307e031.0497e032.14362.1246e051.3312e0532.67425.0034e065.3519e06
Ropt82.401856.47242.12019.3949e036.4715e032.97947.1436e048.7447e04
eRopt÷eR00.04500.05380.66150.04420.04860.09110.01420.0163

5

CONCLUSIONS

The applied PSO algorithm presents accurate results in the discrete process of controlling an unmanned aerial vehicle. Despite the difficulties associated with the unstable operation of the algorithm, the implemented factor λ suppressing the motion of the population of particles allowed for the improvement of the average population dispersion by almost 8 orders of magnitude. Application of the coefficient λ = 0.65 resulted in the reduction of ɛavr from 1.3944 to 2.7744e-08. Thus, much greater precision of optimization was achieved, while slightly increasing the total cost of the route.

The stabilization of the PSO algorithm did not bring significant benefits in terms of matching to the given trajectory, reducing the value of μe by only 5.8%. In order to improve the fitness index, weight matrices determining the cost function were modified. The selection of new weighting coefficients allowed for improvement of μe by over 98%, which was illustrated in the plot of individual state variables.

In subsequent stages of work on the application of the PSO algorithm to optimize the tracking of UAV trajectories, one can consider the application of integration term for fitness error into cost function. This would eliminate visible steady-state error. Another modification may be the introduction of requirements on the output values of state variables, thus limiting the system dynamics.

REFERENCES

[1] 

Kaniewśki, P., Leśnik, C., Serafin, P. and Łabowski, M., “Chosen Results of Flight Tests of WATSAR System,” in 17th International Radar Symposium IRS, 1 –5 (2016). Google Scholar

[2] 

Gopalakrishnan, E. M., “Quadcopter Flight Mechanics and Control Algorithms,” Diploma Thesis Assignment, Czech Technical University in Prague, Prague (2016). Google Scholar

[3] 

Zulu, A. and John, S., “A Review of Control Algorithms for Autonomous Quadrotors,” Open Journal for Applied Sciences, 4 547 –556 (2014). https://doi.org/10.4236/ojapps.2014.414053 Google Scholar

[4] 

Kaniewski, P., Kazubek, J. and Kraszewski T., “Application of UWB Modules in Indoor Navigation System,” in 2017 IEEE International Conference on Microwaves, Antennas, Communications and Electronic Systems (COMCAS), (2017). https://doi.org/10.1109/COMCAS.2017.8244726 Google Scholar

[5] 

Kraszewski T. and Czopik G., “Tracking of land vehicle motion with the use of distance measurements,” in Proc. SPIE 11055, XII Conference on Reconnaissance and Electronic Warfare Systems, 110550Y (2019). https://doi.org/10.1117/12.2524954 Google Scholar

[6] 

Holejko, D. and Kościelny, W. J., “Automatyka procesów ciągłych,” Oficyna Wydawnicza Politechniki Warszawskiej, Warszawa, (2012). Google Scholar

[7] 

Changlong, L., Jian, P. and Yufang, C., “PID and LQR Trajectory Tracking Control for An Unmanned Quadrotor Helicopter: Experimental Studies,” in Proceedings of the 35th Chinese Control Conference, (2016). Google Scholar

[8] 

Xie, H., Cabecinhas, D. and Cunha, R., “A trajectory tracking LQR controller for a quadrotor: Design and experimental evaluation,” in TENCON 2015 - 2015 IEEE Region 10 Conference, (2015). Google Scholar

[9] 

Zhou, K. and Doyle, J. C., “Essentials of Robust Control,” Prentice Hall, (1999). Google Scholar

[10] 

Abdolhosseini, M., “Model Predictive Control of an Unmanned Quadrotor Helicopter: Theory and Flight Tests,” A Thesis in The Department of Mechanical and Industrial Engineering, Canada (2012). Google Scholar

[11] 

Matuszewski, J. and Dikta, A., “Emitter location errors in electronic recognition system,” in Proceedings of SPIE - The International Society for Optical Engineering, C1 –C8 (2017). https://doi.org/10.1117/12.2269295 Google Scholar

[12] 

Bouffard, P., “On-board Model Predictive Control of a Quadrotor Helicopter: Design, Implementation and Experiments,” Electrical Engineering and Computer Sciences, University of California at Berkeley, (2012). Google Scholar

[13] 

Ganga, G. and Dharmana, M. M., “MPC Controller for Trajectory Tracking Control of Quadcopter,” in 2017 International Conference on Circuits Power and Computing Technologies, (2017). https://doi.org/10.1109/ICCPCT.2017.8074380 Google Scholar

[14] 

Matuszewski, J., “Radar signal identification using a neural network and pattern recognition methods,” in 14th International Conference on Modern Problems of Radio Engineering, Telecommunications and Computer Science, TCSET 2018 - Proceedings, 79 –83 (2018). https://doi.org/10.1109/TCSET.2018.8336160 Google Scholar

[15] 

Falanga, D., Foehn, P., Lu, P. and Scaramuzza, D., “PAMPC: Perception-Aware Model Predictive Control for Quadrotors,” in IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), (2018). https://doi.org/10.1109/IROS.2018.8593739 Google Scholar

[16] 

Kamel, M., Burri, M. and Siegwart, R., “Linear vs Nonlinear MPC for Trajecotry Tracking Applied to Rotary Wing Micro Aerial Vehicle,” IFAC (International Federation of Automatic Control) Hosting by Elsevier, (2017). Google Scholar

[17] 

Kennedy J. and Eberhart, R., “Particle Swarm Optimization,” in Proceedings of IEEE International Conference on Neural Networks. IV, 1942 –1948 (1995). Google Scholar

[18] 

Konatowski, S. and Pawlowski, P., “PSO algorithm for UAV autonomous path planning with threat and energy cost optimization,” in Proc. SPIE 11055, XII Conference on Reconnaissance and Electronic Warfare Systems, 110550T (2019). https://doi.org/10.117/12.2524886 Google Scholar

[19] 

Poli, R., “Analysis of the Publications on the Applications of Particle Swarm Optimisation,” Hindawi Publishing Corporation, Journal of Artificial Evolution and Applications, (2008). https://doi.org/10.1155/2008/685175 Google Scholar

[20] 

Sabatino, F., “Quadrotor control: modeling, nonlinear control design, and simulation,” Master’s Degree Project, KTH Electrical Engineering, Sweden(2015). Google Scholar

[21] 

Kraszewski, T. and Czopik, G., “Nonlinear Kalman filtering in the presence of additive noise,” in Proc. SPIE 10418, XI Conference on Reconnaissance and Electronic Warfare Systems, 104180N (2017). https://doi.org/10.1117/12.2269355 Google Scholar

[22] 

Elkholy, M. H., “Dynamic Modeling and Control of a Quadrotor using Linear and Nonlinear Approaches,” Thesis, American University in Cairo, (2014). Google Scholar

[23] 

Konatowski, S. and Pawlowski, P., “Application of the ACO algorithm for UAV path planning,” Przeglad Elektrotechniczny, 95 (7), 115 –118 (2019). https://doi.org/10.15199/48.2019.07.24 Google Scholar
© (2020) COPYRIGHT Society of Photo-Optical Instrumentation Engineers (SPIE). Downloading of the abstract is permitted for personal use only.
Piotr Pawłowski and Stanisław Konatowski "Linear controller design with the use of PSO algorithm for UAV trajectory tracking", Proc. SPIE 11442, Radioelectronic Systems Conference 2019, 114420Z (11 February 2020); https://doi.org/10.1117/12.2565129
Advertisement
Advertisement
RIGHTS & PERMISSIONS
Get copyright permission  Get copyright permission on Copyright Marketplace
KEYWORDS
Unmanned aerial vehicles

Particle swarm optimization

Particles

Detection and tracking algorithms

Matrices

Control systems

Mathematical modeling

Back to Top