2
Views
0
CrossRef citations to date
0
Altmetric
Research Article

Path Planning of UAV Using Levy Pelican Optimization Algorithm In Mountain Environment

, , , , &
Article: 2368343 | Received 04 Jul 2023, Accepted 07 Jun 2024, Published online: 16 Jun 2024

ABSTRACT

To overcome the issues of simple strategy and easy fall into local optimum when solving UAV 3D path planning problem, we propose an improved Levy Pelican Optimization Algorithm (LPOA) that incorporates the hunter-prey algorithm and solves the UAV 3D path planning problem based on the improved LPOA. Based on the original algorithm, on the one hand, we introduce Levy flight and adaptive parameters to update the pelican position, balance the algorithm development phase and exploration phase, and effectively avoid the problem of falling into local optimum at the early stage of the algorithm. On the other hand, we use chaotic mapping to initialize the population, integrate the prey generation strategy to enhance the prey generation formula and improve algorithm orientation and convergence speed. The test results are compared and analyzed with those of classical, current mainstream, and recently released swarm intelligence optimization algorithms. Using 3D mountain range model experiments, the algorithm is compared before and after optimization, and the improved optimization algorithm is then applied to the actual problem of UAV 3D path planning. Research has found that the improved LPOA optimizes the total target cost of the algorithm by 9.75% and optimizes the planned average shortest path by 20.30%.

Introduction

In recent years, UAVs have been widely used in the fields of traffic inspection, disaster rescue, surveillance, and investigation because of their small size and easy operation. Nowadays, drone technology has developed relatively maturely and has been widely commercialized. Intelligence and convenience have become one of the main development directions for drones. However, as the difficulty of application scenarios gradually increases, people’s demand for the intelligence level of drones is also increasing. In the existing literature, the vast majority of studies have transformed the path-planning problem of unmanned aerial vehicles from a three-dimensional environment to a two-dimensional plane for algorithmic analysis. However, in practical work, drones face more complex and uncertain environments. Therefore, in the modeling of drone flight environments, this paper introduces terrain factors and threat areas, and conducts path planning research on this basis.

As a crucial component of UAV intelligence, 3D path planning is a hot topic for current study in the field of intelligent control and decision-making. The purpose of drone path planning is to delineate a reasonable path for drones from their departure point to their destination in order to meet flight safety and short-range requirements. Its essence is the optimal or approximate optimal feasible solution under multiple constraint conditions. The optimization problem is a hot topic in today’s scientific research, social life, and engineering practice. The research in this direction focuses on transforming specific problems into mathematical models and optimizing solutions. For example, in industrial design, how to select appropriate design parameters to minimize the consumption of manpower, material resources, and financial resources while meeting design requirements; How to allocate limited resources in the most efficient way in the overall allocation of resources. On the one hand, optimization problems need to consider balance and specificity; on the other hand, they need to achieve maximum overall benefits. Many optimization problems need to be solved in areas such as business management, artificial intelligence, and system control.

Numerous academics have worked to increase the effectiveness of UAV path planning, and the use of optimization algorithms has significantly increased this capability. Currently, Ant Colony Algorithm (Yang, Chen, and Ye Citation2022), Particle Swarm Algorithm (Wang et al. Citation2023), Bee Colony Algorithm (Hao, Luo, and Zhang Citation2021), and Gray Wolf Optimization Algorithm (Yu et al. Citation2023) are widely used in UAV path planning problems. However, each of these algorithms has its own shortcomings, such as sluggish convergence and entering the local optimum too early, which make it impossible to ensure the precision of UAV search and the path planning limitations.

The Pelican Optimization Algorithm (POA) (Trojovský and Dehghani Citation2022) was proposed by Pavel Trojovský and Mohammad Dehghani in 2022, which simulates the natural behavior of pelicans during hunting. Compared to classic optimization algorithms such as GA, PSO, and GWO, the performance of the Pelican optimization algorithm has greatly improved. However, the original Pelican Optimization Algorithm (POA) has shortcomings in avoiding local optima and achieving adequate algorithmic accuracy in practical applications of UAV path planning.

To address these shortcomings, we propose an improved LPOA to optimize the UAV 3D path. The improved LPOA has three main enhancements: First, the pelican population is initialized using chaotic mapping (Logistic), which increases diversity; Second, the Levy flight strategy and adaptive parameter adjustment strategy are introduced to improve the algorithm’s early optimal discovery ability and successfully combat the issue that the algorithm tends to fall into local optima; Finally, by incorporating hunter-prey algorithms, we introduce prey generation strategies to increase algorithm orientation, improve algorithm convergence speed, and balance development capability and local exploration capability. Finally, its feasibility in solving the UAV 3D path planning problem is verified by experimental simulation.

In order to solve the problems of difficult and inefficient path planning for drones in mountainous areas, this paper introduces chaotic mapping to make the algorithm population initialization more stochastic, ergodic and regular, the integration of Pelican Optimization Algorithm and Hunter Prey Optimization Algorithm to increase the orientation of the algorithm in the development stage, and introducing adaptive parameter adjustment and Levy flight update strategies to improve the development capability of the algorithm and its ability not easily to fall into local optimum. In addition, a 3D mountain range model is created to simulate how the improved LPOA would be used in the real-world UAV flight problem.

In summary, our main contributions are as follows:

  • We propose a Pelican optimization algorithm based on Levy flight and integrate the Hunter prey algorithm to optimize prey generation and update strategies. To our knowledge, this is the first attempt to integrate Hunter prey and Pelican algorithms. Experimental results have shown that the improved algorithm achieves better results in finding the optimal solution and solving unmanned aerial vehicle path planning problems.

  • We also introduce chaotic mapping and survival of the fittest strategy into the Pelican optimization algorithm, making the prey more strategic in the generation process and enhancing the algorithm’s ability to find optimal solutions and jump out of local optima. Using benchmark functions to validate the performance of the improved LPOA, it was found that compared to classical optimization algorithms, LPOA has stronger performance and faster convergence speed.

  • We apply the improved Pelican optimization algorithm to the three-dimensional path planning problem of unmanned aerial vehicles (UAVs) and evaluate the reliability of the improved LPOA model in UAV three-dimensional path planning. Compared with the pre-optimized Pelican algorithm, it was found that the optimized algorithm can achieve shorter and safer paths compared to the pre-optimized algorithm.

The rest of this paper is organized as follows: In Section II, we provide a review and overview of related works on UAV path optimization. In Section III, we introduce the basic theory of the Pelican Optimization Algorithm and UAV path planning. In Section IV, we give the improved LPOA model. In Section V, we use benchmark functions to verify the performance of the improved LPOA and to evaluate the reliability of the improved LPOA model for UAV 3D path planning. The convergence speed, accuracy, and stability of the improved LPOA algorithm are discussed in Section VI. Finally, we conclude and give some future work in Section Ⅶ.

Related Work

Numerous approaches have been put out for the UAV path planning problem in the research process, including the Artificial Potential Field Method, Rapid Exploration Random Tree (RRT) (Chen et al. Citation2016), and A* search algorithm. Chen et al. (Citation2016). reformulated the UAV path planning problem as a constrained optimization problem by introducing additional control forces to improve the artificial potential field method and applying the function optimization method will solve the UAV path planning problem. Kothari, Postlethwaite, and Gu (Citation2009) developed an algorithm for fast path generation based on RRT by considering the kinematic constraints of the UAV, where the path planner automatically identifies a dynamic obstacle and avoids it according to the criteria. Tian et al. (Citation2020). solved the UAV path planning model by improving the A* and gravitational search algorithms to plan the optimal path with the heading angle and return point of the agricultural UAV as the optimization objectives. Although traditional methods can solve the UAV path planning problem, they require a lot of computational time and resources.

The population intelligence optimization technique is a stochastic optimization method based on population iteration, which uses the population simulation behavior of animals or other populations to approximate some optimization problems that are difficult to solve directly. Numerous algorithms based on swarm intelligence optimization have been widely validated and applied, including genetic algorithm, particle swarm algorithm, bee swarm algorithm, gray wolf optimization algorithm, whale optimization algorithm, etc. With increased computer computing power, swarm intelligence optimization algorithms can obtain better results without consuming too much computing time. Therefore, several swarm intelligence optimization algorithms with superior characteristics are proposed and applied to the field of path planning.

Punitha and Geetha (Citation2023) used a POA-based hyperparameter tuning technique to tune the hyperparameters (ephemeris, batch size, and learning rate) of Deep Belief Network (DBN) methods. Hu et al. (Citation2018) introduced a new logic mapping-based approach to improve Pigeon-Inspired Optimization (PIO) to optimize the UAV path planning problem considering a large number of static and dynamic constraints. Yang et al. (Citation2019) proposed an improved Random Chemical Reaction Optimization algorithm(RMCRO)based on a dual containers strategy. Prashant, Anupam, and Ritu (Citation2018). applied the Glowworm Swarm Optimization(GSO) to the UAV 3D path planning problem. Radmanesh, Kumar, and Sarim (Citation2018). used the Gray Wolf Optimization (GWO) algorithm in a Bayesian framework to solve the UAV trajectory planning problem in the presence of moving obstacles that encounter unknown trajectories. Ali et al. (Citation2023) Propose a combination of maximum minimum ant colony optimization and differential evolution, and apply it to the path planning problem of multiple unmanned aerial vehicles.

Unimproved swarm intelligence algorithms generally suffer from difficulties in jumping out of local optimum, early maturity, and imbalance between global and local exploration capabilities, and to address these problems, Zhang et al. (Citation2018) proposed a new phase-angle encoded fruit fly optimization algorithm with variational adaptation mechanism applied to UAV path planning. Liu, You, and Liu (Citation2018) proposed a heuristic-based dynamic pheromone update strategy to improve the ACO algorithm based on the traditional ACO algorithm, which accelerated the convergence speed and improved the search effect of the algorithm. Fang, Yu, and Wang (Citation2010) introduced the constraints of the UAV into the PSO algorithm, thus reducing the search space of the algorithm and improving the solution speed of the algorithm. Chen and Fei (Citation2017) proposed an improved method based on spherical vectors for solving the path planning problem of UAVs in complex environments, considering the correspondence between the intrinsic constraints of UAVs and the search space. The improved LPOA has stable convergence and improves the safety and feasibility of generated paths. Huang et al. (Citation2021) enhanced the global exploration capability of the algorithm by introducing cross-variance operators and adaptive weights in the mothballing optimization algorithm, and enabled the UAV to quickly avoid the dangerous area and choose the optimal path. Du et al. (Citation2021). applied the whale optimization algorithm based on Levy flight to UAV 3D trajectory planning, which well balanced the local convergence and global exploitation capability of the algorithm.

The Pelican Optimization Algorithm is a meta-heuristic algorithm with a simple structure and few parameters, which simulates the natural behavior of pelicans during the hunting process. In this paper, POA is used as the basis of the improvement algorithm because of its simple structure and easy implementation. POA has only one control parameter in the global exploration phase and a single update strategy in the local exploration phase. It can be flexibly applied to many engineering problems without changing its own structure. It provides a derivative-free mechanism, similar to other population-based meta-heuristic algorithms, to optimize problems stochastically without computing derivatives. It relies on a linear parameter to achieve a balance between global and local exploration, which can effectively prevent the population from falling into a local optimum. In this paper, the POA is improved by combining a chaotic mapping-based initialization with a Levy flight strategy to enhance the ability of the algorithm to jump out of being trapped in a local optimum, and by incorporating a hunter-prey algorithm to increase the orientation of the global exploration phase and introducing an adaptive parameter adjustment strategy to balance global exploration and local exploitation. The proposed improved LPOA is used to realize the path planning under the UAV 3D model.

Theoretical Analysis

Principle of Pelican Optimization Algorithm

The Pelican Optimization Algorithm simulates the behavior and strategy of pelicans when attacking and hunting prey in two phases: approaching prey and surface flight phase. The Pelican Optimization Algorithm (POA) is mathematically modeled according to the hunting stage as follows:

Global Exploration Phase

In the first stage, the pelicans determine the location of the prey and then move toward this determined area. Modeling this pelican’s strategy, the mathematical expression for the pelican’s behavior during this phase is as follows:

(1) xi,jP1=xi,j+randpjIxi,j,Fp<Fixi,j+randxi,jpj,else(1)
(2) Xi=XiP1,FiP1<FiXi,else(2)

where xi,jP1 is the position of the jth dimension based on the i-th pelican after the first stage update; Fi is the corresponding objective function value; I is a random integer of 1 or 2; rand is a random number in the range [0,1];pj is the position of the jth dimension of the prey;Fp is the value of the objective function corresponding to the prey;XiP1 is the location of the population after the development phase.

Local Exploration Phase

As the pelicans close in on their prey, they spread their wings over the water and then collect the prey in their throat pouch. This strategy allows the pelicans to catch more fish in the attack area. Modeling this behavior of pelicans enables the proposed POA to converge to better points in the hunting area. This process increases the ability of POA to explore globally and exploit locally. From a mathematical point of view, the algorithm must check the points near the pelican position to converge to a better solution. This behavior of pelicans during hunting was mathematically modeled as follows:

(3) xi,jP2=xi,j+R1tT2rand1xi,j(3)
(4) Xi=XiP2,FiP2<FiXi,else(4)

where xi,jP2 is the position of the jth dimension based on the i-th pelican after the second stage update;Ris a random integer of 0 or 2;tis the number of current iterations of the algorithm;Tis the maximum number of iterations of the algorithm.

POA has high convergence accuracy and good stability, but still has the following limitations:

  1. In the process of population initialization, the distribution of initial solutions is random and uneven, and the quality of individuals in the population varies, which can easily lead to a lack of population diversity and thus miss the potential optimal solution.

  2. The location update strategy of POA is simple, and the algorithm can easily lead the algorithm into local optimum during the development of the search process.

  3. The update iteration of POA is linear, which not only makes it difficult to balance the development phase and the local exploration phase, but also tends to lead to too little space for algorithms to explore in the pre-development phase, thus making it difficult to explore the space where the optimal solution is located, and to fail to converge to the location where the optimal solution is located in the later local exploration process because the exploration range is too large.

UAV Path Planning Cost Function

Route Cost Function

The path cost function is a function set to find the shortest path from one node to another in the UAV flight path to calculate the cost of passing through each node. In the path planning algorithm, the path cost function is used to evaluate the value of each node in order to select the node that is most likely to result in the shortest path for expansion. By continuously selecting the node with the smallest value for expansion, the algorithm can find the shortest path from the starting point to the endpoint. Common estimation methods include Manhattan distance, Euclidean distance, etc. The route cost function L is expressed as follows:

(5) L=i=1N1xi+1xi2+yi+1yi2+zi+1zi2(5)

where N denotes the total number of points in the flight path of the UAV,(xi,yi,zi)denotes the coordinates of point i in the flight path of the UAV in the 3D coordinate system.

Smoothness Cost Function

UAV path smoothness can be measured by using curvature as a metric, where a smaller curvature indicates a smoother path. Therefore, using curvature as a cost function makes the path planning algorithm trade-off between path smoothness and path length. In the specific implementation, this paper uses spline curves to fit the paths, calculates the curvature of each section of the spline curve as a cost function, and assigns a smoothness penalty function. At the same time, a certain maximum curvature threshold is set to ensure the safe flight of UAVs, besides which the path segments will be discarded or re-planned. The smaller the flight angle of the drone, the safer the flight path. The smoothness cost function Q of the flight path is as follows:

(6) Q=i=1N1arccosIiIi+1||Ii||Ii+1||γq(6)

Where Q is the smoothness of the UAV flight path, Iiis the vector connected to point i and point i+1; γQis the UAV path smoothness penalty factor. If the actual turning angle of the flight path exceeds the constraint limit, it is set to infinity; the smaller the turning angle of the UAV flight, the safer the flight path is represented.

Flight Altitude Cost Function

UAV flight altitude cost function H:

(7) H=i=1Nγhhiha(7)

where γh is the penalty factor for the UAV flight altitude exceeding the constraint limits, set to infinity when the maximum and minimum ranges are exceeded, and to zero when it is within the constraint range;

Collision Threat Cost Function

Affected by environmental terrain, obstacles, no-fly zones, etc., UAV path planning needs to consider the threat cost of the environment, located in the path planning of the ith section of the path UAV approaching threat points or terrain collision objects. Setting the distance between the edge of the current UAV and the collision zone as D and the distance from the UAV to the center of the projected circle of the mountain range as di, the UAV and obstacle collision threat cost function B is as follows:

(8) B=i=1NγbD+Ridi(8)

Where, γb is the obstacle threat cost penalty factor, D is the distance from the peripheral collision zone to the mountain range. Set the projection of the mountain range collision threat zone as a circle, Ri as the radius, and di as the distance from the UAV to the center of the projected circle of the mountain range.

Total Cost Function

The path cost function, smoothness cost function, flight height cost function and collision threat cost function in the UAV path planning process are considered comprehensively to construct a multi-factor constrained target flight benefit function. Different cost functions have different degrees of influence on UAV path planning, and let their weight coefficients be v1, v2, v3, v4, respectively, so that the total benefit function of UAV path planning is:

(9) minF=v1L+v2Q+v3H+v4B(9)

where v1, v2, v3, v4 are weight parameters, L denotes the flight path length cost function of UAV, Q denotes the smoothness cost function of UAV flight path, H denotes the flight altitude cost function of UAV from the flight start point to the end point, and B denotes the collision threat cost function of UAV and obstacle.

Methodology

Logistic Chaos Initialization

Chaotic mapping is a nonlinear dynamical system with stochastic nature, which can be used in the optimization field to replace pseudo-random number generators for population initialization, selection, crossover and mutation operations to make the initial position of the population more uniform and ergodic. The random and uniform initialization distribution largely influences the whole process of the algorithm. The commonly used chaotic mapping methods are Logistics mapping (Alatas, Akin, and Ozer Citation2009; Wang et al. Citation2021), Singer mapping (Varol Altay and Alatas Citation2020), Sine mapping (Jin et al. Citation2022), and Cubic mapping (Feng et al. Citation2017; Zhang et al. Citation2021). In this paper, we choose the more widely used Logistics mapping with bistable and chaotic behavior to improve the Pelican Optimization Algorithm. shows the distribution map of Logistic chaotic maps.The Logistics mapping is defined as follows:

Figure 1. Logistic chaotic mapping distribution.

Figure 1. Logistic chaotic mapping distribution.

(10) ZN+1=μZN1ZN(10)

where ZN is the number of chaos in the range of 0,1 and μ is the control parameter.

Adaptive Adjustment of Weights

Adaptive adjustment is a process of automatically adjusting the size of weights according to the number of iterations of the algorithm during the iteration and evolution of the algorithm, so as to adapt them to the parameter characteristics and structural characteristics of the iteration of the algorithm under consideration, in order to optimize the convergence speed and convergence accuracy of the algorithm and balance the global exploration and local exploration phases. In the process of POA optimization solving, the linear inertia weight adjustment strategy is too simple and will affect the overall iteration speed of the algorithm. shows the simulation distribution of Levy’s flight strategy. Therefore, in this paper, a nonlinear adaptive weight is proposed to replace the linear weight in the global exploration phase of POA, defined as follows:

Figure 2. Schematic diagram of Levy’s flight.

Figure 2. Schematic diagram of Levy’s flight.

(11) α=e10tT2(11)
(12) xi,jP1=αxi,j+randαpjIxi,j,Fp<Fiαxi,j+randxi,jαpj,else(12)

where α is the adaptive weight, t is the number of current iterations of the algorithm, T is the maximum number of iterations of the algorithm, and pj is the position of the jth dimension of the prey.

Prey Guide Generation

The improved LPOA, incorporating the idea that the prey will iterate to a safe region in the hunter-prey algorithm, simulates the strategy formulation of the prey generation and iteration process to increase the orientation of the algorithm in the global exploration phase, improve the convergence speed of the algorithm, and help the algorithm jump out of the local optimal solution and avoid premature convergence of the algorithm. The improved prey generation strategy is as follows:

(13) pj=randmaxxi,ji=1Nxi,jcj212N1(13)

Where pj is the position of the jth dimension of the prey; cjis the average of each search agent that is the pelicans location.

Random Swimming Strategy

After the above prey generation strategy adjustment and improvement, although it improves the guiding ability of the algorithm in the global exploration stage, that is, the ability of the population individuals to gradually approach the optimal solution and the convergence speed of the algorithm, it also leads to the problem that the algorithm tends to fall into premature maturity in the later stage and cannot jump out of the local optimal solution. To address this problem, this paper introduces the Levy flight stochastic wandering strategy. Levy flight is a random wandering model, whose core idea is to simulate the random wandering process by random step length and direction, and the probability of its flight step length conforms to the heavy-tailed distribution, which means that the probability of random large span steps of population individuals is relatively high, which can well solve the problem of early convergence of the algorithm. The specific strategy approach is as follows: in the pelicans search prey stage, initialize the population position and speed, generate a random step and direction to simulate random wandering, and iterate according to the position update formula, compare the updated pelicans’ position with the original position for the fitness value, implement the principle of superiority and inferiority, and retain the position of individuals with higher fitness to complete the random wandering strategy of the algorithm. The equation for updating the position in conjunction with Levy’s flight is as follows:

(14) Xi=XiP1,FiP1<FiXi+aLevys,λ,else(14)
(15) Levys,λ=λβγλsinπλ2π1s1+λ(15)
(16) s=μv1β(16)

Where XiP1 is the population location after the development phase, a takes the value of 1, denotes point-to-point multiplication, Levys,λ is the Levy random search path, which denotes the step length of one Levy flight, s is the Levy flight path Lλ, the parameter β takes 1.5, and the parameters μ and v are normally distributed random numbers.

Non-Linear Adjustment Parameter

Once the pelicans reach the surface, they spread their wings over the water, forcing the fish to move upward, and then prey on its prey with its throat pouch. This strategy of surface flight by pelicans allows them to catch more fish in their strike zone. This behavioral process of pelicans was modeled and the original linear adjustment parameters were set to nonlinear exponentially decreasing parameters to increase the local search ability and exploitation of the POA, making the POA converge to a better location in the hunting area. From a mathematical point of view, the algorithm is iterated with the algorithm and the radius of the pelican’s exploration neighborhood is subsequently reduced so that it can converge to a better position. This behavior of pelicans during hunting was mathematically modeled as:

(17) xi,jP2=xi,j+Re30tT22rand1xi,j(17)
(18) Xi=XiP2,FP2i<Fi   Xi,else(18)

Where xi,jP2 is the position of the jth dimension based on the ith pelican after the second stage update; R is a random integer of 0 or 2; t is the number of current iterations; and T is the maximum number of iterations.

Improved LPOA Design

The LPOA algorithm is a hybrid of the Hunter Hunt Algorithm (HPO) and the POA algorithm, based on the Pelican Optimization Algorithm and incorporating the hunter-hunting strategy in HPO. With the idea that prey will autonomously choose a safe location, it replaces the strategy of randomly generating prey in POA. There are three main improvements to the fusion algorithm: firstly, using chaotic mapping (Logistic) to initialize the Pelican population to increase diversity and accelerate the convergence speed of the algorithm; Secondly, by integrating hunter-prey algorithms and introducing prey generation strategies to increase algorithm directionality, improve algorithm convergence speed, and balance development and local exploration capabilities. Thirdly, introducing the Levy flight strategy and adaptive parameter adjustment strategy to enhance the algorithm’s ability to discover the optimal region, increase the algorithm’s ability to jump out of local optima, and effectively avoid the algorithm falling into local optima.

Let the initial number of particles be N and the maximum number of iterations be T. The number of groupings is determined according to the initial fitness, and the specific algorithm flow is as follows:

Step 1: Determine the overall size N and the number of iterations T of the improved LPOA and determine the values of each parameter set;

Step 2: Logistic chaos mapping to initialize the population and calculate the objective function;

Step 3: Determination of prey location based on prey generation algorithm (8);

Step 4: Introduction of an adaptive weight-adjusted population update formula to calculate the new position of an individual in the jth dimension using Equationequation (7);

Step 5: Determine whether the conditions are met. If the condition is met, execute Step 6, otherwise execute Step 4;

Step 6: Introducing the Levy flight strategy to update individual positions, calculating individual fitness using Equationequation (9), and retaining the individual optimal solution and the global optimal solution;

Step 7: Calculation of the new position of the individual in the jth dimension using Equationequation (12);

Step 8: Judge whether the conditions are met. Execute Step 8 if the condition is met, otherwise calculate the individual fitness using Equationequation (9) and retain the individual optimal solution and the global optimal solution;

Step 9: Determine the individual fitness value according to the objective function and retain the location of the individual with the maximum fitness value as the location where the prey will appear in the next population iteration;

Step 10: We determine whether the maximum number of iterations is reached, if so, we combine the interpolation method to find the best path, otherwise we iterate the population according to the same update strategy until the condition is satisfied.

The flow chart of the improved LPOA is shown in . Firstly, use Equationequation (5) to initialize the population, then use Equationequation (8) to generate prey positions. Calculate the new positions of the population individuals using Equationequation (7). After that, adopt Equationequation (9) to calculate and retain the optimal positions of the individuals. Next, apply Equationequation (12) to update the individual positions again, employ Equationequation (13) to retain the optimal positions of the individuals, retain the global optimal solution, and mark them as prey positions for the next iteration. When the iteration limit is reached, the Output optimal solution and optimal parameters of the BP neural network.

Figure 3. Flow chart of improved LPOA.

Figure 3. Flow chart of improved LPOA.

Experiments and Results Analysis

Baseline Test Function

For the purpose of objectively evaluating the effectiveness of various metaheuristic algorithms and verifying the effectiveness of improved LPOA, we selected eight more typical standard test functions to evaluate the capability of improved LPOA using CEC2017 test functions. The functions F1-F4 are single-peaked functions, all of which have only one global optimal solution, and are used to measure the speed and accuracy of the convergence of the algorithm. Functions F8 and F11 are multi-peaked functions with one global optimum and multiple local optimum multimodal for estimating the global search and mining capability of the algorithm. The specific expressions, dimensions, search ranges and theoretical optimal solutions of these benchmark functions are shown in . For a more intuitive understanding of these benchmark functions and their optimal values, shows a 3D view of the functions (30 dimensions).

Figure 4. The parameter space diagram of the benchmark function.

Figure 4. The parameter space diagram of the benchmark function.

Table 1. Details of the benchmark functions.

Comparison of Different Algorithms

To verify the performance of the proposed improved LPOA in solving optimization problems, we evaluate the capability of the improved LPOA through the use of the CEC2017 test function. Improved LPOA solves the objective function for several different types of single and high-dimensional multi-peaks and compares it with several well-known optimization algorithms. These competing algorithms include: (i) popular methods: Genetic Algorithm (GA) (Goldberg and Holland Citation1988) and Particle Swarm Algorithm (PSO) (Kennedy and Eberhart Citation1995); (ii) popular and highly cited methods: Grey Wolf Optimization (GWO) (Mirjalili, Mirjalili, and Lewis Citation2014) and Whale Optimization Algorithm (WOA) (Mirjalili, Lewis, and Lewis Citation2016); and (iii) a recently published method: Marine Predator Algorithm (MPA) (Faramarzi et al. Citation2020).

The experiments were implemented on Windows 11 operating system with an 11th generation AMD Ryzen 7 4800 H processor, 2.9 GHz and 16 GB RAM, and simulated on MATLAB 2019a, with all algorithm parameters chosen to have a population size of 30, a maximum number of 1000 iterations and 30 runs. The average fitness and standard error of fitness of the improved LPOA and its comparative algorithms are shown in , where bold values indicate the best results. Details of the benchmark functions used are shown in , the parameter space diagram is shown in , the comparison results are shown in and the comparison iterations are shown in .

Figure 5. Algorithm comparison iteration diagram.

Figure 5. Algorithm comparison iteration diagram.

Table 2. Comparison of the performance of the algorithms in the benchmark function.

As shown in , in the F1 and F3 single-peaked benchmark function tests, the improved LPOA was able to search for the optimal solution of the function, and in the F2 and F4 benchmark functions, the optimal solutions obtained were significantly better than other swarm intelligence algorithms, which included the unimproved LPOA; meanwhile, in the F8 and F11 multi-peaked function tests, the improved LPOA had stronger global search and local mining capabilities, as well as greater stability. In summary, the improved LPOA performs significantly better than the classical swarm intelligence algorithm and POA in the above benchmark functions, which have better ability to approach the optimal solution and outperform other swarm intelligence algorithms in the local exploration phase of development.

Statistical Analysis

To further evaluate the validity of the suggested enhancement tactics, this paper used a Wilcoxon signed-rank test to compare LPOA with six meta-heuristic algorithms and applied the Friedman test (EquationEquation (14)) to calculate each algorithm’s ranking. The number of populations N = 30 was set, each test function was subjected to 30 independent runs of each algorithm, dimension D = 30, and the Wilcoxon signed-rank test with α = 0.05 was implemented for LPOA and other algorithms on 6 test functions. The α-values are presented along with statistics for “}}+,” “}}−” and “}} =.” “}}+” shows that LPOA clearly outperforms other comparison algorithms, “}}−” indicates inferiority, and “}} =” denotes no significant difference. N/A represents not applicable when both searches for superiority result in 0, indicating a comparable performance. Bold text indicates insignificant or comparable differences.

(19) Ff=12nkk+1ΣjRj2kk+124(19)

Where n is the count of case tests, k is the quantity of algorithms, and Rj is the mean ranking of the j th algorithm.

shows the results of Friedman’s test. The LPOA algorithm has a lower average ranking value than that of the other algorithms, indicating its superior performance. Moreover, reveals that the LPOA algorithm’s mean value decreases relative to POA as dimensionality increases. This shows that LPOA is more robust in higher dimensions than POA and further verifies the effectiveness of our optimization strategy.

Table 3. Order by Friedman test in dimensions D = 30.

Experiment Settings and Results Analysis

To verify the feasibility of the algorithm designed in this paper in solving the UAV 3D path planning problem, we use MATLAB software for experimental simulation. The map of this simulation is referred to the map in the literature (Lin et al. Citation2023), and the model size is set to: 100 km *150 km *30 km. The specific steps are: decoding the data table containing the model parameters, setting the starting and ending points of the UAV flight, getting the base path of the flight, after initially setting the rough navigation points, further obtaining the fine navigation points by interpolation, and determining the UAV flight coordinates by the spline difference method, and the obtained coordinates and parameters are applied to the proposed improved LPOA for iterative updates. To model the threat area, we use a bar chart to represent the threat area. Using the Euclidean distance to calculate the shortest path of UAV flight, set the penalty function method to constrain the target cost function, the penalty coefficient parameters and other algorithm parameters are set as shown in , the simulation comparison results are shown in , the simulation results are shown in .

Figure 6. Simulation result graph.

Figure 6. Simulation result graph.

Figure 7. Comparison of algorithm iterations.

Figure 7. Comparison of algorithm iterations.

Table 4. Partial parameters of the algorithm.

Table 5. Statistics of experimental results.

Comparing the results of two sets of experiments, it can be seen that when the two algorithms are used for UAV 3D path planning, compared with POA, the improved LPOA increases the average calculation time of the algorithm by 11.85%, optimizes the total target cost by 9.75%, and optimizes the average shortest path planned by 20.30%. Although the improved LPOA is not as good as POA in terms of operation time and iteration times, it is significantly better than POA in terms of planning the shortest path and stability. This indicates that the improved LPOA has stronger ability to search for optimal solutions and autonomously jump out of local optima, and the search range is also wider. Overall, the improved LPOA is more suitable for UAV 3D path planning.

Discussions

After comprehensive analysis of the benchmark function test results, convergence curves, and Wilcoxon sign rank test results of each algorithm, it is found that the LPOA algorithm has significantly improved local and global detection capabilities. It surpasses our compared GA, GWO, original POA algorithms, and other optimization algorithms in terms of convergence speed, accuracy and stability. However, the same finding is that although the improved LPOA algorithm achieves higher accuracy and convergence speed in peak functions, its stability is sometimes not as good as the original POA algorithm. This is a problem that we will pay attention to and solve in the future.

Conclusion

To address the problems of high computational complexity and difficulty in deriving the shortest path in the UAV 3D path planning problem, this paper proposes an improved LPOA based on the UAV 3D path planning problem, which addresses the problems of the original pelican optimization algorithm such as simple strategy and easy to fall into local optimality, incorporates the hunter-prey algorithm to increase the algorithm orientation, and introduces Levy flight and adaptive weights to update the pelican position, and uses chaotic mapping to initialize the population to improve the convergence speed. In order to verify the effectiveness of the proposed improved LPOA, a comparative benchmark function test with the classical algorithms of GA, PSO, GWO, WOA, etc., in addition to the experimental simulation comparison of POA and the improved LPOA with MATLAB, verifies the feasibility and effectiveness of the improved LPOA in solving the UAV 3D path planning problem. The experimental results show that the improved LPOA has stronger exploitation and local search capability in addition to better stability of the planned paths. The future research direction will try to integrate with classical algorithms such as GWO to solve the problem that the algorithm is easy to fall into local optimum on the composite function.

Author Contributions

Conceptualization, G.Z. and L.M.; methodology, S.L. and G.Z.; software, S.L.; formal analysis, S.L. and K.X.; investigation, T.B. and X.B.; resources, G.Z. and L.M.; data curation, S.L.; writing – original draft preparation, S.L. and K.X.; writing – review and editing, G.Z. and L.M.; visualization, S.L. and K.X.; supervision, G.Z. and L.M.; project administration, G.Z.; funding acquisition, G.Z. and L.M. All authors have read and agreed to the published version of the manuscript.

Disclosure Statement

No potential conflict of interest was reported by the author(s).

Data Availability Statement

The data used to support the findings of this study are included within the article.

Additional information

Funding

This research was supported by the open fund for Natural Science Research Program Project of Huai’an (HABL202210), Enterprise-University-Research Institute Collaboration Project of Jiangsu Province (BY20231288), The Key Laboratory for traffic and transportation security of Jiangsu Province (Huaiyin Institute of Technology) (TTS2020-09), Chinese Government Scholarship for Overseas Studies (CSC NO. 201506090109).

References

  • Alatas, B., E. Akin, and A. B. Ozer. 2009. Chaos embedded particle swarm optimization algorithms. Chaos, Solitons & Fractals 40 (4):1715–24. doi:10.1016/j.chaos.2007.09.063.
  • Ali, Z. A., H. Zhangang, and D. Zhengru. 2023. Path planning of multiple UAVs using MMACO and DE algorithm in dynamic environment. Measurement and Control 56 (3–4):459–69. doi:10.1177/0020294020915727.
  • Chen, J. F., and J. Fei. 2017. UAV path planning based on particle swarm optimization with global best path competition. International Journal of Pattern Recognition and Artificial Intelligence 32 (6):1859008. doi:10.1142/S0218001418590085.
  • Chen, Y. B., G. C. Luo, Y. S. Mei, J. Q. Yu, and X. L. Su. 2016. UAV path planning using artificial potential field method updated by optimal control theory. International Journal of Systems Science 47 (6):1407–20. doi:10.1080/00207721.2014.929191.
  • Du, X. Y., Q. C. Guo, and Y. Y. Li. 2021. An improved whale algorithm based UAV 3D path planning method in urban environment. Computer Science 48 (12):304–11.
  • Fang, S. L., L. Yu, and Y. F. Wang. 2010. UAV trajectory planning based on particle swarm optimization algorithm. Computer Simulation 27 (8):41–3,113.
  • Faramarzi, A., M. Heidarinejad, S. Mirjalili, and A. H. Gandomi. 2020. Marine predators algorithm: A nature-inspired metaheuristic. Expert Systems with Applications 152:113377. doi:10.1016/j.eswa.2020.113377.
  • Feng, J., J. Zhang, X. Zhu, and W. Lian. 2017. A novel chaos optimization algorithm. Multimedia Tools and Applications 76 (16):17405–36. doi:10.1007/s11042-016-3907-z.
  • Goldberg, D. E., and J. H. Holland. 1988. Genetic algorithms and machine learning. Machine Learning 3 (2/3):95–99. doi:10.1023/A:1022602019183.
  • Hao, W. L., B. Luo, and Z. Y. Zhang. 2021. Application study of UAV path planning based on the balanced search factor artificial bee colony algorithm. Journal of Physics Conference Series 2083 (3):032064. doi:10.1088/1742-6596/2083/3/032064.
  • Huang, H., K. Wu, H. F. Wang. 2021. Low-altitude surge path planning for UAVs based on improved mothballing algorithm. Chinese Journal of Inertial Technology 29 (2):256–63.
  • Hu, C. H., Y. Xia, and J. G. Zhang. 2018. Adaptive operator quantum-behaved pigeon-inspired optimization algorithm with application to UAV path planning. Algorithms 12 (1):3. doi:10.3390/a12010003.
  • Jin, J., L. Xing, J. Shen, R. Li, M. Yang, and Z. Zhou. 2022. Design of a dynamic sparse circulant measurement matrix based on a new compound sine chaotic map. Institute of Electrical and Electronics Engineers Access 10:10827–37. doi:10.1109/ACCESS.2022.3142535.
  • Kennedy, J., and R. Eberhart. 1995. Particle swarm optimization. Proceedings of the ICNN’95—International Conference on Neural Networks, vol. 4, 1942–48, Perth, Australia, 27 November–1 December.
  • Kothari, M., I. Postlethwaite, and D. Gu. 2009. Multi-UAV path planning in obstacle rich environments using rapidly-exploring random trees[C]//IEEE control systems society(CSS). Control Theory Committee of the Chinese Society of Automation. Proceedings of Joint 48th IEEE Conference on Decision and Control and 28th Chinese Control Conference(3), Shanghai, China, 680–85, IEEE.
  • Lin, W. X., W. J. Xie, P. Zhang. 2023. UAV 3D path planning based on group optimization improved particle swarm algorithm. Firepower and Command Control 48 (1):20–25.
  • Liu, Z. Q., X. M. You, and S. Liu. 2018. An ant colony algorithm for a heuristic dynamic pheromone update strategy. Computer Engineering and Applications 54 (20):20–27.
  • Mirjalili, S., A. Lewis, and A. Lewis. 2016. The whale optimization algorithm. Advances in Engineering Software 95:51–67. doi:10.1016/j.advengsoft.2016.01.008.
  • Mirjalili, S., S. M. Mirjalili, and A. D. Lewis. 2014. Grey wolf optimizer. Advances in Engineering Software 69:46–61. doi:10.1016/j.advengsoft.2013.12.007.
  • Prashant, P., S. Anupam, and T. Ritu. 2018. Three-dimensional path planning for unmanned aerial vehicles using glowworm swarm optimization algorithm. International Journal of Systems Assurance Engineering and Management 9 (4):836–52. doi:10.1007/s13198-017-0663-z.
  • Punitha, A., and V. Geetha. 2023. Automated climate prediction using pelican optimization based hybrid deep belief network for smart agriculture. Measurement: Sensors 27:27. doi:10.1016/j.measen.2023.100714.
  • Radmanesh, M., M. Kumar, and M. Sarim. 2018. Grey wolf optimization based sense and avoid algorithm in a Bayesian framework for multiple UAV path planning in an uncertain environment. Aerospace Science and Technology 77 (juna):168–79. doi:10.1016/j.ast.2018.02.031.
  • Tian, R., M. Cao, F. Ma. 2020. Agricultural UAV path planning based on improved A~* and gravity search mixed algorithm[C]//Hubei Zhongke institute of geology and environment technology. Proceedings of the 2nd International Conference on Artificial Intelligence and Computer Science (AICS 2020), 586–93, IEEE. doi:10.26914/c.cnkihy.2020.029034.
  • Trojovský, P., and M. Dehghani. Pelican optimization algorithm: A novel nature-inspired algorithm for engineering applications. Sensors (Basel) 22 (3):855. January 23, 2022. doi:10.3390/s22030855.
  • Varol Altay, E., and B. Alatas. 2020. Bird swarm algorithms with chaotic mapping. Artificial Intelligence Review 53 (2):1373–414. doi:10.1007/s10462-019-09704-9.
  • Wang, G. Y., J. Z. Lu, A. Jiao, Z. C. Guo, and Q. Zhang. 2021. Chaotic particle swarm chicken flock fusion optimization for RSSI center-of-mass localization algorithm. Computer Engineering 47 (6):197–202+209.
  • Wang, Z. W., G. K. Sun, K. P. Zhou, and L. Q. Zhu. 2023. A parallel particle swarm optimization and enhanced sparrow search algorithm for unmanned aerial vehicle path planning. Heliyon 9 (4):e14784. doi:10.1016/j.heliyon.2023.e14784.
  • Yang, Y. X., Z. X. Chen, and J. Ye. 2022. Optimization of dynamic obstacle avoidance path of multirotor UAV based on ant colony algorithm. Wireless Communications and Mobile Computing 2022:1–9. doi:10.1155/2022/1299434.
  • Yang, Q., Z. Yang, T. Y. Zhang, and G. X. Hu. 2019. A random chemical reaction optimization algorithm based on dual containers strategy for multi-rotor UAV path planning in transmission line inspection. Concurrency and Computation: Practice and Experience 31 (12):e4658.1–13. doi:10.1002/cpe.4658.
  • Yu, X. B., N. J. Jiang, X. M. Wang, and M. Y. Li. 2023. A hybrid algorithm based on grey wolf optimizer and differential evolution for UAV path planning. Expert Systems with Applications 215:215. doi:10.1016/j.eswa.2022.119327.
  • Zhang, X. Y., X. Y. Lu, S. M. Jia, and X. Z. Li. 2018. A novel phase angle-encoded fruit fly optimization algorithm with mutation adaptation mechanism applied to UAV path planning. Applied Soft Computing Journal 70:371–88. doi:10.1016/j.asoc.2018.05.030.
  • Zhang, M. J., H. Zhang, X. Chen, and J. Yang. 2021. Grey wolf optimization algorithm based on cubic mapping and its application. Computer Engineering and Science 43 (11):2035–42.