Next Article in Journal
A ROS Multi-Tier UAV Localization Module Based on GNSS, Inertial and Visual-Depth Data
Previous Article in Journal
User Preferences in Drone Design and Operation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Modified Mayfly Algorithm for UAV Path Planning

1
College of Computer Science and Engineering, Shandong University of Science and Technology, Qingdao 266590, China
2
Faculty of Electrical Engineering and Computer Science, VŠB-Technical University of Ostrava, 70032 Ostrava, Czech Republic
*
Author to whom correspondence should be addressed.
Submission received: 19 April 2022 / Revised: 8 May 2022 / Accepted: 18 May 2022 / Published: 23 May 2022
(This article belongs to the Section Drone Design and Development)

Abstract

:
The unmanned aerial vehicle (UAV) path planning problem is primarily concerned with avoiding collision with obstacles while determining the best flight path to the target position. This paper first establishes a cost function to transform the UAV route planning issue into an optimization issue that meets the UAV’s feasible path requirements and path safety constraints. Then, this paper introduces a modified Mayfly Algorithm (modMA), which employs an exponent decreasing inertia weight (EDIW) strategy, adaptive Cauchy mutation, and an enhanced crossover operator to effectively search the UAV configuration space and discover the path with the lowest overall cost. Finally, the proposed modMA is evaluated on 26 benchmark functions as well as the UAV route planning problem, and the results demonstrate that it outperforms the other compared algorithms.

1. Introduction

Unmanned aerial vehicles (UAV), as opposed to manned aircraft, refer to unmanned aircraft that can be controlled by remote radio control equipment or airborne computers. UAVs are less expensive and more flexible than manned aircraft, and they can reach difficult or dangerous places for humans to perform tasks. Therefore, UAVs have been widely used in civil and military fields. In the civil field, drones have played an important role in agricultural plant protection environment, aerial photography, express transportation, remote sensing of the oceans, and so on. In the military field, military drones can replace pilots in complex and dangerous missions such as intelligence gathering and reconnaissance surveillance. If the UAV is to complete the above tasks, one of the basic capabilities that the UAV must have is path planning capability [1].
The UAV path planning problem is to plan a collision-free path for the UAV from the starting point to the target point under the given flight conditions and flight environment. The planned path has the minimum cost and satisfies the relevant constraints. This problem can be simply described as an optimization problem with multiple constraints [2], so it is a challenge to traditional optimization strategies. There are already many mature solutions to this problem. In the direction of path planning based on graph search, Ref. [3] uses the A* algorithm for the UAV path planning problem with the goal of taking the least risk and consuming the least amount of fuel. Ref. [4] uses the D* Lite algorithm to plan an efficient path to the fire point for firefighting UAVs. In the direction of path planning based on sampling, Ref. [5] uses a hybrid algorithm combined with the artificial potential field method and the RRT-Connect algorithm for the path planning problem of UAV. Even though the techniques described above are relatively mature in mathematical theory, they are inefficient when working with discontinuous and non-derivative functions [6]. When tackling the UAV route planning problem with many restrictions [7], they are readily trapped into local optimum solutions.
The path planning issue has been demonstrated to be an NP-hard problem, and the problem complexity grows with problem size [8]. When solving NP-hard problems, heuristic algorithms can produce high-quality solutions and are simple to implement. As a result, some well-developed meta-heuristics with good performance have been proposed in recent years, such as the Cuckoo Search algorithm (CS) [9,10], Particle Swarm Optimization (PSO) [11,12,13], Genetic Algorithm (GA) [14,15], Artificial Bee Colony (ABC) algorithm [16,17], Differential Evolution (DE) algorithm [18,19], Grey Wolf Optimizer (GWO) [20,21], Ant Colony Optimization (ACO) algorithm [22,23], etc.
The Mayfly algorithm (MA) [24] is a recently suggested optimization method, which takes the flight and mating behavior of the mayfly as the model. Female and male mayflies make up the entire mayfly population. The movements of the male and female mayflies offer the MA the capacity to conduct local searches, and the procedure of developing offspring through mayfly mating gives the MA global search capability.
At present, research on MA is still relatively small. Inspired by the bare-bones PSO (BBPSO) [25], and then, Juan Zhao [26] proposed the bare-bones mayfly algorithm. The chaotic mayfly algorithm was suggested by Mohamed A. M. Shaheen [27], who used a logical chaotic map to initialize the mayfly population. This paper presented a modified Mayfly Algorithm (modMA), which includes the exponent decreasing inertia weight strategy, adaptive Cauchy mutation, and an enhanced crossover operator to analyze the path planning issue of UAV from the ground station to the destination, and it achieves good results.
Many works on improving two-dimensional paths using metaheuristics have been proposed to this point. Ref. [28] used the bat and cuckoo algorithm in path planning. Ref. [29] used the grey wolf optimizer to tackle the UAV route planning issue. Ref. [30] used a chaotic cuckoo search algorithm to optimize drone paths in two-dimensional (2D) space. Besides, many researchers used other meta-heuristic algorithms to study UAV path planning problems [31,32,33]. However, no one has proposed the use of MA to tackle UAV path planning in a 2D environment. Hence, this paper will use the modified Mayfly Algorithm (modMA) to study this problem. The following are the contributions to this paper.
(1)
It proposes an enhanced crossover operator based on the MA, which can improve MA’s exploration capability and convergence speed. Then it proposes a modified Mayfly Algorithm (modMA), which combines the EDIW strategy, adaptive Cauchy mutation, and the enhanced crossover operator to balance the MA’s processes of exploration and exploitation;
(2)
It introduces three versions of the modMA and compares their performance on six 100 and 300 dimension benchmark functions;
(3)
Compare the three versions of the modified MA with other algorithms (MA, PSO, GWO, BOA) on twenty-six 50 dimension benchmark functions, and analyze the results of the experiments;
(4)
Use the three versions of the modified MA for tackling the 2D path planning problem of agricultural UAV.
This paper is organized as follows: The standard MA, as well as the problem of UAV path planning, are briefly described in Section 2. Section 3 provides three optimization ideas for improving the MA. In Section 4, two experiments are planned to compare the MA’s enhanced performance using different optimization ideas and apply the three versions of the modified MA to the path planning problem of the agricultural UAV. Section 5 concludes.

2. Related Work

This section will provide a quick overview of the standard MA and the two-dimensional path planning problem of UAV.

2.1. Standard Mayfly Algorithm

The proposed MA’s fundamental concept is derived from the flight and mating behavior of mayflies. It combines the advantages of PSO [11], GA [14] and FA [34]. MA initially produces a mayfly population comprising males and females at random. The current velocity and position of the ith mayfly are two n-dimensional vectors, they are denoted as v i = v i 1 , v i 2 , v i n and x i = x i 1 , x i 2 , x i n , respectively. Each mayfly modifies its position depending on its individual best ( p b e s t ) position and the best ( g b e s t ) position found by the whole mayfly swarm thus far.

2.1.1. Male Mayfly Flight

Male mayflies cluster together, which suggests that their positions are updated based on social and personal experience. x i t is defined as the present position of the ith male mayfly at iteration t. Assuming that x i t is the current position of the ith mayfly at iteration t, the position can be updated by adding to a velocity v i t . Thus the male mayfly’s position update formula is:
x i t + 1 = x i t + v i t .
Consider those male mayflies are always performing nuptial dances not far from the water. The male mayfly’s velocity update formula is as follows:
v i j t + 1 = g v i j t + a 1 e β r p 2 p b e s t i j x i j t + a 2 e β r g 2 g b e s t j x i j t ,
where β is the visibility coefficient, a 1 and a 2 are defined as the positive constants representing the attraction. p b e s t i j is the best position obtained by the ith male mayfly in dimension j. r p and r g are the Euclidean distances between x i and p b e s t i and between x i and g b e s t , respectively. The gravity coefficient is given by g, which can be a fixed number between 0 and 1, or it can be steadily lowered over iterations as in Equation (3).
g = g max g max g min i t e r max × i t e r ,
where g max and g min respectively represent the smallest and largest weights. The present and the total number of iterations are given by i t e r and i t e r max , respectively.
The personal best position p b e s t i at iteration t + 1 is determined by Equation (4).
p b e s t i = x i t + 1 , i f f x i t + 1 < f p b e s t i s a m e a s b e f o r e , o t h e r w i s e .
The best male mayflies keep performing up and down motions through different velocities. The velocities of these male mayflies are determined by Equation (5).
v i j t + 1 = v i j t + d × r ,
where the nuptial dance coefficient is given by d, and r means a random value in the range 1 to 1.

2.1.2. Female Mayfly Flight

Female mayflies do not cluster together, however, they move towards male mayflies. y i t is defined as the present position of the ith female mayfly at iteration t. The change of the ith female mayfly in position is calculated as:
y i t + 1 = y i t + v i t .
In the MA, male and female mayflies with the same individual fitness ranking will attract each other, and the female mayfly’s position changes in response to the location of a male mayfly with the same ranking. The female mayfly’s velocity update formula is:
v i j t + 1 = g v i j t + a 2 e β r m f 2 x i j t y i j t , i f f y i > f x i g v i j t + f l × r , i f f y i f x i ,
where v i j t and y i j t are respectively defined as the ith female mayfly’s velocity and position in dimension j at iteration t. a 2 and β are defined as the attraction constant and the visibility coefficient, respectively. r m f is the Euclidean distance between the ith female mayfly and the ith male mayfly, f l is a random walk coefficient which suggests that a female is not attracted to a male, and r means a random value in the range −1 to 1.

2.1.3. Mating Procedure

The mating is represented by the crossover operator which provides the global search capability for the MA. In the MA, male and female mayflies with the same individual fitness ranking will mate with each other to produce offspring mayflies. The mating operation of each pair of male and female mayflies produces two offspring, and the formula for the crossover operator is:
γ 1 = L × m a l e + 1 L × f e m a l e γ 2 = L × f e m a l e + 1 L × m a l e ,
where L means a random value in the range 0 to 1. Moreover, m a l e and f e m a l e denote the parents. Initially, the offspring’s velocity is set to zero.

2.1.4. Mutate the Genes of Offspring

The mutation operator provides partial local search capability for MA. The chosen offspring can be updated by adding a random value to the variable throughout this process, so the offspring are changed to
γ n = γ n + σ N n 0 , 1 ,
where the standard deviation and the standard normal distribution are represented by σ and N n , respectively.

2.1.5. Reduction of Nuptial Dance and Random Walk

Although these operators provide the MA with powerful local search capability, d and f l must be gradually reduced. Both values can be updated over the iterations t using Equations (10) and (11), respectively.
d t = d 0 δ t
f l t = f l 0 δ t ,
where δ is a fixed number between 0 and 1.
As previously stated, Algorithm 1 depicts the MA’s pseudo-code.
Algorithm 1 Pseudocode of MA.
Input: male and female population sizes, N 1 and N 2 ; maximum iterations, i t e r max ; visibility coefficient, β ; learning factors, a 1 and a 2 ; nuptial dance coefficient, d; random flight coefficient, f l ; objective function, f x
Output: Optimal solution g b e s t
1:
Initialize the male and female velocities v m and v f
2:
Evaluate population based on f x
3:
Find the global best ( g b e s t )
4:
for i t e r = 1 to i t e r max  do
5:
     Adjust the speed and position of each female mayfly using Equations (6) and (7)
6:
     Adjust the speed and position of each male mayfly using Equations (1), (2) and (5)
7:
     Sort the mayflies and rank them based on f x
8:
     Perform crossover and generate male and female offspring
9:
     Mutate the offspring
10:
    Divide offspring into male and female at random
11:
    Update the worst old individuals with the finest new ones
12:
    Update p b e s t and g b e s t
13:
end for

2.2. UAV Path Planning Problem

UAV path planning aims to discover the best flight route for the UAV given a variety of complicated flying restrictions such as threat constraints and fuel limits [35]. The flying height of the drone might be constant along its flight path from the start point to the target point, so this paper only focuses on the UAV’s horizontal flying distance. The mathematical model for UAV path planning and the cost function used to evaluate the planned path are described as follows.

2.2.1. Mathematical Model for Uav Path Planning

In this model, we define S and T to be the start point and target point of the UAV, respectively. It is crucial to prevent collisions with numerous obstacles during the flight of the drone. As a result, this paper employs circles of varying radii to substitute barriers of varying threat levels. So the task of a UAV flight is to find a flight path from S to T with the smallest overall cost while avoiding collisions with obstacles. Figure 1 depicts a schematic representation of the environment modeling for the UAV’s two-dimensional path planning. The path connected by the red line segments is the feasible path.
The segment S T between the S and T in the original coordinate system O X Y is split into D + 1 equal portions by D vertical lines L k , k = 1 , 2 , , D . We can get the path from S to T by picking a point on each vertical line. Thus, the planned path can be expressed as:
L = S , x 1 , y 1 , , x D , y D , T .
To accelerate the processing speed, let the segment S T be the horizontal axis and use Equation (13) to transfer each point x k , y k in the O X Y to x k , y k in the new coordinate system O X Y .
x k y k = cos θ sin θ sin θ cos θ x k x s y k y s ,
where θ denotes to the rotation angle of the O X Y , and the point x s , y s is the coordinate in the O X Y .
As shown in Figure 1, the abscissa of each node in the O X Y can be calculated using formula x k = S T D + 1 × k , so the planned path can be simplified and expressed as:
L = 0 , 0 , x 1 , y 1 , , x D , y D , S T , 0 .

2.2.2. Fitness Function Modeling

A fitness function can be used to calculate the cost of a planned path. The fitness function value can be used to judge the quality of the planned path. The fitness function established in this paper is defined as the sum of two cost functions, given as follows:
F L = w 1 F 1 L + w 2 F 2 L ,
where F L denotes the total cost function of the planned path; F 1 L denotes the cost of the planned path’s length; F 2 L denotes the smoothness cost of the planned path. ω 1 and ω 2 are the weight coefficients of the above cost function, and they are defined as:
ω i 0 i = 1 2 w i = 1 .
Given the UAV’s restricted energy supply, the shorter the planned path length, the less time and energy the UAV spends, and the better it is for the UAV. Assume that the topography of the flight environment and information on the threatened area are known. The start state and the target state are L 0 and L D + 1 , respectively. Hence, the cost F 1 related to the path length can be computed as:
F 1 L = k = 0 D d L k , L k + 1 ,
where d L k , L k + 1 is the distance between x k , y k and x k + 1 , y k + 1 . If the waypoint falls into the obstacle, we choose the intersection of the vertical line with the obstacle, the point closest to the waypoint, as the new search agent. Figure 2a,b depicts the post-collision processing flow. The path connected by the red line segments is the modified feasible path.
The smoothness cost evaluates the turning rate critical to generating feasible paths. The smooth cost F 2 can be computed as:
F 2 L = k = 1 D Δ k Δ k = cos φ cos θ k , φ θ i φ , φ < θ i cos θ = a i T a i + 1 a i a i + 1 ,
where the φ is the maximum turning angle, θ is the current turning angle, and a i is a vector representing the ith segment of the entire route.

3. Modifided Mayfly Algorithm

The standard MA has a better convergence speed than other swarm algorithms when dealing with low-dimensional situations. However, due to the influence of velocity fluctuation, the stability of the MA is poor, thus it leads to poor results. Furthermore, when dealing with high-dimensional nonlinear complicated situations, the MA cannot merely rely on its mechanism to get out of the local optimal zone, so the MA performs poorly on the multimodal functions. This section proposes a modified mayfly algorithm named modMA, which combines three strategies to improve the MA. One improvement is to use the exponent decreasing inertia weight strategy to improve MA, another uses the adaptive Cauchy mutation strategy to improve MA, and a third uses an enhanced crossover operator to improve MA.

3.1. Improvement 1: Exponent Decreasing Inertia Weight Strategy

There are many decreasing inertia weight strategies, such as linear [36], adaptive [37], logarithmic [38], and others [39]. The larger inertia weight in the earlier period is favorable to the exploration of particles, and the particles can search a larger space. The smaller inertia weight in the later period is beneficial to the exploitation of particles. This paper introduces the exponent decreasing inertia weight [40] into MA, formula is as follows:
g = g min + exp 1 i t e r max i t e r max i t e r + 1 g max g min ,
where g max , g min , i t e r , and i t e r max are the same to Equation (3).

3.2. Improvement 2: Adaptive Cauchy Mutaion Strategy

When utilizing Equations (1) and (2) in the standard MA to change the velocity of each male mayfly, the diversity of the entire mayfly population may decline. To mitigate this problem, the position of each male mayfly should be readjusted by using Cauchy-based mutation [41,42]. The standard Cauchy distribution’s probability density function can be described as:
f x = 1 π × 1 1 + x 2 ,
where < x < , the corresponding distribution function is expressed as:
F x = 1 π arctan x + 1 2 .
Random numbers generated via the standard Cauchy distribution are shown below:
C M = tan π × ε 1 2 ,
where C M denotes a random value produced by the inverse function of the standard Cauchy distribution function, ε means a random value in the range 0 to 1 produced by a uniform distribution.
According to Fogarty [43], improved performance is attained when the mutation rate falls exponentially with the number of iterations. Ref. [44] pointed out that the concept is related to that of the simulated annealing (SA) algorithm [45]. So after utilizing Equations (1) and (2) to change the position of each male mayfly, the position of each male mayfly needs to be readjusted using the Equation (22), which combines Cauchy mutation strategy with an adaptive mutation.
X i t + 1 = x i t + 1 + x i t + 1 × C M × exp 1 t × α ,
where x i t + 1 is the ith individual calculated using Equations (1) and (2), and X i t + 1 represents the mutated individual. α is a contraction-expansion coefficient that controls the speed of convergence and it is defined as 0.15.
In this section, we combine the Cauchy mutation strategy with an adaptive mutation which can make the MA generate perturbations with a large step size in the early iterations so that the particles can jump from their current position to another and help MA escape the local optima. The perturbations with a smaller step size in the late iterations can speed up the convergence of the MA. It is worth mentioning that we do not use Cauchy-based mutation to readjust the positions of the particles calculated using Equations (1) and (5).

3.3. Improvement 3: Enhanced Crossover Operator

Although the crossover and reproduction operations of mayflies provide the MA with exploration ability as well as enhance the MA’s convergence speed, the MA has a not strong exploration ability. Hence, we use the horizontal crossover search [46] to improve it. The enhanced crossover operator of the MA employing horizontal crossover search is as follows:
γ 1 = L × m a l e + 1 L × f e m a l e + c 1 × m a l e f e m a l e γ 2 = L × f e m a l e + 1 L × m a l e + c 2 × f e m a l e m a l e ,
where c 1 and c 2 are expansion coefficients, and they are both random values between −1 and 1 produced by a uniform distribution.
The horizontal crossover operation divides the problem-solving space of multi- dimensional into half-population of hypercubes, allowing new spots on the hypercube’s periphery to be sampled with a low probability, and reducing the blind region that are unable to explore by two paired parent individuals. Offspring generated using the horizontal crossover operation need to be compared with their parents, and individuals with greater fitness values are selected for the following iteration. It causes the MA to continuously converge to the best solution and ensure the convergence efficiency without affecting the optimization accuracy through the horizontal crossover operation.
We can also appropriately shrink or expand the search space generated by the two paired parent individuals. The formula of the crossover operator of the MA improved by shrinking the search space is as follows:
γ 1 = d 1 × L × m a l e + 1 L × f e m a l e γ 2 = d 3 × L × f e m a l e + 1 L × m a l e ,
where d 1 and d 3 are the contraction coefficients, and they are both random values between 0.7 and 1 produced by a uniform distribution.
The formula of the crossover operator of the MA improved by expanding the search space is as follows:
γ 1 = d 2 × L × m a l e + 1 L × f e m a l e γ 2 = d 4 × L × f e m a l e + 1 L × m a l e ,
where d 2 and d 4 are the expansion coefficients, and they are both random values between 1 and 1.3 produced by a uniform distribution.
Therefore, the enhanced crossover operator formula of MA can be described as:
γ 1 = L × m a l e + 1 L × f e m a l e , r a n d 1 < p o n e L × m a l e + 1 L × f e m a l e + c 1 × m a l e f e m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o d 1 × L × m a l e + 1 L × f e m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o , r a n d 3 < p t h r e e d 3 × L × m a l e + 1 L × f e m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o , r a n d 3 > p t h r e e .
γ 2 = L × f e m a l e + 1 L × m a l e , r a n d 1 < p o n e L × f e m a l e + 1 L × m a l e + c 2 × f e m a l e m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o d 2 × L × f e m a l e + 1 L × m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o , r a n d 3 < p t h r e e d 4 × L × f e m a l e + 1 L × m a l e , r a n d 1 > p o n e , r a n d 2 < p t w o , r a n d 3 > p t h r e e ,
where r a n d 1 , r a n d 2 , and r a n d 3 are the random input numbers between [0, 1]. p o n e , p t w o , and p t h r e e are the switching probabilities, which control the method of offspring generation. For the value of switching probability p o n e , we refer to the parameter tuning technique of switching probability in the Butterfly Optimization Algorithm (BOA) [47]. From our simulations, we found that p o n e = 0.8, p t w o = 0.5, and p t h r e e = 0.5 work better for most applications.

4. Experimental Results and Application

In this part, we select a variety of numerical optimization functions from CEC benchmark functions to assess the effect of the modified MA presented in this article. Table A1 and Table A2 in Appendix A show the expression, dimension, domain of a variable, and minimum value of each benchmark function. These benchmark functions used in this study can be found in [48], and they are classified into two groups. The unimodal benchmark functions (F1–F14) and multimodal benchmark functions (F15–F26) are applied to calculate the abilities to exploit and explore of the algorithm benchmarked by benchmark functions, respectively.
To assess the efficacy of the three improvement techniques described in this study for MA, we first test and analyze the three versions of the improved MA through comparison experiment 1 by six benchmark functions from Table A1 and Table A2 with D i m = 100 and D i m = 300. It is worth mentioning that modMA-1 is characterized in this study as an MA that is improved by an adaptive Cauchy mutation strategy and the original crossover operator, modMA-2 is defined as an MA modified using only the enhanced crossover operator, and modMA is defined as an MA that incorporates three improved strategies.
To demonstrate that the proposed modMA outperforms other algorithms, we design the comparison experiment 2 for MA [24], modMA-1, modMA-2, modMA, PSO [11], GWO [20], and BOA [47] for 26 benchmark functions with D i m = 50. Finally, we apply the three versions of the modified MA to the UAV path planning problem.

4.1. Parameter Settings of Seven Algorithms in Test

In the two experiments, we select MA [24], modMA-1, modMA-2, modMA, PSO [11], GWO [20], and BOA [47] for comparison. Table 1 shows the parameter settings of each algorithm. To promote equality in the comparison, all algorithms in this study are iterated 1000 times, the dimension is 50, and each algorithm has a maximum number of solutions of 40. For example, we use 20 female mayflies and 20 male mayflies for all simulations of MA. We analyze the Average (Avg) and Standard deviation (Std) of the fitness values after 30 runs on each benchmark function in both experiments.

4.2. Experiment 1: Comparison with MA, modMA-1, modMA-2,

In experiment 1, we compare the performance of MA [24], modMA-1, modMA-2, and modMA on six high-dimensional functions (3 unimodal problems and 3 multimodal problems) from Table A1 and Table A2 with D i m = 100 and D i m = 300. It can be seen from Figure 3 and Figure 4a–f that the proposed modMA, modMA-1, modMA-2 have improved the convergence trend of the MA at high dimensions (i.e., 300 and 500), that is, modMA, modMA-1, modMA-2 can obtain better values on the benchmark functions with fewer iterations.From Figure 3c,e,f we can see that modMA has a certain level of ability in escaping from local optima values in the late iterations. From Table 2 and Table 3, the proposed modMA, modMA-1, modMA-2 can also get better results. From the A v g and S t d in Table 2 and Table 3, the modMA can solve the problems that MA has poor ability and instability in finding the optimal solution when solving high-dimensional complex functions.

4.3. Experiment 2: Comparison with Other Swarm Algorithms

The performance of MA [24], modMA-1, modMA-2, modMA, PSO [11], GWO [20], and BOA [47] for 26 benchmark functions with D i m = 50 is compared in this experiment. At the same time, the A v g and the S t d of functions are shown in Table 4.
From Table 4, the proposed modMA, modMA-1, and modMA-2 all perform well on most benchmark functions when A v g is used as a comparison criterion.
modMA has the best performance on these 26 benchmarks functions with D i m = 50 except F 4 , F 5 , F 7 , F 20 , F 21 and F 23 . modMA can obtain the minimum values on benchmark functions F 13 , F 14 , F 15 , F 16 , F 18 , F 24 , F 26 .
The Friedman test values and Wilcoxon sign rank test values that can reflect the difference between the proposed modMA and other algorithms (i.e., MA, modMA-1, modMA-2, PSO, GWO, and BOA) are also given in Table 5 and Table 6. Note, the significant level α is set to 0.05. This signifies that the sample result is not statistically significant if the p-value is larger than 0.05.
In addition, we also select the convergence curves of various algorithms on some benchmark functions to visually show the degree of convergence of the modMA-1, modMA-2, and modMA, as shown in Figure 5 and Figure 6. Compared with MA, the convergence accuracy of the proposed modMA-1, modMA-2, and modMA is significantly improved. Compared to modMA-1 and modMA-2, modMA converges faster and finds the global optimum with fewer iterations in most functions. On the whole, modMA can effectively improve the capability of exploitation, exploration, and stability of MA. modMA also has a better convergence rate and accuracy than other algorithms.

4.4. Uav Path Planning Experiment

In this section, the proposed modMA is evaluated in two separate scenarios, the threat locations for the two cases are listed in Table 7. We select PSO [11], GWO [20], BOA [47], MA [24], modMA-1, modMA-2, and modMA for experiments. The parameter settings of these algorithms are the same as in Section 4.1.
In both cases, we assume that the start point and target point of the drone are (0, 0), and (500, 500). The maximum turning angle ϕ k is set to 45 degrees. The values of weight coefficients ω 1 and ω 2 are set to 0.95 and 0.05, respectively. This paper discusses D = 30 and D = 50 in each scenario separately. D is set to 50, that is, the distance between the start point and target point is cut into 50 segments. To guarantee equality of the comparison, the number of particles, the pre-defined maximum iteration value, and each algorithm’s number of runs are all set to 40, 200, and 30.
The experimental results are listed in Table 8. The corresponding convergence curves are shown in Figure 7a–f and Figure 8a–f. From Figure 7a–f and Figure 8a–f, all the seven algorithms can find collision-free flight paths, but they perform differently in terms of path length and smoothness. It can be seen from Table 8 that in the case of D = 30, that is, in a lower dimension, each algorithm can achieve good results, and the path length planned by modMA is shorter and the path is smoother. In the case of D = 50, that is, in a higher dimension, modMA, modMA-1, and modMA-2 greatly improve the performance of MA. modMA and modMA-1 can achieve better results in most cases, and both have good initial solutions and convergence rates, but the fluctuation of modMA is smaller than that of modMA-1. Among all the comparison algorithms, the overall cost of modMA planning is the smallest in most cases, which shows that the path planned by the modMA can reach the best when the UAV avoids collision, which proves the effectiveness of the modMA.
The path planning problem has many local solutions, this makes classical optimization techniques difficult to solve. modMA shows excellent performance on this complex problem, i.e., the quality of the solution and the stability of the solution. In addition, modMA also has good initial solution and fast convergence speed. However, the model established in this paper still has some shortcomings. After collision handling, that is, the operation of moving the waypoint to the edge of the obstacle, the planned path length may be longer than the theoretical optimum.

5. Conclusions

A new algorithm modMA which incorporates a mixed strategy consisting of three improved techniques is proposed throughout this research for solving the UAV path planning problem. By introducing the EDIW strategy to balance the particles’ processes of exploration and exploitation. By perturbing the position of each male particle with an adaptive Cauchy mutation operator, the diversity of the swarm is increased. By introducing an enhanced crossover operator, the exploration ability of the modMA is enhanced. To assess the efficacy of these three improvement techniques on MA, two experiments are designed. The suggested modMA is tested on 26 benchmark functions, and it has obvious advantages in finding both the best value and convergence speed. Finally, the proposed modMA, together with PSO, GWO, and BOA, are applied to the UAV path planning problem; simulation experiments show that the effect of modMA which is applied to the UAV path planning problem is relatively stable, and the quality of the planned path is high. The time cost of modMA in the path planning problem of UAV is higher than that of PSO, BOA and GWO, which is determined by its algorithm structure, but the the convergence speed is fast in the process of solving the problem.
In future work, hybrid [49,50] can be introduced to further enhance the performance of the modMA. The cost of the drone collision threat can also be considered in the UAV path planning problem.

Author Contributions

Conceptualization, X.W. and J.-S.P.; Formal analysis, X.W., J.-S.P., Q.Y. and S.-C.C.; Methodology, X.W., J.-S.P., L.K., V.S. and S.-C.C.; Validation, J.-S.P., Q.Y., L.K. and V.S.; Writing—original draft, X.W.; Writing—review & editing, X.W., J.-S.P., Q.Y., L.K., V.S. and S.-C.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest of this paper.

Appendix A

Table A1. Unimodal benchmark functions.
Table A1. Unimodal benchmark functions.
NameFormula of FunctionsDimRange f min
Sphere F 1 x = Σ D i m i = 1 x i 2 50[−100, 100]0
Schwefel 2.22 F 2 x = Σ D i m i = 1 x i + i = 1 D i m x i 50[−10, 10]0
Schwefel 1.2 F 3 x = i = 1 D i m j = i i x j 2 50[−100, 100]0
Schwefel 2.21 F 4 x = max x i , 1 i D i m 50[−10, 10]0
Step F 5 x = i = 1 D i m x i + 0.5 2 50[−10, 10]0
Quartic F 6 x = i = 1 D i m D i m · x i 2 + r a n d 0 , 1 50[−1.28, 1.28]0
Exponential F 7 x = exp 0.5 i = 1 D i m x i 50[−10, 10]0
Sum power F 8 x = i = 1 D i m x i i + 1 50[−1, 1]0
Sum square F 9 x = i = 1 D i m D i m · x i 2 50[−10, 10]0
Rosenbrock F 10 x = i = 1 D i m 100 x i + 1 x i 2 + x i 1 2 50[−5, 10]0
Zakharov F 11 x = i = 1 D i m x i 2 + i = 1 D i m 0.5 i x i 2 + i = 1 D i m 0.5 i x i 4 50[−5, 10]0
Trid F 12 x = x i 1 2 + i = 1 D i m i · 2 x i 2 x i 1 2 50[−10, 10]0
Elliptic F 13 x = i = 1 D i m 10 6 i 1 / D i m 1 · x i 2 50[−100, 100]0
Cigar F 14 x = x 1 2 + 10 6 i = 1 D i m x i 2 50[−100, 100]0
Table A2. Multimodal benchmark functions.
Table A2. Multimodal benchmark functions.
NameFormula of FunctionsDimRange f min
Rastrigin F 15 x = i = 1 D i m x i 2 10 cos 2 π x i + 10 50[−5.12, 5.12]0
NCRastrigin F 16 x = i = 1 D i m y i 2 10 cos 2 π y i + 10 , y i = x i , x i < 0.5 r o u n d 2 x i / 2 , x i > 0.5 50[−5.12, 5.12]0
Ackley F 17 x = 20 exp 0.2 1 D i m i = 1 D i m x i 2 + exp 1 D i m i = 1 D i m cos 2 π x i + 20 + exp 1 50[−50, 50]0
Griewank F 18 x = 1 4000 i = 1 D i m x i 2 i = 1 D i m cos x i i + 1 50[−600, 600]0
Alpine F 19 x = i = 1 D i m x i · sin x i + 0.1 x i 50[−10, 10]0
Penalized 1 F 20 x = π D i m i = 1 D i m 1 y i 1 2 1 + 10 sin 2 π y 1 + y D i m 1 2 + 10 sin 2 π y 1 + i = 1 D i m u x i , 10 , 100 , 4 y i = 1 + x i + 1 / 4 , u y i , a , k , m = k x i a m , x i > a 0 , a x i a k x i a m , x i < a 50[−100, 100]0
Penalized 2 F 21 x = 1 10 sin 2 π x 1 + i = 1 D i m 1 x i 1 2 1 + sin 2 3 π x i + 1 + x D i m 1 2 1 + sin 2 2 π x i + 1 + i = 1 D i m u x i , 5 , 100 , 4 50[−100, 100]0
Schwefel F 22 x = i = 1 D i m x i · sin x i 50[−100, 100]0
Levy F 23 x = sin 2 3 π x i + i = 1 D i m 1 x i 1 2 1 + sin 2 3 π x i + 1 + x D i m 1 · 1 + sin 2 2 π x D i m 50[−10, 10]0
Weierstrass F 24 x = i = 1 D i m k = 0 k max a k cos 2 π b k x i + 0.5 D i m · k = 0 k max a k cos π b k , a = 0.5 , b = 3 , k max = 20 50[−1, 1]0
Solomon F 25 x = 1 cos 2 π i = 1 D i m x i 2 + 0.1 i = 1 D i m x i 2 50[−100, 100]0
Bohachevsky F 26 x = i = 1 D i m x i 2 + 2 x i + 1 2 0.3 · cos 3 π x i 50[−10, 10]0

References

  1. Yu, X.; Zhang, Y. Sense and avoid technologies with applications to unmanned aircraft systems: Review and prospects. Prog. Aerosp. Sci. 2015, 74, 152–166. [Google Scholar] [CrossRef]
  2. Huo, L.; Zhu, J.; Wu, G.; Li, Z. A novel simulated annealing based strategy for balanced UAV task assignment and path planning. Sensors 2020, 20, 4769. [Google Scholar] [CrossRef] [PubMed]
  3. Dhulkefl, E.J.; Durdu, A. Path planning algorithms for unmanned aerial vehicles. Int. J. Trend Sci. Res. Dev. 2019, 3, 359–362. [Google Scholar] [CrossRef]
  4. Zhang, Z.; Wu, J.; Dai, J.; He, C. A novel real-time penetration path planning algorithm for stealth UAV in 3D complex dynamic environment. IEEE Access 2020, 8, 122757–122771. [Google Scholar] [CrossRef]
  5. Zhang, D.; Xu, Y.; Yao, X. An improved path planning algorithm for unmanned aerial vehicle based on rrt-connect. In Proceedings of the 2018 37th Chinese Control Conference (CCC), Wuhan, China, 25–27 July 2018; pp. 4854–4858. [Google Scholar]
  6. Huo, L.; Zhu, J.; Li, Z.; Ma, M. A hybrid differential symbiotic organisms search algorithm for UAV path planning. Sensors 2021, 21, 3037. [Google Scholar] [CrossRef] [PubMed]
  7. Zhang, D.; Duan, H. Social-class pigeon-inspired optimization and time stamp segmentation for multi-UAV cooperative path planning. Neurocomputing 2018, 313, 229–246. [Google Scholar] [CrossRef]
  8. Zhang, X.; Duan, H. An improved constrained differential evolution algorithm for unmanned aerial vehicle global route planning. Appl. Soft Comput. 2015, 26, 270–284. [Google Scholar] [CrossRef]
  9. Rajabioun, R. Cuckoo optimization algorithm. Appl. Soft Comput. 2011, 11, 5508–5518. [Google Scholar] [CrossRef]
  10. Song, P.C.; Pan, J.S.; Chu, S.C. A parallel compact cuckoo search algorithm for three-dimensional path planning. Appl. Soft Comput. 2020, 94, 106443. [Google Scholar] [CrossRef]
  11. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the ICNN’95-International Conference on Neural Networks, Perth, WA, USA, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar]
  12. Chu, S.C.; Roddick, J.F.; Pan, J.S. A parallel particle swarm optimization algorithm with communication strategies. J. Inf. Sci. Eng. 2005, 21, 809–818. [Google Scholar]
  13. Phung, M.D.; Ha, Q.P. Safety-enhanced UAV path planning with spherical vector-based particle swarm optimization. Appl. Soft Comput. 2021, 107, 107376. [Google Scholar] [CrossRef]
  14. Mirjalili, S. Genetic algorithm. In Evolutionary Algorithms and Neural Networks; Springer: Berlin/Heidelberg, Germany, 2019; pp. 43–55. [Google Scholar]
  15. Roberge, V.; Tarbouchi, M.; Labonté, G. Comparison of parallel genetic algorithm and particle swarm optimization for real-time UAV path planning. IEEE Trans. Ind. Info. 2012, 9, 132–141. [Google Scholar] [CrossRef]
  16. Basturk, B. An artificial bee colony (ABC) algorithm for numeric function optimization. In Proceedings of the IEEE Swarm Intelligence Symposium, Indianapolis, IN, USA, 12–14 May 2006. [Google Scholar]
  17. Lei, L.; Shiru, Q. Path planning for unmanned air vehicles using an improved artificial bee colony algorithm. In Proceedings of the 31st Chinese Control Conference, Hefei, China, 25–27 July 2012; pp. 2486–2491. [Google Scholar]
  18. Price, K.V. Differential evolution: A fast and simple numerical optimizer. In Proceedings of the North American Fuzzy Information Processing, Berkeley, CA, USA, 19–22 June 1996; pp. 524–527. [Google Scholar]
  19. Pan, J.S.; Liu, N.; Chu, S.C. A hybrid differential evolution algorithm and its application in unmanned combat aerial vehicle path planning. IEEE Access 2020, 8, 17691–17712. [Google Scholar] [CrossRef]
  20. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey wolf optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef] [Green Version]
  21. Lv, J.X.; Yan, L.J.; Chu, S.C.; Cai, Z.M.; Pan, J.S.; He, X.K.; Xue, J.K. A new hybrid algorithm based on golden eagle optimizer and grey wolf optimizer for 3D path planning of multiple UAVs in power inspection. Neural Comput. Appl. 2022, 193, 509–532. [Google Scholar] [CrossRef]
  22. Dorigo, M.; Birattari, M.; Stutzle, T. Ant colony optimization. IEEE Comput. Intell. Mag. 2006, 1, 28–39. [Google Scholar] [CrossRef]
  23. Konatowski, S.; Pawłowski, P. Ant colony optimization algorithm for UAV path planning. In Proceedings of the 2018 14th International Conference on Advanced Trends in Radioelecrtronics, Telecommunications and Computer Engineering (TCSET), Lviv-Slavske, Ukraine, 20–24 February 2018; pp. 177–182. [Google Scholar]
  24. Zervoudakis, K.; Tsafarakis, S. A mayfly optimization algorithm. Comput. Ind. Eng. 2020, 145, 106559. [Google Scholar] [CrossRef]
  25. Kennedy, J. Bare bones particle swarms. In Proceedings of the 2003 IEEE Swarm Intelligence Symposium, SIS’03 (Cat. No. 03EX706), Indianapolis, IN, USA, 26 April 2003; pp. 80–87. [Google Scholar]
  26. Juan, Z.; Zheng-Ming, G. Bare bones mayfly optimization algorithm. In Proceedings of the 2020 2nd International Conference on Machine Learning, Big Data and Business Intelligence (MLBDBI), Taiyuan, China, 23–25 October 2020; pp. 238–241. [Google Scholar]
  27. Shaheen, M.A.; Hasanien, H.M.; El Moursi, M.; El-Fergany, A.A. Precise modeling of PEM fuel cell using improved chaotic MayFly optimization algorithm. Int. J. Energy Res. 2021, 45, 18754–18769. [Google Scholar] [CrossRef]
  28. Gigras, Y.; Gupta, K.; Choudhury, K. A comparison between bat algorithm and cuckoo search for path planning. Int. J. Innov. Res. Comput. Commun. Eng. 2015, 3, 4459–4466. [Google Scholar]
  29. Zhang, S.; Zhou, Y.; Li, Z.; Pan, W. Grey wolf optimizer for unmanned combat aerial vehicle path planning. Adv. Eng. Softw. 2016, 99, 121–136. [Google Scholar] [CrossRef] [Green Version]
  30. Pan, J.S.; Liu, J.L.; Hsiung, S.C. Chaotic cuckoo search algorithm for solving unmanned combat aerial vehicle path planning problems. In Proceedings of the 2019 11th International Conference on Machine Learning and Computing, Zhuhai, China, 22–24 February 2019; pp. 224–230. [Google Scholar]
  31. Duan, H.; Qiao, P. Pigeon-inspired optimization: A new swarm intelligence optimizer for air robot path planning. Int. J. Intell. Comput. Cybern. 2014, 7, 24–37. [Google Scholar] [CrossRef]
  32. Wang, G.; Guo, L.; Duan, H.; Liu, L.; Wang, H. A modified firefly algorithm for UCAV path planning. Int. J. Hybrid Inf. Technol. 2012, 5, 123–144. [Google Scholar]
  33. Zhu, W.; Duan, H. Chaotic predator–prey biogeography-based optimization approach for UCAV path planning. Aerosp. Sci. Technol. 2014, 32, 153–161. [Google Scholar] [CrossRef]
  34. Yang, X.S. Firefly algorithm, Levy flights and global optimization. In Research and Development in Intelligent Systems XXVI; Springer: Berlin/Heideberg, Germany, 2010; pp. 209–218. [Google Scholar]
  35. Foo, J.L.; Knutzon, J.; Kalivarapu, V.; Oliver, J.; Winer, E. Path planning of unmanned aerial vehicles using B-splines and particle swarm optimization. J. Aerosp. Comput. Inf. Commun. 2009, 6, 271–290. [Google Scholar] [CrossRef]
  36. Shi, Y.; Eberhart, R. A modified particle swarm optimizer. In Proceedings of the 1998 IEEE International Conference on Evolutionary Computation Proceedings, IEEE World Congress on Computational Intelligence (Cat. No. 98TH8360), Anchorage, AK, USA, 4–9 May 1998; pp. 69–73. [Google Scholar]
  37. Nickabadi, A.; Ebadzadeh, M.M.; Safabakhsh, R. A novel particle swarm optimization algorithm with adaptive inertia weight. Appl. Soft Comput. 2011, 11, 3658–3670. [Google Scholar] [CrossRef]
  38. Gao, Y.L.; An, X.H.; Liu, J.M. A particle swarm optimization algorithm with logarithm decreasing inertia weight and chaos mutation. In Proceedings of the 2008 International Conference on Computational Intelligence and Security, Washington, DC, USA, 13–17 December 2008; Volume 1, pp. 61–65. [Google Scholar]
  39. Rathore, A.; Sharma, H. Review on inertia weight strategies for particle swarm optimization. In Proceedings of Sixth International Conference on Soft Computing for Problem Solving; Springer: Berlin/Heidelberg, Germany, 2017; pp. 76–86. [Google Scholar]
  40. Cao, Z.; Shi, Y.; Rong, X.; Liu, B.; Du, Z.; Yang, B. Random grouping brain storm optimization algorithm with a new dynamically changing step size. In Proceedings of the International Conference in Swarm Intelligence; Springer: Berlin/Heidelberg, Germany, 2015; pp. 357–364. [Google Scholar]
  41. Zou, Y.; Liu, P.X.; Yang, C.; Li, C.; Cheng, Q. Collision detection for virtual environment using particle swarm optimization with adaptive cauchy mutation. Clust. Comput. 2017, 20, 1765–1774. [Google Scholar] [CrossRef]
  42. Chakraborty, F.; Roy, P.K.; Nandi, D. Oppositional elephant herding optimization with dynamic Cauchy mutation for multilevel image thresholding. Evol. Intell. 2019, 12, 445–467. [Google Scholar] [CrossRef]
  43. Fogarty, T.C. Varying the Probability of Mutation in the Genetic Algorithm. In Proceedings of the 3rd International Conference on Genetic Algorithms, Fairfax, VA, USA, 4–7 June 1989; Morgan Kaufmann Publishers Inc.: San Francisco, CA, USA, 1989; pp. 104–109. [Google Scholar]
  44. Lin, W.Y.; Lee, W.Y.; Hong, T.P. Adapting Crossover and Mutation Rates in Genetic Algorithms. J. Inf. Sci. Eng. 2003, 19, 889–903. [Google Scholar]
  45. Van Laarhoven, P.J.; Aarts, E.H. Simulated annealing. In Simulated Annealing: Theory and Applications; Springer: Berlin/Heidelberg, Germany, 1987; pp. 7–15. [Google Scholar]
  46. Meng, A.b.; Chen, Y.c.; Yin, H.; Chen, S.Z. Crisscross optimization algorithm and its application. Knowl. Based Syst. 2014, 67, 218–229. [Google Scholar] [CrossRef]
  47. Arora, S.; Singh, S. Butterfly optimization algorithm: A novel approach for global optimization. Soft Comput. 2019, 23, 715–734. [Google Scholar] [CrossRef]
  48. Zhang, M.; Long, D.; Qin, T.; Yang, J. A chaotic hybrid butterfly optimization algorithm with particle swarm optimization for high-dimensional optimization problems. Symmetry 2020, 12, 1800. [Google Scholar] [CrossRef]
  49. Wang, G.G.; Gandomi, A.H.; Zhao, X.; Chu, H.C.E. Hybridizing harmony search algorithm with cuckoo search for global numerical optimization. Soft Comput. 2016, 20, 273–285. [Google Scholar] [CrossRef]
  50. Pan, J.S.; Zhuang, J.; Liao, L.; Chu, S.C. Advanced equilibrium optimizer for electric vehicle routing problem with time windows. J. Netw. Intell. 2021, 6, 216–237. [Google Scholar]
Figure 1. Two-dimensional representation of planning space.
Figure 1. Two-dimensional representation of planning space.
Drones 06 00134 g001
Figure 2. The post-collision processing flow. (a) S c e n a r i o 1 ; (b) S c e n a r i o 2 .
Figure 2. The post-collision processing flow. (a) S c e n a r i o 1 ; (b) S c e n a r i o 2 .
Drones 06 00134 g002
Figure 3. Comparison of convergence curve between MA, modMA-1, modMA-2, and modMA with D i m = 100.
Figure 3. Comparison of convergence curve between MA, modMA-1, modMA-2, and modMA with D i m = 100.
Drones 06 00134 g003
Figure 4. Comparison of convergence curve between MA, modMA-1, modMA-2, and modMA with D i m = 300.
Figure 4. Comparison of convergence curve between MA, modMA-1, modMA-2, and modMA with D i m = 300.
Drones 06 00134 g004
Figure 5. Comparison of convergence curve of MA, modMA-1, modMA-2, modMA, PSO, GWO and BOA in benchmark functions F 1 , F 2 and F 5 when D i m = 50.
Figure 5. Comparison of convergence curve of MA, modMA-1, modMA-2, modMA, PSO, GWO and BOA in benchmark functions F 1 , F 2 and F 5 when D i m = 50.
Drones 06 00134 g005
Figure 6. Comparison of convergence curve between MA, modMA-1, modMA-2, modMA, PSO, GWO and BOA with in benchmark functions F 6 , F 12 , F 18 , F 19 , F 20 and F 22 Dim = 50.
Figure 6. Comparison of convergence curve between MA, modMA-1, modMA-2, modMA, PSO, GWO and BOA with in benchmark functions F 6 , F 12 , F 18 , F 19 , F 20 and F 22 Dim = 50.
Drones 06 00134 g006
Figure 7. Path diagram of a single run in Case 1. (a) Comparative path planning results in Case 1, D i m = 30; (b) Evolution curves of four algorithms in Case 1, D i m = 30; (c) Evolution curves of different algorithms in Case 1, D i m = 30; (d) Comparative path planning results in Case 1, D i m = 50; (e) Evolution curves of four algorithms in Case 1, D i m = 50; (f) Evolution curves of different algorithms in Case 1, D i m = 50.
Figure 7. Path diagram of a single run in Case 1. (a) Comparative path planning results in Case 1, D i m = 30; (b) Evolution curves of four algorithms in Case 1, D i m = 30; (c) Evolution curves of different algorithms in Case 1, D i m = 30; (d) Comparative path planning results in Case 1, D i m = 50; (e) Evolution curves of four algorithms in Case 1, D i m = 50; (f) Evolution curves of different algorithms in Case 1, D i m = 50.
Drones 06 00134 g007
Figure 8. Path diagram of a single run in Case 2. (a) Comparative path planning results in Case 2, D i m = 30. (b) Evolution curves of four algorithms in Case 2, D i m = 30. (c) Evolution curves of different algorithms in Case 2, D i m = 30. (d) Comparative path planning results in Case 2, D i m = 50. (e) Evolution curves of four algorithms in Case 2, D i m = 50. (f) Evolution curves of different algorithms in Case 2, D i m = 50.
Figure 8. Path diagram of a single run in Case 2. (a) Comparative path planning results in Case 2, D i m = 30. (b) Evolution curves of four algorithms in Case 2, D i m = 30. (c) Evolution curves of different algorithms in Case 2, D i m = 30. (d) Comparative path planning results in Case 2, D i m = 50. (e) Evolution curves of four algorithms in Case 2, D i m = 50. (f) Evolution curves of different algorithms in Case 2, D i m = 50.
Drones 06 00134 g008
Table 1. Parameter settings for the algorithms to be compared.
Table 1. Parameter settings for the algorithms to be compared.
No.NameParameter
1MA g max = 0.9, g min = 0.2, a 1 = 1, a 2 = a 3 = 1.5, d = 5, β = 2, f l = 1
2modMA-1 g max = 0.9, g min = 0.2, a 1 = 1, a 2 = a 3 = 1.5, d = 5, β = 2, f l = 1, α = 0.15
3modMA-2 g max = 0.9, g min = 0.2, a 1 = 1, a 2 = a 3 = 1.5, d = 5, β = 2, f l = 1
4modMA g max = 0.9, g min = 0.2, a 1 = 1, a 2 = a 3 = 1.5, d = 5, β = 2, f l = 1, α = 0.15
5PSO g max = 0.9, g min = 0.2, c 1 = c 2 = 1.5
6GWO a f i r s t = 2, a f i n a l = 0
7BOA p r o b a b i l i t y s w i t c h = 0.8, p o w e r e x p o n e n t = 0.1, m o d u l a r m o d a l i t y = 0.01
Table 2. MA, modMA-1, modMA-2, and modMA test results on the 100-dimensional functions in experiment 1.
Table 2. MA, modMA-1, modMA-2, and modMA test results on the 100-dimensional functions in experiment 1.
FunctionsMAmodMA-1modMA-2modMA
F 1 Best1.130 × 10 2 4.798 × 10 16 6.615 × 10 100 1.443 × 10 113
Avg2.586 × 10 2 5.163 × 10 9 2.228 × 10 90 5.000 ×  10 102
Std1.033 × 10 2 1.320 × 10 8 5.748 × 10 90 2.713 × 10 101
F 3 Best1.049 × 10 4 2.301 × 10 14 3.723 × 10 81 3.236 × 10 98
Avg2.029 × 10 4 1.035 × 10 5 1.499 × 10 67 1.783 ×  10 81
Std5.771 × 10 3 2.889 × 10 5 8.154 × 10 67 9.097 × 10 81
F 6 Best1.517 × 10 1 1.586 × 10 4 3.283 × 10 4 6.919 × 10 5
Avg92.821 × 10 1 1.920 × 10 3 1.120 × 10 3 8.239 ×  10 4
Std6.322 × 10 2 2.029 × 10 3 5.825 × 10 4 5.655 × 10 4
F 15 Best4.179 × 10 1 2.274 × 10 13 3.084 × 10 1 0.000 × 10 0
Avg5.948 × 10 1 5.983 × 10 11 5.799 × 10 1 0.000 ×  10 0
Std9.749 × 10 0 1.629 × 10 10 1.473 × 10 1 0.000 × 10 0
F 17 Best7.314 × 10 0 8.795 × 10 10 4.441 × 10 15 4.441 × 10 15
Avg9.007 × 10 0 1.006 × 10 5 5.862 ×  10 15 5.862 ×  10 15
Std9.048 × 10 1 1.516 × 10 5 1.770 × 10 15 1.770 × 10 15
F 23 Best1.762 × 10 2 1.652 × 10 2 1.483 × 10 2 1.366 × 10 2
Avg6.624 × 10 1 4.767 × 10 1 3.482 × 10 1 2.002 ×  10 1
Std1.275 × 10 0 6.518 × 10 1 8.994 × 10 1 3.296 × 10 1
Table 3. MA, modMA-1, modMA-2, and modMA test results on the 300-dimensional functions in experiment 1.
Table 3. MA, modMA-1, modMA-2, and modMA test results on the 300-dimensional functions in experiment 1.
FunctionsMAmodMA-1modMA-2modMA
F 1 Best1.223 × 10 4 4.977 × 10 12 4.135 × 10 97 1.469 × 10 109
Avg1.607 × 10 4 1.547 × 10 6 9.198 × 10 87 4.037 ×  10 92
Std1.865 × 10 3 5.898 × 10 6 3.814 × 10 86 2.206 × 10 91
F 3 Best1.405 × 10 5 1.363 × 10 8 9.877 × 10 77 1.422 × 10 91
Avg2.414 × 10 5 1.168 × 10 3 4.772 × 10 63 2.737 ×  10 77
Std8.673 × 10 4 4.095 × 10 3 2.340 × 10 62 1.495 × 10 76
F 6 Best2.985 × 10 0 1.681 × 10 4 2.015 × 10 4 6.201 × 10 5
Avg3.827 × 10 0 2.248 × 10 3 1.273 × 10 3 8.106 ×  10 4
Std5.001 × 10 1 2.093 × 10 3 6.273 × 10 4 5.993 × 10 4
F 15 Best1.868 × 10 2 6.366 × 10 12 1.249 × 10 2 0.000 × 10 0
Avg2.351 × 10 2 2.824 × 10 7 2.269 × 10 2 0.000 ×  10 0
Std2.567 × 10 1 1.187 × 10 6 4.775 × 10 1 0.000 × 10 0
F 17 Best1.245 × 10 1 9.821 × 10 7 4.441 × 10 15 4.441 × 10 15
Avg1.337 × 10 1 7.345 × 10 5 6.099 ×  10 15 6.099 ×  10 15
Std4.853 × 10 1 1.129 × 10 4 1.741 × 10 15 1.803 × 10 15
F 23 Best4.761 × 10 0 2.691 × 10 0 3.108 × 10 0 2.294 × 10 0
Avg7.554 × 10 0 4.673 × 10 0 5.422 × 10 0 3.979 ×  10 0
Std1.804 × 10 0 1.061 × 10 0 1.415 × 10 0 8.642 × 10 1
Table 4. MA, modMA-1, modMA-2, modMA, PSO, GWO, and BOA test results on the 50-dimensional functions in experiment 2.
Table 4. MA, modMA-1, modMA-2, modMA, PSO, GWO, and BOA test results on the 50-dimensional functions in experiment 2.
FunctionsMAmodMA-1modMA-2modMAPSOGWOBOA
F 1 Mean4.778 × 10 5 5.874 × 10 13 2.055 × 10 90 4.660 ×  10 106 3.555 × 10 3 2.875 × 10 48 1.761 × 10 14
Std1.533 × 10 4 1.598 × 10 12 1.119 × 10 89 1.82 × 10 105 9.273 × 10 3 2.797 × 10 48 7.850 × 10 16
F 2 Mean4.695 × 10 3 7.326 × 10 9 4.029 × 10 51 4.294 ×  10 55 2.038 × 10 2 1.406 × 10 28 2.791 × 10 22
Std7.433 × 10 3 1.632 × 10 8 7.881 × 10 51 1.834 × 10 54 3.023 × 10 2 1.342 × 10 28 8.588 × 10 22
F 3 Mean1.978 × 10 3 8.022 × 10 8 3.506 × 10 70 2.191 ×  10 83 2.306 × 10 3 2.120 × 10 8 1.773 × 10 14
Std8.416 × 10 2 2.235 × 10 7 1.920 × 10 69 1.015 × 10 82 7.139 × 10 2 6.684 × 10 8 1.050 × 10 15
F 4 Mean1.693 × 10 0 6.127 × 10 6 2.147 ×  10 41 3.468 × 10 41 6.888 × 10 1 1.802 × 10 11 1.057 × 10 11
Std3.424 × 10 1 1.037 × 10 5 9.710 × 10 41 1.900 × 10 40 8.100 × 10 2 2.251 × 10 11 4.996 × 10 13
F 5 Mean4.184 ×  10 8 4.388 × 10 8 4.502 × 10 8 5.995 × 10 8 4.134 × 10 5 1.873 × 10 0 1.031 × 10 1
Std1.871 × 10 8 2.737 × 10 8 3.135 × 10 8 2.724 × 10 8 1.382 × 10 4 5.635 × 10 1 7.762 × 10 1
F 6 Mean6.249 × 10 2 1.826 × 10 3 1.145 × 10 3 6.490 ×  10 4 3.759 × 10 2 1.010 × 10 3 6.995 × 10 4
Std1.634 × 10 2 1.533 × 10 3 6.072 × 10 4 5.269 × 10 4 1.022 × 10 2 3.972 × 10 4 2.370 × 10 4
F 7 Mean2.67 × 10 109 2.67 × 10 109 2.67 × 10 109 2.67 × 10 109 0.000 ×  10 0 5.688 × 10 91 4.816 × 10 14
Std9.62 × 10 125 9.62 × 10 125 9.62 × 10 125 9.62 × 10 125 0.000 × 10 0 2.500 × 10 90 2.567 × 10 13
F 8 Mean9.117 × 10 24 8.800 × 10 47 5.99 × 10 250 1.345 ×  10 265 1.431 × 10 27 2.35 × 10 202 7.036 × 10 17
Std3.569 × 10 23 4.504 × 10 46 0.000 × 10 0 0.000 × 10 0 6.681 × 10 27 0.000 × 10 0 8.769 × 10 17
F 9 Mean1.857 × 10 6 8.590 × 10 15 9.788 × 10 95 8.851 ×  10 107 5.935 × 10 4 5.060 × 10 49 1.779 × 10 14
Std2.261 × 10 6 2.701 × 10 14 5.349 × 10 94 4.84 × 10 106 7.443 × 10 4 9.881 × 10 49 9.194 × 10 16
F 10 Mean4.387 × 10 1 4.432 × 10 1 4.232 × 10 1 4.214 ×  10 1 8.405 × 10 1 4.691 × 10 1 4.865 × 10 1
Std4.150E × 10 1 5.236 × 10 1 5.382 × 10 1 4.549 × 10 1 5.093 × 10 1 8.848 × 10 1 3.134 × 10 2
F 11 Mean1.188 × 10 6 3.801 × 10 12 5.403 × 10 97 1.677 ×  10 108 3.334 × 10 4 3.162 × 10 48 1.781 × 10 14
Std5.051 × 10 7 2.081 × 10 11 2.684 × 10 96 6.50 × 10 108 3.967 × 10 4 5.144 × 10 48 7.002 × 10 16
F 12 Mean3.576 × 10 0 6.667 ×  10 1 6.667 ×  10 1 6.667 ×  10 1 4.652 × 10 0 6.667 ×  10 1 9.938 × 10 1
Std3.066 × 10 0 1.938 × 10 7 1.899 × 10 7 3.630 × 10 7 4.149 × 10 0 5.015 × 10 7 2.995 × 10 3
F 13 Mean0.000 ×  10 0 0.000 ×  10 0 0.000 ×  10 0 0.000 ×  10 0 2.10 × 10 147 0.000 ×  10 0 8.645 × 10 23
Std0.000 × 10 0 0.000 × 10 0 0.000 × 10 0 0.000 × 10 0 1.13 × 10 146 0.000 × 10 0 3.426 × 10 22
F 14 Mean2.423 × 10 2 0.000 ×  10 0 0.000 ×  10 0 0.000 ×  10 0 2.96 × 10 119 0.000 ×  10 0 5.324 × 10 15
Std1.327 × 10 1 0.000 × 10 0 0.000 × 10 0 0.000 × 10 0 1.62 × 10 118 0.000 × 10 0 5.818 × 10 15
F 15 Mean2.164 × 10 1 2.634 × 10 13 2.189 × 10 1 0.000 ×  10 0 9.333 × 10 1 2.776 × 10 1 3.790 × 10 15
Std4.315 × 10 0 1.725 × 10 13 5.793 × 10 0 0.000 × 10 0 2.150 × 10 1 1.073 × 10 0 2.076 × 10 14
F 16 Mean2.080 × 10 1 3.878 × 10 14 2.167 × 10 1 0.000 ×  10 0 9.597 × 10 1 2.067 × 10 0 4.049 × 10 1
Std8.058 × 10 0 1.339 × 10 13 7.864 × 10 0 0.000 × 10 0 2.736 × 10 1 3.886 × 10 0 1.051 × 10 2
F 17 Mean5.000 × 10 0 1.751 × 10 7 6.099 × 10 15 5.507 ×  10 15 8.183 × 10 1 3.490 × 10 0 1.158 × 10 12
Std8.102 × 10 1 8.547 × 10 7 1.803 × 10 15 1.656 × 10 15 6.928 × 10 1 7.937 × 10 0 1.646 × 10 12
F 18 Mean1.386 × 10 0 1.184 × 10 13 9.036 × 10 4 0.000 ×  10 0 1.534 × 10 2 0.000 ×  10 0 3.938 × 10 15
Std2.809 × 10 1 5.123 × 10 13 2.856 × 10 3 0.000 × 10 0 2.036 × 10 2 0.000 × 10 0 3.047 × 10 15
F 19 Mean2.890 × 10 3 1.782 × 10 9 2.272 × 10 4 3.265 ×  10 57 5.072 × 10 3 1.060 × 10 4 1.652 × 10 14
Std1.243 × 10 2 3.270 × 10 9 7.865 × 10 4 1.437 × 10 56 4.089 × 10 3 2.878 × 10 4 1.204 × 10 14
F 20 Mean1.473 × 10 0 3.536 ×  10 10 1.040 × 10 2 5.339 × 10 10 5.595 × 10 1 7.583 × 10 2 8.704 × 10 1
Std8.628 × 10 1 2.116 × 10 10 3.692 × 10 2 2.591 × 10 10 5.458 × 10 1 2.722 × 10 2 1.443 × 10 1
F 21 Mean1.095 × 10 1 4.040 × 10 1 1.986 ×  10 1 6.401 × 10 1 2.134 × 10 0 1.435 × 10 0 4.954 × 10 0
Std7.068 × 10 0 3.868 × 10 1 3.389 × 10 1 5.245 × 10 1 2.113 × 10 0 3.360 × 10 1 1.596 × 10 1
F 22 Mean6.665 × 10 2 2.451 × 10 10 2.741 × 10 3 1.077 ×  10 80 1.316 × 10 1 1.513 × 10 36 1.302 × 10 21
Std2.995 × 10 1 8.827 × 10 10 5.282 × 10 3 3.542 × 10 80 1.770 × 10 1 3.101 × 10 36 3.949 × 10 21
F 23 Mean1.836 × 10 1 1.769 × 10 1 1.900 × 10 1 1.395 × 10 1 8.792 ×  10 2 6.202 × 10 0 2.488 × 10 1
Std5.037 × 10 1 3.862 × 10 1 3.908 × 10 1 1.084 × 10 1 2.203 × 10 1 2.122 × 10 0 3.279 × 10 0
F 24 Mean7.653 × 10 0 0.000 ×  10 0 5.258 × 10 1 0.000 ×  10 0 7.259 × 10 0 6.534 × 10 0 1.832 × 10 0
Std9.000 × 10 0 0.000 × 10 0 8.550 × 10 1 0.000 × 10 0 4.673 × 10 0 3.388 × 10 0 2.790 × 10 0
F 25 Mean2.261 × 10 1 5.679 × 10 2 3.980 × 10 1 3.286 ×  10 2 3.177 × 10 0 3.383 × 10 1 7.466 × 10 1
Std5.471 × 10 0 4.972 × 10 2 2.258 × 10 16 4.553 × 10 2 8.810 × 10 1 1.214 × 10 1 2.313 × 10 1
F 26 Mean3.129 × 10 0 4.385 × 10 15 0.000 ×  10 0 0.000 ×  10 0 2.479 × 10 1 0.000 ×  10 0 1.552 × 10 14
Std1.848 × 10 0 1.532 × 10 14 0.000 × 10 0 0.000 × 10 0 4.433 × 10 1 0.000 × 10 0 8.417 × 10 16
Table 5. Friedman test statistical results of seven algorithms.
Table 5. Friedman test statistical results of seven algorithms.
FunctionSum of SquaresDegree of FreedomMean Squaresp-Value
F 1 826.6676137.7781.372 × 10 35
F 2 770.6676128.4444.81761 × 10 33
F 3 814.0676135.6785.13321 × 10 35
F 4 821.3336136.8892.39823 × 10 35
F 5 704.8676117.4784.65662 × 10 30
F 6 591.533698.58896.18862 × 10 25
F 7 69061153.39314 × 10 36
F 8 821.5336136.9221.72524 × 10 35
F 9 836.2676139.3785.01757 × 10 36
F 10 440.933673.48893.53761 × 10 18
F 11 836.2676139.3785.01757 × 10 36
F 12 730.26121.73.30782 × 10 31
F 13 5406903.39314 × 10 36
F 14 536.233689.37221.27613 × 10 33
F 15 737.656122.9424.72241 × 10 34
F 16 643.4676107.2443.58476 × 10 28
F 17 742.0836123.6814.75385 × 10 32
F 18 724.9176120.8191.97730 × 10 33
F 19 648.4676108.0781.66346 × 10 27
F 20 727.9336121.3224.19129 × 10 31
F 21 683.4676113.9114.33937 × 10 29
F 22 713.8676118.9781.82038 × 10 30
F 23 562.667693.77781.23609 × 10 23
F 24 590.25698.3755.55632 × 10 27
F 25 817.86136.32.83026 × 10 35
F 26 719.3336119.8898.82755 × 10 35
Table 6. The statistical results of the Wilcoxon rank-sum test for seven algorithms.
Table 6. The statistical results of the Wilcoxon rank-sum test for seven algorithms.
FunctionmodMAMAmodMA-1modMA-2PSOGWOBOA
F 1 N / A 3.020 × 10 11 3.020 × 10 11 4.504 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 2 N / A 3.020 × 10 11 3.020 × 10 11 5.494 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 3 N / A 3.020 × 10 11 3.020 × 10 11 4.504 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 4 N / A 3.020 × 10 11 3.020 × 10 11 7.773 × 10 9 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 5 N / A 3.848 × 10 3 2.151 × 10 2 3.265 × 10 2 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 6 N / A 3.020 × 10 11 1.518 × 10 3 1.058 × 10 3 3.020 × 10 11 3.368 × 10 4 5.369 ×  10 2
F 7 N / A N / A N / A N / A 1.685 × 10 14 1.212 × 10 12 1.212 × 10 12
F 8 N / A 2.113 × 10 11 2.113 × 10 11 5.561 ×  10 1 2.113 × 10 11 2.113 × 10 11 2.113 × 10 11
F 9 N / A 3.020 × 10 11 3.020 × 10 11 4.975 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 10 N / A 6.627 ×  10 1 3.020 × 10 11 1.761 ×  10 1 1.067 × 10 7 3.020 × 10 11 3.020 × 10 11
F 11 N / A 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 12 N / A 3.338 × 10 11 1.273 × 10 2 2.581 ×  10 1 3.020 × 10 11 6.722 × 10 10 3.020 × 10 11
F 13 N / A N / A N / A N / A 1.212 × 10 12 N / A 1.212 × 10 12
F 14 N / A 5.584 × 10 3 N / A N / A 1.212 × 10 12 N / A 1.212 × 10 12
F 15 N / A 1.212 × 10 12 1.836 × 10 10 1.212 × 10 12 1.212 × 10 12 5.542 × 10 3 3.337 ×  10 1
F 16 N / A 1.212 × 10 12 1.171 × 10 12 1.212 × 10 12 1.212 × 10 12 8.814 × 10 7 2.788 × 10 3
F 17 N / A 1.015 × 10 11 1.015 × 10 11 1.910 ×  10 1 1.015 × 10 11 7.763 × 10 12 1.014 × 10 11
F 18 N / A 1.212 × 10 12 1.206 × 10 12 8.152 ×  10 2 1.212 × 10 12 N / A 4.523 × 10 12
F 19 N / A 3.020 × 10 11 3.020 × 10 11 3.690 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 20 N / A 3.020 × 10 11 2.266 × 10 3 5.106 ×  10 1 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 21 N / A 3.690 × 10 11 2.608 × 10 2 1.529 × 10 5 7.697 × 10 4 5.092 × 10 8 3.020 × 10 11
F 22 N / A 3.020 × 10 11 3.020 × 10 11 4.077 × 10 11 3.020 × 10 11 3.020 × 10 11 3.020 × 10 11
F 23 N / A 1.501 × 10 2 7.062 ×  10 1 6.627 ×  10 1 5.555 × 10 2 3.020 × 10 11 3.020 × 10 11
F 24 N / A 1.212 × 10 12 N / A 4.777 × 10 8 1.212 × 10 12 1.212 × 10 12 1.455 × 10 4
F 25 N / A 2.772 × 10 11 9.762 × 10 3 1.182 × 10 12 2.930 × 10 11 2.964 × 10 11 2.964 × 10 11
F 25 N / A 1.212 × 10 12 3.428 × 10 7 N / A 1.212 × 10 12 N / A 1.167 × 10 12
Table 7. Space environment settings.
Table 7. Space environment settings.
Case NumberSerial NumberObstacle CenterObstacle Radius
11(50, 105)70
2(125, 250)35
3(304, 400)45
4(404, 320)50
5(440, 440)20
6(280, 310)25
7(230, 220)25
8(230, 100)50
21(160, 160)15
2(50, 105)70
3(275, 185)80
4(400, 425)40
5(125, 250)35
6(275, 325)28
7(450, 250)45
8(175, 410)70
9(35, 325)50
10(330, 300)25
Table 8. The average and standard deviation values of the total cost function over thirty runs.
Table 8. The average and standard deviation values of the total cost function over thirty runs.
Case NumberDResultsMAmodMA-1modMA-2modMABOAPSOGWO
130Avg705.432690.146692.234689.532711.309698.138693.970
Std6.1991.1463.3131.0147.4556.8972.749
50Avg753.834699.756723.285698.312720.847739.353710.557
Std18.1432.82211.3901.41913.54918.4219.951
230Avg717.855692.493693.226691.735711.219694.774694.458
Std10.7181.7295.0871.3594.1803.2731.675
50Avg781.436703.315747.785702.119721.602732.321710.133
Std28.5573.12323.1301.9786.18912.1677.973
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Wang, X.; Pan, J.-S.; Yang, Q.; Kong, L.; Snášel, V.; Chu, S.-C. Modified Mayfly Algorithm for UAV Path Planning. Drones 2022, 6, 134. https://0-doi-org.brum.beds.ac.uk/10.3390/drones6050134

AMA Style

Wang X, Pan J-S, Yang Q, Kong L, Snášel V, Chu S-C. Modified Mayfly Algorithm for UAV Path Planning. Drones. 2022; 6(5):134. https://0-doi-org.brum.beds.ac.uk/10.3390/drones6050134

Chicago/Turabian Style

Wang, Xing, Jeng-Shyang Pan, Qingyong Yang, Lingping Kong, Václav Snášel, and Shu-Chuan Chu. 2022. "Modified Mayfly Algorithm for UAV Path Planning" Drones 6, no. 5: 134. https://0-doi-org.brum.beds.ac.uk/10.3390/drones6050134

Article Metrics

Back to TopTop