Abstract

This paper presents the method to solve the problem of path planning for an unmanned aerial vehicle (UAV) in adversarial environments including radar-guided surface-to-air missiles (SAMs) and unknown threats. SAM lethal envelope and radar detection for SAM threats and line-of-sight (LOS) calculation for unknown threats are considered to compute the cost for path planning. In particular, dynamic SAM lethal envelope is taken into account for path planning in that SAM lethal envelope does change its direction according to the flight direction of UAV. In addition, terrain masking, nonisotropic radar cross section (RCS), and dynamic constraints of UAV are considered to determine the cost of the path. An improved particle swarm optimization (PSO) algorithm is proposed for finding an optimal path. The proposed algorithm is composed of preprocessing steps, multi-swarm PSO algorithm, and postprocessing steps. The Voronoi diagram and Dijkstra algorithm as preprocessing steps provide the initial path for the multi-swarm PSO algorithm which uses multiple swarms with sub-swarms for the balance between exploration and exploitation. Postprocessing steps include waypoint insertion and 3D path smoothing. The computation time is reduced by using the map generation, the coordinate transformation, and the graphic processing unit (GPU) implementation of the algorithm. Various simulations are carried out to compare the performance of the proposed method according to the number of iterations, the number of swarms, and the number of cost evaluation points. The -test results show that the suggested method is statistically better than existing methods.

1. Introduction

In this paper, we propose the method to solve the problem of path planning for an unmanned aerial vehicle (UAV) in adversarial environments where there are radar-guided surface-to-air missiles (SAMs). The problem needs realistic models which take many aspects into consideration related to the hostile environments. They include dynamic SAM lethal envelope, radar detection, and unknown threat. In particular, we take into account terrain masking, nonisotropic radar cross section (RCS), and dynamic constraints of UAV when computing the cost for those hostile environments. There are few papers integrating all these aspects together. This paper suggests the improved particle swarm optimization (PSO) algorithm to offer an optimal path which can take these realistic models into consideration.

These days, UAVs are widely used in broad areas such as commercial and military applications [1, 2]. Path planning is definitely one of the main technologies that UAVs require [3]. The objective in UAV path planning is to complete a given mission while maximizing the safety of UAV until the mission is completed [4]. In military applications, there exist a lot of threats in route of the UAV. These threats include a SAM, a radar, and so on. Thus, the UAV path planning requires the route for avoiding these hostile threats to arrive at the target safely.

As a related field, robot path planning is for finding an optimal path to avoid a collision. This obstacle avoidance is the main purpose for the robot path planning. UAV path planning shares much in common since threats can be treated as obstacles. The similarity in both areas can make the path planning algorithms in robot applications applicable to UAV path planning. However, there is a main difference between robot path planning and UAV path planning in that UAV path planning needs vehicle dynamic constraints [5]. UAV must maintain a certain velocity while flying. It means that sharp turns are not allowed because of dynamic constraints.

Although the current literature on UAV path planning does not consider the realistic models altogether, there are various papers which take each or several aspects into account. Terrain masking which is important for the survivability of UAV is considered in References [6, 7]. Nonisotropic RCS is taken into account in References [811]. Numerous path planning algorithms have been proposed. One category of path planning algorithms is graph-based method. This method include the A and D lite algorithm [1215] and Voronoi diagram method [16, 17]. Metaheuristic optimization methods are another path planning algorithms. Among them, simulated annealing [18], ant colony [6], genetic algorithm [1924], and PSO [3, 20, 22, 25, 26] algorithms have been widely used for path planning. In terms of implementing dynamic constraints of UAV, GA and PSO algorithms are preferable to the graph-based algorithms.

This paper deals with the path planning problem for UAV under the hostile environments of radar-guided SAMs. It is distinguished from the current literature in that dynamic SAM lethal envelope is considered in addition to radar detection and terrain masking is taken into consideration for computing the cost of radar detection and unknown threats. Dynamic SAM lethal envelope means that SAM lethal envelope changes its direction according to the flight direction of UAV. No previous works have dealt with dynamic SAM lethal envelope in calculating the threat cost of the SAM. We also take terrain masking into consideration. When UAV is under adversarial environments, UAV needs to fly as low as possible to minimize the detection by a radar. In that case, terrain masking is an important factor to increase the survivability of UAV. Terrain masking is considered in two kinds of calculations. One is to determine whether a radar can detect UAV and the other is line-of-sight (LOS) calculation to consider the unknown threats. Unknown threats may exist somewhere in the UAV route. If UAV is visible on the ground or UAV is not obscured by terrain, it may be shot down by those unknown threats. Therefore, the more visible UAV is around its location, the riskier UAV is at that location. In addition to dynamic SAM lethal envelope and terrain masking, the nonisotropic RCS of UAV is considered in calculating radar detectability. RCS changes dramatically depending on the attitudes of UAV. RCS as well as terrain masking affects the cost for radar detection.

In this paper, we propose the path planning method using an improved PSO algorithm, which is composed of preprocessing steps, multi-swarm PSO algorithm, and postprocessing steps. As preprocessing steps, the Voronoi diagram and Dijkstra algorithm are utilized to generate the initial path. Preprocessing steps are particularly effective for test cases where it is difficult to find an optimal path. The multi-swarm PSO algorithm use multiple swarms with a lot larger population size than traditional PSO algorithms thanks to graphic processing unit (GPU) implementation so that fast convergence is possible with a balance between exploration and exploitation. Various maps such as the flight altitude map, the terrain masking map, and the 3D LOS map are constructed, and the coordinate transformation is carried out to reduce the computation time. Postprocessing steps include the waypoint insertion and the path smoothing for decreasing the vulnerability due to the threats by inserting a waypoint. The results for various test cases are analyzed and compared with those of other PSO algorithms.

The remainder of this paper is as follows. UAV and threat modeling is described in Section 2. The path planning method is proposed in Section 3. In Section 4, the simulation parameters, results, and discussions in comparison to those of the existing methods are described. Finally, the conclusions are provided in Section 5.

2. UAV and Threat Modeling

2.1. UAV Modeling

The level flight with a constant velocity between waypoints is assumed for UAV. The waypoints are used to construct a simplified path of UAV. They are the reference points which provide the position information for UAV. The altitude of UAV is maintained between the neighboring waypoints. When the horizontal path is determined, the altitude of UAV is determined according to the horizontal path. Safety margin is also considered to avoid ground collision when determining the altitude of UAV. Dynamic constraints of UAV are implemented using the minimum turning radius () and the turning angle (). The minimum turning radius is determined by the flight characteristics. The turning angle represents the angle between the two adjacent segments along the path of UAV. Sharp turns can be controlled using the turning angle as a dynamic constraint of UAV. Figure 1 shows the coordinates, path, and dynamic constraints of UAV mentioned above.

The coordinate transformation is carried out to reduce the computation time for the PSO algorithm as shown in Figure 2 [3, 27]. In a new coordinate system, the axis lies in a line from a starting point () to a destination () and the axis is perpendicular to the axis. A straight line is uniformly divided into () segments. is the number of waypoints (). The length of equally distributed segments is defined as , and the coordinates of each waypoint can be represented in a new coordinate system using the following equations.

Then, the waypoints to be determined can be expressed as in 1D rather than both and positions. The segment length between two adjacent waypoints can be obtained using the following equation. where . and become and , respectively. and are positions of and . Therefore,

The heading angle () for in a new coordinate system can be expressed using the following equation. where . is the four-quadrant inverse tangent.

The turning angle can be expressed using the following equation. where . can have a value from 0 to .

Nonisotropic RCS of UAV is modeled. RCS is dependent on the position and attitudes of UAV relative to the radar. RCS is used to calculate the radar detectability. RCS values used in this paper are discussed in detail in Section 2.2.

2.2. Threat Modeling

Threat modeling is composed of 3 parts. SAM lethal envelope and radar detection are two components for SAM threats. The other is the unknown threat of which location is not known when the path is planned.

SAM lethal envelope is the launch envelope which is drawn from calculating the probability of kill at the position of UAV at the time of SAM launch. SAM lethal envelope is assumed to be elliptical, and the SAM is located at a focus of the ellipse. For a stationary target, a circular shape can be used for SAM lethal envelope. For a fast moving target such as UAV, SAM lethal envelope as a launch envelope can be modeled as an ellipse. In this paper, dynamic SAM lethal envelope is taken into account in that the envelope changes its direction in terms of the heading of UAV. The probability of kill usually becomes lower when the offset of a UAV flight trajectory from the SAM site gets larger. One of the reasons for low probability of kill is that more maneuver of SAM is needed for a large offset. In Figure 3, we see that the semimajor axis of the elliptical envelope is parallel to the flight direction of UAV. If the flight direction of UAV is changed, the envelope also changes the direction while the location of the SAM is fixed at the original place. Once UAV is within the SAM lethal envelope, the cost of SAM engagement is added to the total cost. Of course, if UAV is out of the envelope, there is no cost induced from the envelope.

The locations of the SAM and the radar are assumed to be known and located at the same place. Radar detection signal is inversely proportional to the 4th power of the distance between the radar and UAV. The altitude of UAV as well as the horizontal path is considered in calculating the cost of radar detection. Terrain masking is utilized to maximize the safety of UAV. Once the horizontal path is determined, the altitudes of UAV according to that horizontal path are determined automatically assuming the level flight with a constant velocity between two neighboring waypoints. This altitude is determined by the path planner considering the safety margin of UAV flight.

The cost for unknown threats is calculated from LOS calculation. When UAV is visible from the ground near UAV, it can be in danger due to possible threats. LOS calculations are conducted from the ground regions within a specified distance from UAV. The exposure density of UAV from the ground regions using LOS calculations is converted to the cost for unknown threats. Terrain masking is considered in both cost calculations of radar detection and LOS for unknown threats. When UAV flies through the valley, the cost for unknown threat will be low due to terrain masking.

Threat costs for traveling along the path include SAM lethal envelope, radar detection, and LOS calculation at the same time. Integration of the cost over the entire path would be needed for exact calculation of total cost. However, we compute the cost at cost evaluation points along an entire path and consider the distance between the points for calculating total costs. This approximation is used considering a long distance of UAV path and the computation time. The number of cost evaluation points in a segment is determined as a constant, and it is the same for all segments. Figure 4 shows two segments as a part of the path where denotes the UAV position to calculate the threat cost and stands for a SAM site. which is the distance between two adjacent cost evaluation points is the distance between UAV positions and along a path. denotes the distance between UAV location and the th radar.

The cost of total threats including SAM-related threats and unknown threats is the summation of three components when all the turning angles as dynamic constraints are greater than a threshold. Otherwise, the penalty cost () which is a very high value is given for the path which does not satisfy dynamic constraints. Total threat cost is calculated as a summation over cost evaluation points and SAM sites using the following equation. where is the cost of SAM lethal envelope at the UAV location due to the th SAM. is a constant for the cost of radar detection. is the value for terrain masking. denotes the RCS value of UAV. is a constant for the cost of LOS calculation. and denote the number of ground positions where UAV is visible and the number of total ground positions where LOS calculations are conducted for the UAV location , respectively. denotes a threshold for the turning angle.

represents whether UAV is masked by the terrain from a radar. If UAV is not masked by the terrain, the value becomes 1 and the radar equation is applied for calculating the cost of radar detection. If UAV is masked, the value is 0. RCS values are calculated from widely accepted approximation for the ellipsoid as shown in the following equation [28]. The parameters , and are selected in such a way that RCS is relatively small when viewed from the front or tail side but RCS is relatively large when viewed from the side or below [9]. Figure 5 shows RCS for the ellipsoid, which varies according to and . The positions of UAV relative to a radar and UAV heading are used for calculating RCS. A pitch and a bank angle of UAV are assumed to be zero. where denotes the angle between UAV’s heading and the direction to a receiving radar. denotes the angle between the wing axis of UAV and the projected line of a receiving radar on the plane of the wing and the tail axis.

The cost for unknown threats is calculated from LOS calculations from the ground region near UAV. LOS calculations are conducted at the ground positions within a specified distance around the position of UAV. When UAV is visible from all ground positions, becomes , which is the maximum value for the cost of unknown threats.

In Figure 6, the total costs for two different UAV headings are shown. SAM lethal envelope changes its direction according to the heading of UAV. The cost of radar detection is computed considering terrain masking and RCS. To determine whether UAV is masked by the terrain for each radar, the terrain masking map is generated. The terrain masking map for radar detectability is generated for every radar, and it contains the maximum altitude of UAV below which UAV can be masked by the terrain for a certain radar. The costs of SAM lethal envelope and radar detection are computed once a path is generated since SAM lethal envelope changes its direction according to the heading of UAV. The cost of radar detection depends on the nonisotropic RCS of UAV, which changes according to the attitude of UAV. LOS calculations should be carried out for the altitudes as well as the horizontal positions of UAV. Figure 7 shows the 3D LOS map for several different altitudes and a stack of LOS maps which are used to compute the vulnerability of UAV for unknown threats. UAV with lower altitude is less vulnerable to unknown threats as shown in Figure 7. Safer areas are represented in blue colors. The terrain masking map and the 3D LOS map which take long time for calculation are precomputed for the region of interest.

3. Path Planning Method

3.1. The Traditional and Standard PSO Algorithms

PSO is a population-based stochastic algorithm which is inspired by social behavior of birds and fishes [29, 30]. It combines self-experience with social experience. The particles are randomly initialized at first. Then, they search for the solution space based on the position and the velocity update. Each particle has a position and a velocity.

where denotes the dimension of the particle, which is the number of variables. is a set of waypoint positions.

Each particle keeps track of individual best and global best of all particles. and denote the individual best and global best vector, respectively.

Fitness functions are evaluated for each particle, and and are determined after an iteration. Then, the velocity and the position are updated according to the following equations. where is the iteration number. , , and denote the inertia weight, the individual learning coefficient, and the global learning coefficient, respectively. and are vectors of random values which range from 0 to 1.

Fitness function evaluations and the update of the velocity and the position are iterated until the criteria are met. The above traditional PSO algorithm can be implemented easily, and it needs a few parameters. It can be utilized for solving the problem of UAV path planning. However, it may be possible that the algorithm converges prematurely or falls into local optima.

In contrast to the traditional PSO algorithm, the standard PSO algorithm was proposed in [31]. Among some differences between these algorithms, there are two major differences. In the standard PSO algorithm, a ring topology is used rather than a global topology in the traditional PSO algorithm. In a global topology, every particle shares information from the best particle in the entire swarm. However, in a ring topology, a particle can communicate with only two neighboring particles. This enables the algorithm to escape from a local optimum. The other distinction of the standard PSO algorithm from the traditional PSO algorithm is the introduction of a constriction factor . For >4, the convergence is guaranteed [31]. The following equations are used in the standard PSO algorithm. where is a local best vector.

3.2. The Proposed PSO Algorithm

Figure 8 shows the flowchart of the proposed PSO algorithm to find an optimal path for UAV. Whole processes are composed of 3 stages which are preprocessing steps, multi-swarm PSO algorithm, and postprocessing steps. The flight altitude map, the terrain masking map, and the 3D LOS map are prepared in advance. The process starts by assigning the parameters containing a starting point and a destination. As preprocessing steps, the Voronoi diagram and Dijkstra algorithm are conducted to produce the initial path for the PSO algorithm. Then, the coordinate transformation is done to accelerate the searching speed. The multi-swarm PSO algorithm searches for an optimal path with iterations based on transformed coordinates. It differs from the traditional and standard PSO algorithms in that many particles are used and new topology for PSO is suggested. Whole particles are decomposed into multiple swarms which contain sub-swarms. A global topology is used within a sub-swarm, and a ring topology is used between sub-swarms so that fast convergence can occur with a balance between exploration and exploitation. Postprocessing steps start by transforming the coordinates back into the original coordinates. Then, the waypoint insertion and the path smoothing are conducted as postprocessing steps.

Preprocessing steps are for generating an initial path which is utilized to initialize the particles in one sub-swarm. The particles initialized from preprocessing steps start to search near the initial path, and the particles of the other sub-swarms start the search in a random fashion. The advantage of the initialization is that the PSO algorithm can have better chances to find an optimal path with less iterations. The Voronoi diagram and Dijkstra algorithm which are simple and fast path planning algorithms are used to produce a path in a fast and reliable way. The optimization criterion is the same as the one which is used for the multi-swarm PSO algorithm. The cost calculation for the Dijkstra algorithm is based on the threat modeling in Section 2. Figure 9 shows two initial paths generated from the Voronoi diagram. In Figure 9(a), only SAM sites are used for obtaining Voronoi edges. The optimal path obtained by using only SAM sites is generated between SAM sites. There may be cases where a path is better away from SAM sites not between SAM sites. Therefore, virtual points in addition to the SAM sites are used to construct Voronoi edges as shown in Figure 9(b). These virtual points are generated by adding more points to make an initial path which can keep a safe distance from SAM sites. The path generated by using virtual points and SAM sites is provided as initial values for the PSO algorithm. The path from the preprocessing steps is adapted to produce an initial path for the PSO algorithm using the 1D interpolation method.

The multi-swarm PSO algorithm is different from other PSO algorithms in several aspects. Many particles are used in the algorithm, and a whole population is composed of multiple swarms. Each swarm has many sub-swarms. A global topology is used within each sub-swarm, and a ring topology is used between the two adjacent sub-swarms. By using the combined topologies, fast convergence is possible with a balance between the exploration and the exploitation. There is no data communication between the swarms. Figure 10 shows the topologies used in the multi-swarm PSO algorithm. A large number of particles are exploited for the multi-swarm PSO algorithm. All the particles can be updated simultaneously at each iteration using the vectorization. The number of cost evaluation points should be the same for all segments since all cost tables should be vectorized for parallel computing. The distance between adjacent cost evaluation points for all segments is computed and used for cost calculations. GPU parallel computing technologies can decrease the computation time effectively for massively parallel computations [32].

We have two steps for postprocessing steps. The first step is the waypoint insertion to decrease the vulnerability due to the threats. The other step is 3D path smoothing. Waypoint insertion is implemented in such a way that a long segment is divided into two segments by inserting a new waypoint. If a segment length is larger than two times of the minimum segment length, a waypoint is added. The minimum segment length is a constant value which is determined by the flight characteristics, and the length of every segment along a path should be larger than this value. A new waypoint is determined within the intersected area by two circles whose radius is twice of the minimum segment length. Then, the size of two new segments becomes less than the radius of the circle so that another waypoint insertion will not be necessary for newly added segments. There are 221 candidate waypoints which are constructed by a rhombus within the intersected area as shown in Figure 11. All the candidate waypoints are evaluated by the same cost functions used in the PSO, and the waypoint with the least cost is chosen for a waypoint insertion. Dynamic constraints are also considered in cost evaluations. Figure 12 shows an example for waypoint insertion. New segments which are indicated as red lines are determined by inserting a waypoint.

The other postprocessing step is 3D path smoothing. The minimum turning radius which can be determined by the flight characteristics is used for the turn. The midcourse guidance law [33] is used for ascending and descending flights. An ascending or descending trajectory is determined according to a downrange distance (), flight path angles (, ), and an altitude change () as shown in Figure 13.

A trajectory can be described as a third polynomial as a function of a downrange distance as follows.

When both flight path angles are zeroes, a trajectory is expressed in a simple form.

If small angle assumption and a constant velocity () are applied to the above equation, an acceleration command () can be derived. When is zero or R, a maximum acceleration command () is needed. Finally, a minimum required downrange distance is determined as a function of an altitude difference, a velocity, and a maximum acceleration command.

This minimum downrange distance is required to avoid ground collisions for an ascending or descending trajectory. The minimum downrange distance is determined by the flight characteristics. Figure 14 shows the ascending or descending trajectory for 3D path smoothing. When UAV is ascending, it finishes ascending at the waypoint to avoid the ground collisions. On the other hand, it starts to descend at the waypoint when it is descending. Minimum segment length should be at least two times larger than the required downrange so that a certain segment can contain both ascending and descending trajectories.

Several methods for reducing the computation time are proposed in this paper. In general, the computation time of the PSO algorithm is longer than that of other fast algorithms. To compensate this computation time, the maps are generated beforehand. There is the flight altitude map which is needed to calculate the UAV altitude once horizontal positions are defined. If the SAM sites are defined, the terrain masking map for each radar can be constructed. These two kinds of maps are produced according to horizontal positions on a rectangular grid. The values at a specific position are calculated using the interpolation of the map values. The terrain masking map and the flight altitude map are used for calculating the radar detection cost. The 3D LOS map is generated using the terrain according to the altitude as well as horizontal positions.

Another technique to reduce the computation time is the coordinate transformation which decreases the dimension of PSO. As introduced in Section 2, the coordinate transformation can simplify the computation process by reducing the number of variables used in the PSO algorithm.

4. Simulation Results and Discussions

4.1. Simulation Parameters

The parameters regarding UAV, threats, and the PSO algorithm are described in this section. The level flight with a constant velocity for each segment along the path is assumed so that UAV flies 0.15 km above the maximum altitude of terrain for each segment. As shown in Table 1, the velocity and the minimum turning radius of UAV are assumed to be 0.2 km/sec and 2.35 km, respectively. The minimum segment length is 5 km, which is two times larger than the required downrange distance when the maximum altitude change between the waypoints is assumed to 0.5 km. Sharp turns at the waypoint less than radians are not allowed as dynamic constraints of UAV. The penalty cost is 105 when dynamic constraints are not satisfied. Table 2 shows the starting point and the destination in two sorts of test cases, which are short-range test cases and long-range test cases. Each test case includes 10 different configurations of SAM sites.

Table 3 shows the parameters of SAM. The number of SAM sites is 20, and their locations vary for each test case. The cost is computed based on three parts which are SAM lethal envelope, radar detection, and the 3D LOS map. In this paper, SAM lethal envelope is assumed to have an elliptical shape, which changes the direction of the semimajor axis according to the flight direction of UAV. In addition, it is assumed that the cost has the value of 100 when UAV is within the envelope. The cost for radar detection is inversely proportional to the 4th power of the distance away from the SAM site. The cost of radar detection for each threat is limited by a value of 100. The maximum value () for the cost of the 3D LOS map is also 100. If we combine all the costs, we can calculate the cost which is used for determining the path.

The simulation parameters for PSO are specified in Table 4. The number of waypoints is 20 or 40 depending on the short-range or long-range test case, which is also the number of particle dimension. The total number of particles for a single swarm and the number of iterations are 50 and 1000, respectively, if they are not specified in the simulation results. The number of sub-swarms for a swarm is 5. This means that 10 particles are present for each sub-swarm since the total number of particles is 50. When multiple swarms are used, the total number of particles is the number of swarms multiplied by 50. The constriction factor as well as the individual learning coefficient and the global learning coefficient is given in the table.

4.2. Simulation Results

The proposed PSO algorithm with only one swarm as well as the traditional and standard PSO algorithms is implemented to compare the results. The number of particles is 50. Multi-swarm results are discussed later in this section. An initial path for the proposed PSO algorithm is generated by using the Voronoi diagram and Dijkstra algorithm, and it is used to initialize the particles of one sub-swarm so that other sub-swarms are not affected by the preprocessing steps. The simulations are carried out for 20 different test cases where the locations of SAM sites are chosen differently. Monte Carlo simulations for each PSO method are conducted for 50 times by changing the random numbers for each test case. We analyze the performance of the proposed PSO algorithm as a function of the number of iterations. The performance is calculated from the cost relative to the minimum cost out of the all PSO algorithms for each test case. The minimum cost for each test case is obtained from 50 Monte Carlo simulation results after 1000 iterations. Therefore, the maximum value of the performance is 1.

In Figure 15, the performance results are compared for the deterministic method, the traditional PSO, the standard PSO, and the proposed PSO algorithms. Average performances are represented for short-range test cases and long-range test cases. The proposed PSO algorithm shows fast convergence and better results with exploration and exploitation balance. The preprocessing steps are effective particularly for test cases where it is difficult to overcome a local optimum. The postprocessing steps are efficient for a path with long segments. The postprocessing steps affect a path for 8 test cases of short-range and 10 test cases of long-range. We do not need many iterations to reach a satisfactory performance using the proposed PSO algorithm, and the computation time can be also saved. At 200 iterations, the average performance of the proposed PSO algorithm is 0.93 and 0.92 for short-range test cases and long-range test cases, respectively. On the contrary, the traditional PSO algorithm converges prematurely and does not get better with more iterations. The standard PSO results show that the performance gets better with more iterations while the performance is poor with less iterations. The traditional and standard PSO algorithms suffer more on the long-range test cases with 40 variables. Therefore, the results indicate that the proposed algorithm shows much better performance than the other algorithms even though the iterations of the proposed method are much less.

Figure 16 shows the effect of preprocessing steps. All 3 PSO algorithms are initialized by a path from preprocessing steps. A single swarm with 50 particles is used. The difference is mainly from the topologies used in the PSO algorithms. The performance is improved by the initialization from the Dijkstra algorithm for all PSO algorithms. The proposed algorithm shows better results for both short-range and long-range test cases than the other algorithms in terms of the average performance. As we can see in the figure, the traditional PSO algorithm with global topology shows the fastest convergence. Premature convergence can occur so that the performance is not good enough. On the other hand, the standard PSO algorithm with a ring topology shows the slowest convergence. The performance gets better with more iterations. The proposed PSO algorithm shows the convergence in between two other algorithms.

Table 5 compares the statistical results at 200 iterations from the proposed PSO algorithm, the standard PSO algorithm, the traditional PSO algorithm, and the deterministic method which uses the Voronoi diagram and Dijkstra algorithm. The proposed PSO algorithm shows better results than the other two PSO algorithms and the deterministic method for all the test cases in terms of the mean cost and the standard deviation. In particular, we see that the standard deviations of the proposed method are much smaller than those of the other two methods for the long-range test cases where it is more difficult to find solutions. Statistical difference between the proposed PSO algorithm and the standard PSO algorithm is tested using independent -tests. The -test results show that the proposed method is statistically different from the standard PSO for all the test cases since values are significantly less than 0.05. The number of Monte Carlo simulations in which dynamic constraints are not satisfied is shown in parenthesis next to the standard deviations. Dynamic constraints are not satisfied at least one time for all the cases of the traditional PSO algorithm. The standard PSO results are worse for the long-range test cases. The dynamic constraints are not satisfied for test case #2 of long-range even though the proposed PSO algorithm is used.

We plot 50 Monte Carlo simulation paths for each test case to show the consistency of the results. In Figure 17, the best paths for each test case are plotted for the proposed PSO algorithm and the standard PSO algorithm at 200 iterations. The standard PSO results (blue lines) show quite different paths from each other. However, the proposed PSO results (red lines) show very similar paths which are guided by the preprocessing steps. In Figure 18, the effectiveness of the preprocessing steps is more significant for long-range test cases where it is more difficult to find an optimal path with more variables.

Even though the results are quite promising for the proposed PSO algorithm using only a single swarm with 50 particles, there could be some cases which do not satisfy the dynamic constraints. In addition, there are differences in results due to the random numbers which are used for PSO algorithm itself when we can see the Monte Carlo simulation results. The multi-swarm PSO algorithm can ease these problems and increase the performance better. Table 6 shows the relations between the number of swarms and the total number of particles used for the multi-swarm PSO algorithm. A swarm consists of 50 particles, and the total number of particles is 2000 for 40 swarms. Figure 19 shows the performance results according to the number of swarms used in the simulations at 200 iterations. The results of the deterministic method and the traditional PSO and the standard PSO algorithms are compared with those of the proposed PSO algorithm. For both short-range and long-range test cases, we see the better results with more swarms for all PSO algorithms. The results are improved even more for the traditional PSO and the standard PSO algorithms with more swarms. The proposed PSO algorithm can also improve the performance and reduce the possibility of the cases which do not satisfy the dynamic constraints. The average performance of the proposed PSO algorithm with 10 swarms is 0.97 and 0.96 for short-range test cases and long-range test cases, respectively. In addition, the variance of the performance due to the randomness in the PSO algorithm can be reduced significantly. The increase of the computation time as a disadvantage of using multiple swarms can be moderated using the vectorization and the parallel computing.

The cost is analyzed in terms of the number of cost evaluation points between two adjacent waypoints. The computation time is increased with more cost evaluation points. Less cost evaluation points may not consider the effects of the SAM sites properly. Figure 20(a) shows the boxplots of the cost ratio in percentage according to the number of cost evaluation points for 2000 different paths. The cost ratio is defined as the total cost for a certain number of cost evaluation points divided by the total cost for 100 cost evaluation points. The cost ratio is set as 100% when the number of cost evaluation points is 100. The average value of the cost ratio approaches 100% for larger cost evaluation points. The average cost ratio is 97% for 10 cost evaluation points, which is pretty similar to the result of 100 cost evaluation points. Figure 20(b) shows that the computation time ratio is 1.17 and 3.37 for 10 and 100 cost evaluation points when the elapsed time ratio is 1 for 2 cost evaluation points. Therefore, optimal cost evaluation points can be determined in terms of the cost ratio and the elapsed time ratio.

The path considering dynamic SAM lethal envelope which changes the direction of the semimajor axis according to the flight direction of UAV is different from that of static SAM lethal envelope. Figure 21 shows the path comparison between the dynamic and static SAM lethal envelopes. Static SAM lethal envelope is assumed to be parallel to the line connecting the starting point and the destination. Although the UAV position of A or B along the path for dynamic SAM lethal envelopes is within static SAM lethal envelope, UAV is actually not located within dynamic SAM lethal envelope as indicated in red dots.

The elliptical shape of SAM lethal envelopes is assumed in the simulations. How can we implement SAM lethal envelope if it has an arbitrary shape rather than an ellipse? If SAM lethal envelope cannot be defined using the equation due to a complex shape, the maps describing SAM lethal envelope can be used instead of the equation. The maps should be generated for various headings of UAV since SAM lethal envelope changes its direction according to the flight direction of UAV. The computation time for path planning can be reduced when the maps are prepared in advance.

5. Conclusions

The method to find an optimal flight path for UAV in adversarial environments is presented in this paper. Hostile environments include SAM lethal envelope, radar detection, and unknown threats. Dynamic SAM lethal envelope is assumed to have an elliptical shape and changes its direction according to the heading of UAV. Terrain masking, RCS, and dynamic constraints of UAV are taken into account to calculate the cost for path planning. The improved PSO algorithm is suggested by using preprocessing steps, multi-swarm PSO algorithm, and postprocessing steps. Preprocessing steps use the Voronoi diagram and Dijkstra algorithm to generate an initial path which is informed to the particles in one sub-swarm. The multi-swarm PSO algorithm differs from other PSO algorithms in that many particles are decomposed into multiple swarms for parallel computing. Each swarm has sub-swarms so that a good balance between exploration and exploitation can be achieved. In postprocessing steps, a new waypoint is inserted for a long segment to decrease the vulnerability even more. Finally, 3D waypoint smoothing is carried out by using the midcourse guidance law. The computation time for the proposed PSO algorithm is reduced by using the map generation, the coordinate transformation, and the GPU implementation.

The results show that the suggested method is better than existing PSO algorithms in terms of the mean cost and the standard deviation. The average performance of the proposed PSO algorithm with a single swarm at 200 iterations is 0.93 and 0.92 for short-range test cases and long-range test cases, respectively. The performances with 10 swarms become 0.97 and 0.96 while satisfying all the dynamic constraints. The path generated by using dynamic SAM lethal envelope which is a more realistic model is different from that of static SAM lethal envelope.

Data Availability

The data used to support the findings of this study are available from the corresponding author upon request.

Conflicts of Interest

The authors declare that they have no conflicts of interest.