Keywords

1 Introduction

The development of Autonomous Unmanned aerial vehicles (UAV) is of high interest to many researchers in recent years due to its diverse application in both military and civilian environment [1]. Some widely used applications are surveillance, search and rescue, disaster management, target search, goods delivery, wildlife research, etc. [2]. Path planning is an indispensable part of an autonomous UAV system and aims to find the optimum path from start point to end point while satisfying the required constraints such as distance, time, power consumption, safety, etc. Path planning algorithm can be classified as offline and online. In offline path planning, an optimized path is planned before UAV fly for the known destination. On the other hand, online path planning aims to generate a dynamic path on the basis of offline reference path and real-time data of the track [3]. In this work, we considered offline path planning. In conventional path planning problem, one of the basic parameter used to calculate the best path is using the minimum distance traveled like as Traveling Salesman Problem (TSP). But constraints such as obstacle, average altitude, maximum turning angle, etc. is considered in UAV path planning. Therefore the problem becomes complex and characterized as a multi-objective optimization problem [4].

Meta-heuristic methods have been evolved to solve multi-objective optimization problem more efficiently than other available methods such as classical method, heuristic method, etc. [5]. PSO is a nature-inspired population-based meta-heuristic approach that has gained much attention in solving multi-objective optimization problems [6]. PSO deals with a set of solutions inspired by a group of an agent called particle [7]. The major advantages of using PSO are: (a) computationally inexpensive; (b) simple and easy implementation; (c) minimum interaction between particles as it uses its local best and global best information to calculate the new position; and (d) distributed processing as no mutation operation is required to generate the next generation of solution [8]. However, one of the major issues of PSO is the lack of diversity in the particle. Lack of diversity in the particles causes premature convergence and fall for local minima. As a result, a low quality solution is generated for UAV path planning [9]. In this paper, we focus on this particular problem of PSO in UAV path planning. We presented a modified PSO that produces a better solution for UAV path planning by increasing particles diversity. The main contributions of this work are: (a) We introduced a modified version of PSO named n-PSO; (b) We applied the n-PSO algorithm for UAV path planning with static obstacles in a 3D environment; and (c) We compared the n-PSO with other standard versions of PSO used for UAV path planning.

In the subsequent sections, we first give an overview of existing algorithms. In Sect. 3, we present a detailed mathematical model of the problem. An overview of the proposed model is described in Sect. 4. In Sect. 5, we present the experimental outcome of the proposed model. Lastly, we conclude the paper in Sect. 6.

2 Related Work

In recent years, a number of offline UAV path planning algorithms have been proposed based on PSO. Garcia et al. proposed a distributed PSO algorithm for exploration purpose for a search and rescue mission [10]. In the proposed model, PSO is used to generate the waypoints for the UAVs whereas lawnmower algorithm is used for the exploration task for UAVs. Also a new parameter is introduced instead of \(r_1\) and \(r_2\) to decrease the randomness of the algorithm in order to speed up the searching task of multiple targets. However, the author did not consider the diversity factor of the particles in the algorithm and the algorithm is implemented in a 2D environment without any obstacle. Huang et al. proposed a modified PSO called GBPSO for UAV path planning [4]. A competition strategy is introduced for selecting the global best position that helps to increase the diversity in the particles and speed up the global search process. A variant of PSO named CPSO for 2D offline path planning is proposed in [11]. In the proposed model, chaotic maps such as Singer map is used to determine the values of two basic parameters of PSO i.e. exploration and exploitation which create more diversity among the particles. However, the author did not provide the effect of a chaotic map in the particles diversity. Roberge et al. proposed a mathematical model and a cost function for UAV in a 3D environment and developed a parallel implementation method for UAV path planning [12]. In [9], a modified PSO named vPSO is proposed that uses Gaussian probability density function for mutation strategy in Gaussian mutation based PSO algorithm [13]. The author showed that increased diversity in the particles produces a good quality solution for UAV path planning. In addition, a number of variation of standard PSO have been proposed so far to increase the diversity in the particle for general purpose. A new parameter named constriction factor is introduced to improve the stability of PSO by Clerc [14]. Shi et al. introduced a time-varying inertia weight to improve the particle diversity and to avoid premature convergence [15]. To improve the diversity in the particles Sugathan et al. added a dynamic neighborhood parameter in PSO [16]. However, the author did not explicitly define the parameter and the algorithm is simulated with a general cost function. From the above discussion, we conclude that the effect of particle diversity in generating a good quality solution for UAV path planning requires more research attention. In our work, we introduced a dynamic neighborhood parameter named nhbest that increases the diversity in the particles and generates a better path for an autonomous UAV. We provided a comprehensive comparison with existing well-known versions of PSO used for UAV path planning. i.e. c-PSO [14], w-PSO [15].

3 Mathematical Model

3.1 Unmanned Ariel Vehicle (UAV)

A UAV can be classified as an autonomous robot that can move in a 3-Dimensional Space [17]. Let consider U represent UAV and S is a 3D terrain or search space where the UAV is going to move around at discrete time step t. The UAV at time state t can be expressed in 3-dimensional space and can be presented as \( U_t=(x_t, y_t,z_t)\) where \(x_t\), \(y_t\) represent axis position and \(z_t\) represent the altitude of the UAV at time t. However, the UAV flight dynamics is ignored in this work.

3.2 Environment

Defining the environment is an important part of UAV path planning. In this paper, we considered a 3D environment with multiple spherical static obstacles treated as a no-fly zone (NFZ). The environment is represented in a discrete form in the algorithm [18]. We consider a rectangular matrix \(S \in R^3\) represented by \(X\cdot Y\cdot Z\) where X and Y represent the x-axis and y-axis respectively and Z represent the altitude. Each cell is represented by \(C={x_i,y_i,z_i }\) where \(x_i \in X\), \( y_i \in Y\) and \(z_i \in Z\). The NFZ is represented as follows:

$$\begin{aligned} NFZ = \begin{bmatrix} x_{1} &{} y_{1} &{} z_{1} &{} d_{1} \\ x_{2} &{} y_{2} &{} z_{2} &{} d_{2} \\ \dots &{}\dots &{}\dots &{}\dots \\ x_{n} &{} y_{n} &{} z_{n} &{} d_{n} \end{bmatrix} \end{aligned}$$
(1)

where \(d_i\) represent the diameter of the ith object.

3.3 UAV Path

Path planning refers to generating the waypoints for UAVs. The waypoints are separated by equal time steps [12]. However, the discrete path generated by the algorithm is not follow-able by the UAV dynamics and kinematics. Therefore, the generated path needs to be smoothed before it is fed to the UAV flight controller. In this work, we used basis spline or bspline cubic interpolation formula with smoothing factor 0.2 to smooth the path generated by the algorithm [19]. The path is denoted by a matrix where each row represents the ith waypoint.

$$\begin{aligned} trajectory = \begin{bmatrix} x_{1} &{} y_{1} &{} z_{1} \\ x_{2} &{} y_{2} &{} z_{2} \\ \dots &{}\dots &{}\dots \\ x_{n} &{} y_{n} &{} z_{n} \end{bmatrix} \end{aligned}$$
(2)

3.4 Cost Function

Defining the appropriate cost function is an import part of UAV path planning. The optimization algorithm finds the best solution based on the cost function. Optimization problem like TSP uses path length to find the shortest path that traverses all the cities. In the case of UAV path planning, the problem becomes more complex due to multiple constraints such as shortest path, obstacle avoidance, minimum altitude, sharp turn, etc. The algorithm searches for a solution with minimum cost. In this work, we have considered two constraints for UAV path planning i.e. shortest path and obstacle avoidance. We define our cost function as follows:

$$\begin{aligned} F_{cost}=C_{Path}+ C_{NFZ} \end{aligned}$$
(3)

where \(C_{Path}\) calculates the generated path length and \(C_{NFZ}\) penalize if the path collide with the no-fly zone. The path length is calculated using the following Euclidean distance formula:

$$\begin{aligned} C_{Path}= \sum _{i=1}^{n-1}\sqrt{(x_{i+1}-x_i)^2+(y_{i+1}-y_i)^2+(z_{i+1}-z_i)^2} \end{aligned}$$
(4)

where n is the number of waypoints generated, \(x_i\), \(y_i\), \(z_i\) are the axis position of UAV in 3D space. To evaluate whether the generated path collides with NFZ, we first calculate the distance from each waypoint from the NFZ center. If the distance is less than the diameter of the NFZ, then the function penalize heavily. The \(C_{NFZ}\) function is calculated using the following equations:

$$\begin{aligned} Collide=1-\sum _{i=1}^{n_{NFZ}}\frac{\sum _{j=1}^{n-1}\sqrt{(x_j-NFZ_i^x)^2+(y_j-NFZ_i^y)^2+(z_j-NFZ_i^z)^2}}{d_i} \end{aligned}$$
(5)
$$\begin{aligned} C_{NFZ}=argMax (Collide,0) \end{aligned}$$
(6)

where \(NFZ_i^x\), \(NFZ_i^y\) and \(NFZ_i^z\) are 3D center coordinate of ith NFZ, \(n_{NFZ}\) is total number of NFZ and \(d_i\) is the diameter of ith NFZ.

4 n-PSO for Path Planning

4.1 PSO Framework

PSO is a population-based evolutionary algorithm which was first introduced in [20]. The algorithm is inspired by animal common social behavior found in nature like as birds flock. The basic idea of PSO is as stated: “people learn to make sense of the world by talking with other people about it” [7]. The major advantage of PSO is simplicity and problem-solving ability. Since its introduction, PSO has been used in numerous applications for solving optimization problem. The idea of PSO is a number of candidate solutions called particles are taken into consideration and the position of each particle have been updated on the basis of particle best position (local best) and neighbors or swarms best (global best) position iteratively until all the particles converge to an optimal solution. More precisely we can describe that in PSO each particle has treated as a point in an N-dimensional space. The position of each particle is updated or adjusted on the basis of its flying experience and other particles flying experience. Each particle modifies its position on the basis of the information such as current position, current velocity, distance between particle best positions with the current position and distance between global best positions with the current position [14]. Let P(t) is a population of n particles is a multidimensional space at time step t, where \(P(t)=\{P_1 (t),P_2 (t),\dots , P_i(t),\dots , P_n(t)\}\). \(P_i (t)\) is the ith particle in d-dimensional space at time step t, where \(P_i(t)= \{ X_{i,1}(t),X_{i,2}(t),\dots , X_{i,d}(t)\}\) is ith particle position in d-dimensional space. The velocity of ith particle at time step t can be represented as \(V_i(t)= \{V_{i,1}(t),V_{i,2}(t),\dots , V_{i,d}(t)\}\). As outlined in [7], the equation for calculating the new position of ith particle \(P_i(t)\) are as follows:

$$\begin{aligned} X_i (t+1)= X_i(t)+V_i(t+1) \end{aligned}$$
(7)
$$\begin{aligned} V_i (t+1)= \omega (t)V_i (t)+ c_1 r_1(P_l (t)-X_i (t))+c_2 r_2(P_g (t)-X_i (t)) \end{aligned}$$
(8)

where the terms are as follows:

  • \(V_i(t)\): Particle velocity at time t.

  • \(\omega (t)\): Inertia at time t.

  • \(c_1\) and \(c_2\): Constants that used for personal influence and social influence respectively.

  • \(r_1\) and \(r_2\): Random values between 0 and 1.

  • \(P_l(t)\): Particle local best.

  • \(P_g (t)\): Particle global best.

The value of \(\omega (t)\) is calculated using the following formula:

$$\begin{aligned} \omega (t)=\omega _{max} - t\cdot \frac{\omega _{max}-\omega _{min}}{MaxIter} \end{aligned}$$
(9)

where \(\omega _{max}\), \(\omega _{min}\) and MaxIter are final inertia, initial inertia and maximum number of iterations respectively. The particle local best position and global best position vector is computed using the following equations:

$$\begin{aligned} P_l(t)= {\left\{ \begin{array}{ll} P_l(t-1) &{} \text {if }F_{cost}(X_i(t))\ge F_{cost}P_l (t-1))\\ X_i(t) &{} \text { if }F_{cost}(X_i(t))\le F_{cost}(P_l (t-1))\\ \end{array}\right. } \end{aligned}$$
(10)
$$\begin{aligned} P_g(t)= argmin_{P_l(t)}F_{cost}(P_l(t)) \end{aligned}$$
(11)

4.2 Improved PSO

The two most well-known improvements of PSO are constriction factor PSO (c-PSO) [14] and time-varying inertia weight PSO (w-PSO) [15]. Both these methods are proposed to balance between two important characteristics of PSO algorithm i.e. exploitation and exploration. However, PSO still lacks particles diversity. Diversity in the particles is an important part of PSO in order to produce a good quality solution. In the proposed model called n-PSO, we introduced a new parameter based on the neighborhood approach proposed in [16]. The basic idea of our proposed algorithm is, instead to directly jump into the global best position; the particle creates a dynamic neighborhood and uses the neighborhood best position for exploration. The radius of the neighborhood is initially set to 1 and will increase linearly until all particles become a single neighborhood. As a result, the particles converge to the solution in a distributed manner and able to avoid local minima. The time-varying size of the neighborhood is calculated by the following equations:

$$\begin{aligned} nhsize = nhsize + \frac{N_{pop}}{MaxIt} \end{aligned}$$
(12)
$$\begin{aligned} nhbest_i = min_{P_{nh_i}}F_{cost}(P_{nh_i}) \end{aligned}$$
(13)

where nhsize, \(N_{pop}\) and MaxIt are neighborhood size, total number of population and maximum number of iterations. The neighborhood best position can be calculated by equation no. (13) where \(P_{nh_i}\) is the particle position of ith neighborhood. The proposed algorithm is presented as follows:

figure a

5 Experiment and Discussion

We implemented our algorithm using Python 3.7 in a PC (CPU Core i5 3.3 GHz & RAM 8 GB). In the c-PSO algorithm, we have set the value of constriction factor (k) to 0.729 to generate better result [9]. In the w-PSO algorithm, the range of inertia weight (\(\omega \)) is set from 0.6 to 0.2 [15]. In n-PSO, we kept the similar inertia parameter to incorporate the advantages of w-PSO. The value of \(c_1\) and \(c_2\) were set to 2.05 for c-PSO, 2.0 and 1.5 respectively in w-PSO and n-PSO. We first implemented the algorithm in a 2D environment. Figure 1, shows a 2D UAV path generated by the proposed n-PSO algorithm.

Fig. 1.
figure 1

A 2D UAV path generated by n-PSO algorithm

Table 1. Parameter settings for test cases.

In order to compare the proposed algorithm with the other two algorithms, we have set 10 test cases for the simulation. We run each test cases 5 times for each of the algorithms and calculated the average best cost and diversity. The parameters for the test cases are given in Table 1. The performance of the proposed algorithm is presented in Table 2. In every case, n-PSO have generated a better solution than other two algorithms for UAV path planning. The improvement become more significant for larger search space size, number of iterations and number of populations.

Table 2. Comparison of different algorithm with respect to Best Cost.
Fig. 2.
figure 2

Comparisons of n-PSO with c-PSO and w-PSO with respect to the convergence rate

In Fig. 2, a comparison is presented to show the convergence rate of the algorithms. From the figure, we can see that n-PSO converges slowly compared to both c-PSO and w-PSO. But, eventually it has converged to more accurate solution for an equal number of iterations. In order to measure the particles diversity of the proposed algorithm, we used the following formula proposed by Olorunda [21]:

$$\begin{aligned} Diversity~D(t)=\frac{1}{N_{pop}}\sum _{i=1}^{N_{pop}}\sqrt{\sum _{j=1}^{Dim}(x_{ij}(t)-\overline{x_j(t)})^2} \end{aligned}$$
(14)

where \(N_{pop}\) is the total population size, \(x_{ij}(t)\) is ith particle in j dimension and \(\overline{x_j(t)}\) is average of jth dimension. The value of \(\overline{x_j(t)}\) is can be calculated by following equation:

$$\begin{aligned} \overline{x_j(t)} = \frac{1}{N_{pop}}\sum _{i}^{N_{pop}}x_{ij} \end{aligned}$$
(15)

In Table 3, we presented a comparison of particle diversity between n-PSO with others. It shows that the particles diversity of the proposed algorithm has increased significantly. The dynamic neighborhood approach prevent the algorithm to converge quickly to the global optima and increases the particles diversity. Figure 3 shows a comparison of particles diversity variation with respect to a number of iterations between three algorithms. It shows that the diversity in the particles has increased significantly in n-PSO.

Table 3. Comparison of different algorithm with respect to Best Cost.
Fig. 3.
figure 3

Diversity variation versus no. of iterations

In Fig. 4, we presented a time cost comparison of our proposed algorithm with the other two methods. From the figure, we can conclude that the new parameter did not put any significant computational load to the algorithm. Finally, we implement the n-PSO algorithm in a 3D environment with static obstacles. Figure 5 shows a UAV path generated by n-PSO in a 3D environment.

Fig. 4.
figure 4

Time cost analysis of n-PSO

Fig. 5.
figure 5

An UAV path generated by n-PSO in 3D environment.

6 Conclusion

This paper presents a modified PSO based path planning solution for autonomous UAV in a 3D environment. A dynamic neighborhood-based approach is proposed to increase particle diversity. The improvement of the algorithm is verified with two well-known versions of PSO used for UAV path planning. The result showed that the particle diversity in n-PSO has increased significantly which enable n-PSO to successfully produce better UAV path than c-PSO and w-PSO. Also, the time cost analysis showed that the new parameter in the algorithm has less effect on the total execution time. However, we implemented and tested the algorithm in a small scale environment. Also, more rigorous analysis is required to prove that increased diversity in PSO will guarantee better UAV path which is our future area of interest. In addition to that, real-time path planning in 3D environment is also a key research area of UAV path planning.