Abstract
Research on unmanned aerial vehicle (UAV) path planning technology in urban operation scenarios faces the challenge of multi-objective collaborative optimization. Currently, mainstream path planning algorithms, including the multi-objective particle swarm optimization (MOPSO) algorithm, generally suffer from premature convergence to local optima and insufficient stability. This paper proposes a Zaslavskii chaotic multi-objective particle swarm optimization (ZAMOPSO) algorithm to address these issues. First, three-dimensional urban environment models with asymmetric layouts, symmetric layouts, and no-fly zones were constructed, and a multi-objective model was established with path length, flight altitude variation, and safety margin as optimization objectives. Second, the Zaslavskii chaotic sequence perturbation mechanism is introduced to improve the algorithm’s global search capability, convergence speed, and solution diversity. Third, nonlinear decreasing inertia weights and asymmetric learning factors are employed to balance global and local search abilities, preventing the algorithm from being trapped in local optima. Additionally, a guidance particle selection strategy based on congestion distance is introduced to enhance the diversity of the solution set. Experimental results demonstrate that ZAMOPSO significantly outperforms other multi-objective optimization algorithms in terms of convergence, diversity, and stability, generating Pareto solution sets with broader coverage and more uniform distribution. Finally, ablation experiments verified the effectiveness of the proposed algorithmic mechanisms. This study provides a promising solution for urban UAV path planning problems, while also providing theoretical support for the application of swarm intelligence algorithms in complex environments.
1. Introduction
With the rapid rise of the unmanned aerial vehicle (UAV) industry, UAVs have been widely applied in various complex urban operation scenarios, including urban logistics [], target detection and recognition [], public security patrols [,], as well as data acquisition tasks []. As an important component of UAV mission planning systems, path planning aims to design an optimal flight trajectory from the departure point to the destination, according to specific criteria, such as minimizing flight time or maximizing safety, while simultaneously satisfying various constraints. However, specific objectives and constraints may conflict with each other, resulting in the absence of a single global optimal solution. Therefore, path planning technology must balance these requirements to find the optimal feasible solution.
In logistics delivery, accurate and rational path planning ensures that UAVs can fly safely in complex urban environments while improving delivery efficiency. In public security operations, effective path planning enables UAVs to respond rapidly to emergencies, enhancing emergency handling capabilities. In three-dimensional spectrum mapping, efficient informative path planning maximizes the spectrum information collection efficiency of UAVs under limited resource constraints []. Moreover, path planning technology also demonstrates broad application prospects in fields such as precision agriculture and disaster relief.
According to the different application environments and algorithm characteristics, existing path planning methods include graph search–based algorithms, artificial potential field methods, sampling-based search algorithms, and meta-heuristic algorithms []. The graph search–based algorithms are represented by the Dijkstra algorithm and the A* algorithm [,]. The Dijkstra algorithm finds the shortest path by continuously updating the shortest path and distance information of nodes, but it cannot handle negative-weight edges or negative-weight cycles and has high computational complexity []. In [], an enhanced Dijkstra algorithm is presented for the path planning of rail-mounted robots engaged in cargo delivery operations within large-scale workshops. The A* algorithm introduces goal-related heuristic information, which guides the search process and significantly improves its efficiency. However, in grid-based environment modeling, the search space grows exponentially with the increase in problem dimensions, which severely limits the efficiency of the algorithm []. In [], a bi-level optimization approach combining the A* algorithm and the dynamic window method was proposed for UAV path planning. The artificial potential field (APF) method guides the motion of objects by modeling attractive and repulsive forces. The target generates an attractive force that draws the object toward it, while obstacles produce repulsive forces that push the object away. However, this method is prone to premature convergence to local optima, making it difficult to obtain the global optimal solution [,]. In [], an improved APF method was proposed to generate UAV paths that are smoother and more energy-efficient. The Rapidly Exploring Random Tree (RRT) algorithm is a stochastic search method based on random sampling in the space []. Its core principle is to construct a tree-like path through random sampling, thereby rapidly exploring the feasible space. Although RRT is particularly suitable for path search in high-dimensional and complex environments, the generated paths may suffer from non-smoothness and suboptimality [,]. The RRT* algorithm extends the RRT by introducing a path rewiring mechanism, and as the number of sampled points increases, the generated path gradually converges to the global optimal solution []. Common metaheuristic algorithms include gray wolf optimizer (GWO) [], artificial bee colony (ABC) [], genetic algorithms (GA) [], dung beetle optimization (DBO) [], and particle swarm optimization (PSO) []. In recent years, these algorithms have been increasingly applied to UAV path planning due to their ability to search for optimal solutions [,,]. Such methods typically employ a cost function to model the path planning problem as an optimization task, where a path is treated as a candidate solution and subsequently improved using swarm intelligence.
PSO is characterized by fast convergence, strong global search capability, ease of implementation, high adaptability, and good compatibility among nature-inspired algorithms. Based on these advantages, several PSO variants have been applied to path planning, such as self-evolving PSO (SEPSO) [], hybrid PSO [], spherical vector-based PSO (SPSO) [], and quantum PSO (QPSO) []. However, most algorithms are single-objective, and they solve multiple objectives by combining them into a single cost function through a weighting method. Although this method has high computational efficiency, combining multiple objectives can lead to the optimality of the cost function not representing the optimality of individual objectives. In practical applications, most objectives cannot simultaneously achieve their optimal values, and some are even mutually contradictory. Consequently, a multi-objective optimization approach is required.
The advantage of multi-objective optimization lies in its ability to address multiple conflicting objectives simultaneously during the optimization process, without the need for predefined weights, and to generate a set of Pareto-optimal solutions, namely, solutions in the multi-objective space that cannot be further improved. Each solution on the Pareto set is feasible, allowing decision-makers to select the most appropriate option based on practical requirements, rather than relying solely on a single aggregated objective value, thereby enhancing both the flexibility and scientific rigor of decision-making. At present, the multi-objective particle swarm optimization (MOPSO) algorithm and its variants have been widely applied in path planning research [,,].
In urban UAV path planning, PSO often becomes trapped in local optima, leading to issues such as uneven distribution of the solution set and reduced overall performance. Chaotic systems, with their randomness, ergodicity, and sensitivity to initial conditions, can enhance convergence speed. Their randomness enriches the search process, helping algorithms escape local optima.
The Zaslavskii map, a discrete-time nonlinear dynamical system introduced by Zaslavsky in 1978, is a member of the class of two-dimensional chaotic systems. Compared with low-dimensional chaotic systems such as the Logistic and Tent maps, the Zaslavsky map maintains stable chaotic behavior over a wider parameter range, thereby avoiding degeneration into periodic orbits. Additionally, the sequences it generates exhibit a more uniform distribution and lower correlation, enhancing the global search capability of optimization algorithms. Relative to other two-dimensional chaotic systems, such as the Henon map, the Zaslavsky map offers a higher-dimensional parameter space and richer dynamical behavior, producing sequences that are statistically closer to a uniform distribution. Leveraging these advantages, this study proposes a multi-objective particle swarm optimization algorithm based on the Zaslavsky chaotic sequence (ZAMOPSO), which is employed to address urban UAV path planning problems.
The main contributions and innovations of this study are summarized in the following aspects:
- (1)
- To address the issue of premature convergence to local optima in the original MOPSO for urban UAV path planning, Zaslavskii chaotic sequences are employed to generate random numbers, replacing the random factors and in the velocity update formula, thereby enhancing both the complexity and robustness of particle search behavior.
- (2)
- A dynamic parameter adjustment mechanism is used to balance global exploration with local exploitation, while a guidance strategy based on crowding distance is introduced to prioritize non-dominated solutions in sparse regions, thereby improving the diversity of the solution set.
- (3)
- The proposed ZAMOPSO algorithm, along with other multi-objective optimization algorithms, was evaluated across different three-dimensional urban environment models. Comparative results indicate that ZAMOPSO achieves superior overall performance in solving UAV path planning problems in urban environments, and its effectiveness is further confirmed through ablation experiments.
The rest of this paper is structured as follows. Section 2 defines the objective functions and constraints of the multi-objective UAV path planning model. Section 3 describes the underlying principles of the proposed ZAMOPSO algorithm. Section 4 presents comparative and ablation experiments to evaluate the algorithm’s effectiveness. Finally, Section 5 provides the conclusions.
2. Problem Description
A three-dimensional urban environment model was constructed using the three-dimensional grid method. A multi-objective path planning model was then formulated with path length, altitude variation, and safety margin as optimization objectives. The model was solved using the ZAMOPSO algorithm to obtain a set of feasible flight paths. Let the path start point be (), the end point be (), and the intermediate waypoints be (), for . The following objective functions and constraints are considered.
2.1. Objective Functions
2.1.1. Flight Path Length
In the field of path planning, a shorter flight path means that UAVs can reach the destination from the starting point more quickly, thereby reducing costs. The specific objective function is defined as follows:
where represents the total path length, which is obtained by summing the Euclidean distances between consecutive path points.
2.1.2. Altitude Variation
Frequent altitude changes during UAV flight can lead to increased energy consumption. To reduce unnecessary energy consumption, altitude fluctuations should be controlled to maintain a smooth flight trajectory. The specific objective function is defined as follows:
where denotes the total altitude variation along the flight path, represents the altitude difference between the -th waypoint and its preceding waypoint.
2.1.3. Safety Margin
In urban environments, UAVs must avoid buildings during flight. To evaluate the safety of a given path, a safety margin metric is introduced, defined as the minimum normalized elliptical distance between all path points and all buildings, and can be expressed as follows:
where () denote the center coordinates, width, length, and height of the -th building, respectively, and represents the total number of buildings.
To unify all objectives as minimization problems, the negative value of the safety margin is used as the optimization objective. Specifically, the objective function is defined as the negative of the minimum normalized elliptical distance between all path points and all buildings as follows:
2.2. Constraints
2.2.1. Collision Avoidance Constraint
A Boolean collision detection function is incorporated to guarantee the feasibility and safety of UAV flight paths in urban environments. This function is formulated as the summation of Boolean indicators, each of which specifies whether a given path segment intersects with any building []. If the value equals zero, it indicates a collision-free and feasible path; otherwise, the path is considered infeasible and must be excluded from the solution set. The constraint is formulated as follows:
2.2.2. Safety Constraint
In UAV path planning, safety is a critical constraint used to ensure a minimum safe distance between the flight path and surrounding buildings. The corresponding constraint is defined as follows:
where denotes the value computed from Equation (3), while denotes the predefined safety threshold.
2.2.3. Flight Altitude Constraint
Considering urban UAV airspace policies and safety requirements, the flight altitude of UAVs performing delivery tasks should be restricted between a minimum height and a maximum height . The corresponding constraint is expressed as follows:
3. The ZAMOPSO Algorithm
3.1. Multi-Objective Particle Swarm Optimization Algorithm
PSO is a swarm intelligence optimization method inspired by the foraging behavior of birds. The classical PSO was initially developed to address single-objective optimization problems, with the goal of identifying the optimal solution to a given objective function. However, in practice, it is often necessary to simultaneously optimize multiple conflicting objectives. Since multi-objective optimization problems generally do not have a unique solution but instead yield a set of Pareto-optimal solutions, researchers extended PSO and proposed MOPSO []. The velocity update formula of particles in MOPSO is given as follows:
where denotes the velocity of particle at iteration , represents its current position; is the personal best position of particle ; and is the global best position within the swarm. Here, denotes the inertia weight, while and correspond to the cognitive and social learning factors, respectively.
3.2. Particle Velocity Update Strategy Based on Zaslavskii Chaotic Sequences
In the MOPSO algorithm, the velocity update of each particle relies on two random factors, and , which guide the particle toward its personal best and global best positions, respectively. However, traditional uniformly distributed random numbers may lack structured perturbations during the particle update process, potentially impairing the algorithm’s global exploration ability, slowing convergence, and increasing the risk of premature trapping in local optima. Compared with traditional uniformly distributed random numbers, the Zaslavskii chaotic sequence exhibits pseudo-randomness, ergodicity, and complex dynamic behavior, effectively improving the algorithm’s global search capability and convergence performance while mitigating the risk of premature convergence to local optima. Therefore, this paper proposes a particle velocity update strategy based on the Zaslavskii chaotic sequence, using random numbers generated by the Zaslavskii chaotic sequence to replace traditional uniformly distributed random numbers. The Zaslavskii map is a classical chaotic system [], and its mapping equation is defined as follows:
where and represent the state variables of the chaotic system. denotes the number of iterations, represents the modulo operation. When the parameters are set as and , the generated sequence exhibits strong chaotic behavior [].
By employing the chaos-generated random number , Equation (8) is improved, and the optimized form is expressed as follows:
where , are obtained by applying a modulo operation to the sequence .
In the particle update process, the chaos-generated random numbers and replace the conventional random numbers and . This structured perturbation contributes to greater particle search diversity while simultaneously strengthening the algorithm’s global exploration capacity and accelerating its convergence efficiency.
3.3. Dynamic Parameter Adjustment Strategy
3.3.1. Nonlinear Decreasing Inertia Weight
In the MOPSO algorithm, the inertia weight plays a crucial role in determining the global optimization capability. A larger inertia weight is beneficial for global exploration, whereas a smaller inertia weight is more conducive to local exploitation. Therefore, appropriately adjusting the inertia weight is an effective strategy to balance the global and local search abilities of MOPSO. Among various improvements to MOPSO, the inertia weight is commonly adjusted using a linear decreasing strategy. Although this strategy provides strong global search capability in the early stages, if high-quality guiding solutions are not found early on, the continuously decreasing inertia weight in later stages can result in premature convergence to local optima, resulting in optimization failure. Compared with the linear decreasing strategy, the nonlinear decreasing strategy maintains a larger inertia weight for a longer period during the early search phase, thereby enhancing global exploration and reducing the risk of premature convergence caused by the absence of high-quality solutions. In the later stage, the inertia weight decreases rapidly, which strengthens local exploitation, facilitates faster convergence.
To address this issue, a nonlinear decreasing inertia weight strategy is employed in this study, where varies dynamically with the number of iterations. The specific formula for the nonlinear decreasing inertia weight is given as follows:
where denotes the current iteration number, is the maximum number of iterations, represents the initial inertia weight, and corresponds to the final inertia weight.
3.3.2. Asymmetric Learning Factors
In the classical MOPSO algorithm, the factors and are generally treated as constants. However, this approach has a notable drawback: in the later stages of optimization, particle diversity diminishes, often leading to premature convergence. To address this issue, adjusting the learning factors can encourage particles to perform extensive exploration during the early search phase, aiming to obtain high-quality particles with greater diversity and to minimize interference from local optima. The learning factors and govern the influence of individual and social experiences on a particle’s search trajectory, thereby reflecting the information exchange within the swarm. If is set too high, particles tend to over-explore locally; conversely, if is too large, particles may prematurely converge to local optima. Therefore, at the early search stage, a larger and smaller are used to encourage particles to spread widely across the search space, emphasizing “individual independence” while weakening the influence of other particles in the population, i.e., the “social component,” thereby enhancing population diversity. As the iteration progresses, the cognitive learning factor decreases linearly while the social learning factor increases linearly, thereby enhancing the particles’ ability to converge toward the global optimum. The specific formulas for the asymmetric learning factors are expressed as follows:
where denotes the current iteration number, is the maximum number of iterations, and represent the initial and final values of the cognitive learning factor, respectively, while and correspond to the final and initial values of the social learning factor, respectively.
In summary, combining a nonlinear decreasing inertia weight with linearly adjusted learning factors establishes a complementary mechanism. During the early search phase, a larger inertia weight and a higher cognitive component enhance global exploration, while in the later phase, a smaller inertia weight and a higher social component improve convergence performance. Compared with strategies where both parameters decrease linearly, the integration of a nonlinear inertia weight with linearly adjusted learning factors better maintains population diversity and mitigates the risk of premature convergence.
3.4. Guide Particle Selection Strategy Based on Crowding Distance
In the traditional MOPSO algorithm, guide particles are typically selected randomly from the current Pareto front. However, this approach neglects the distribution characteristics of the Pareto solutions, which may cause the solution set to cluster locally or lose diversity. To improve both the diversity and uniform distribution of the solution set, this study employs a guide particle selection strategy that leverages crowding distance, selecting the solution with the largest crowding distance from the current Pareto set as the guide particle. For the -th Pareto solution, its crowding distance is calculated as follows:
where denotes the number of objective functions. and represent the objective values of the two neighboring individuals adjacent to the individual on objective . and denote the maximum and minimum values of the objective on the current Pareto front, respectively. If an individual is located on the boundary (i.e., it attains the maximum or minimum value for the objective ), its crowding distance is assigned infinity to ensure that boundary solutions are preferentially preserved.
3.5. ZAMOPSO Implementation Process
This study applies the ZAMOPSO algorithm to the problem of urban UAV path planning. The flowchart and pseudocode of the algorithm are illustrated in Figure 1 and Algorithm 1, respectively. The ZAMOPSO operating process is outlined below: First, the system is initialized by setting the simulation environment parameters and the initial values of the algorithm parameters. Subsequently, the population and the external archive are initialized. An initial feasible path is generated using the RRT algorithm, and key waypoints are sampled. The three objective functions—path length, altitude variation, and safety margin—are evaluated. During each iteration, particle positions and velocities are updated using random numbers generated from the Zaslavskii chaotic sequence. Inertia weight and learning factors are dynamically adjusted. Guide particles are selected based on crowding distance, while boundary handling and collision detection are also performed. After each iteration, update the individual best and the global best solutions, as well as the Pareto front. When the maximum number of iterations is reached, output the Pareto-optimal solution set of the model. By incorporating Zaslavskii chaotic sequence perturbation, dynamic parameter adjustment, and the crowding distance mechanism, the proposed algorithm achieves improved stability and robustness while simultaneously enhancing its capability in handling multi-objective optimization tasks.
Figure 1.
Flowchart of the ZAMOPSO algorithm.
| Algorithm 1 The ZAMOPSO algorithm’s pseudocode |
| Input: Load 3D city map, define start and goal positions. Set parameters: maximum iterations T, population size nPop, maximum attempts maxAttempts, safety threshold, grid size, inertia weight w, cognitive learning factor c1, social learning factor c2, height limits hmin and hmax and maximum velocity vmax. |
| 1. Generate Zaslavskii chaotic sequence zasX |
| 2. Initialize particle structure and set validCount = 0, attempts = 0 |
| 3. while validCount < nPop and attempts < maxAttempts do |
| 4. Generate a feasible path using path from startPos to goalPos |
| 5. if path exists and safety margin ≥ threshold: |
| 6. Sample waypoints and initialize particle’s position, velocity, and personal best |
| 7. Add particle to the swarm |
| 8. end if |
| 9. end while |
| 10. Initialize external archive paretoSet and up date with all valid particles |
| 11. while t ≤ T do |
| 12. for each particle i in the swarm: |
| 13. Calculate random inertia weight w, cognitive learning factor c1 and social learning factor c2 |
| 14. Select leader from paretoSet using crowding distance |
| 15. Generate chaotic random vectors zasX1, zasX2 |
| 16. Update particle velocity using: |
| 17. Update particle position: |
| 18. Clip position to grid bounds |
| 19. Construct new path and smooth it |
| 20. if path is feasible and margin ≥ threshold: |
| 21. Update particle position |
| 22. Evaluate objectives and obtain currentCost |
| 23. end if |
| 24. if currentCost dominates pBestCost: |
| 25. Update personal best |
| 26. Update paretoSet |
| 27. end if |
| 28. end for |
| 29. end while |
| Output: Final non-dominated UAV path population |
3.6. Computational Complexity of the ZAMOPSO Algorithm
The computational complexity of the standard MOPSO algorithm is established as O, where denotes the number of particles, the number of iterations, the cost of evaluating the objective functions. In this study, the proposed ZAMOPSO algorithm introduces several improvements based on MOPSO, including the use of Zaslavskii chaotic sequences for random number generation, nonlinear decreasing inertia weights, asymmetric learning factors, and a leader selection strategy guided by crowding distance. Among these improvements, chaotic sequence generation and dynamic parameter adjustments introduce only constant-level overhead, whereas the crowding-distance-based leader selection requires sorting the non-dominated solutions in the external archive and calculating crowding distances, with a complexity of O(). Therefore, the overall computational complexity of ZAMOPSO is O(. Compared with the standard MOPSO, ZAMOPSO theoretically introduces an additional computational overhead of order , but this increase does not change the overall order of complexity. In the experimental setup of this study, the population size is relatively small, making the additional overhead of ZAMOPSO negligible; hence, the complexity difference between the two algorithms is not significant.
4. Simulation Results
4.1. Simulation Environment and Parameter Settings
Four different three-dimensional urban environment models, Maps A, B, C, and D were constructed using the three-dimensional grid method in MATLAB R2023a to evaluate the effectiveness of UAV path planning under different optimization algorithms, as shown in Figure 2. Table 1 presents the detailed configuration of the simulation environment and the algorithm parameters.

Figure 2.
Different three-dimensional urban environment models. (a) Map A. (b) Map B. (c) Map C. (d) Map D. The blue cuboids represent buildings, while the red cylinders denote no-fly zones.
Table 1.
Algorithm and environment parameter settings.
4.2. Comparison Experiment
This study compared the proposed ZAMOPSO algorithm with other multi-objective optimization algorithms, including the original MOPSO, the nondominated sorting genetic algorithm II (NSGA-II) algorithm, and the multi-objective dung beetle optimization algorithm (MO-DBO). In Maps A, B, C, and D, 30 independent runs were conducted for each algorithm. During each run, the generated flight paths were recorded, along with the performance curves of the hypervolume (HV) and Inverted Generational Distance (IGD) metrics. It should be emphasized that the paths displayed in the four maps represent only one of the numerous non-dominated solutions within the Pareto set produced by the algorithms. Each solution exhibits dominance in certain objectives, and thus, depending on the application scenario, some non-dominated solutions may be considered more preferable than others.
4.2.1. Map A Simulation Experiment
Map A is a virtual city environment with an asymmetric layout, where the height distribution of buildings is uneven, including both high-rise and low-rise buildings, designed to simulate a traditional city with complex layouts and diverse functionalities. The four algorithms were used for path planning in Map A. As shown in Figure 3 and Figure 4, each algorithm is capable of generating feasible paths. Figure 3 illustrates the three-dimensional views of the paths obtained by each algorithm, while Figure 4 presents their corresponding top-down views.
Figure 3.
Three-dimensional views of the paths.
Figure 4.
Top-down views of the paths.
Figure 5 illustrates the iterative variation curves of the HV metric for the four algorithms in the simulation experiment on Map A. As shown, ZAMOPSO exhibits a rapid increase in HV value during the initial iterations and converges to the optimal value after approximately 80 iterations. Its final HV value is the highest. MOPSO shows a slow increase in HV value during the initial iterations and converges to the optimal value after approximately 80 iterations. Its final HV value is lower than that of ZAMOPSO. The HV value of NSGA-II increases steadily throughout the process, and its final HV value is the lowest. The HV value of MO-DBO fluctuates repeatedly, with the final HV value being similar to that of NSGA-II. These results indicate that ZAMOPSO demonstrates superior overall performance compared with the other algorithms.
Figure 5.
The HV iterative change curve of each algorithm.
Figure 6 presents the iterative variation curves of the IGD metric for the four algorithms in the simulation experiment on Map A. As shown, ZAMOPSO exhibits a rapid decline in IGD value during the initial iterations and converges to the optimal value after approximately 80 iterations. Its final IGD value is the lowest. MOPSO and NSGA-II demonstrate a slow decline in IGD values during the initial iterations and converge to the optimal value after approximately 80 iterations. Their final IGD values are similar, but both are higher than that of ZAMOPSO. MO-DBO converges to the optimal value after approximately 120 iterations, and its final IGD value is the highest among all methods. These results indicate that ZAMOPSO demonstrates superior diversity and convergence compared with the other algorithms.
Figure 6.
The IGD iterative change curve of each algorithm.
Figure 7 illustrates the box plots of the HV value distributions for the four algorithms in the simulation experiment conducted on Map A. As shown, ZAMOPSO has the best extreme values, quartiles, and medians among the four algorithms, with a concentrated HV value distribution. For MOPSO, the extrema, quartiles, and median are all lower than those of ZAMOPSO, and an outlier is observed. NSGA-II exhibits significantly different extreme values, with both the quartiles and medians lower than MOPSO. MO-DBO has the worst extreme values, quartiles, and medians among the four algorithms. These results indicate that ZAMOPSO demonstrates superior stability compared to the other algorithms.
Figure 7.
Boxplots of HV value distributions of each algorithm.
This study evaluates the overall performance of the four algorithms for UAV path planning on Map A using normalized HV and IGD metrics.
The mathematical definition of the HV indicator is the volume of the objective space enclosed by the set of non-dominated solutions obtained by the algorithm and a reference point. HV is an important metric for evaluating the quality of a solution set, capable of measuring both the convergence and diversity of the solution set simultaneously. A larger HV value indicates a higher-quality solution set. The mathematical formulation is given by the following:
where denotes the Lebesgue measure used to compute the volume; |s| represents the number of non-dominated solutions in the set; and denotes the hypervolume formed by the reference point and the -th solution in the set.
The mathematical definition of the IGD indicator is the average distance between the solution set obtained by the algorithm and the true Pareto front. A smaller IGD value indicates that the solution set obtained by the algorithm is closer to the true Pareto front. The mathematical formulation is given by the following:
where denotes the solution set obtained by the algorithm, represents a set of uniformly distributed reference points sampled from the Pareto front, and refers to the Euclidean distance between a reference point in and a solution in .
The maximum, minimum, and mean values of the HV metric provide important criteria for evaluating algorithm performance. A higher value indicates superior comprehensive performance of the algorithm. As shown in Table 2, ZAMOPSO achieves the best performance across all metrics compared with MOPSO, NSGA-II, and MO-DBO. Specifically, the maximum HV values of ZAMOPSO increased by approximately 24.50%, 20.36%, and 27.22%, respectively. The minimum HV values improved by approximately 72.10%, 123.20%, and 122.88%, respectively. The mean HV values increased by approximately 29.62%, 46.69%, and 61.85%, respectively. The 95% confidence interval of ZAMOPSO is also superior to that of other algorithms. These results indicate that, for UAV path planning on Map A, ZAMOPSO exhibits better convergence and diversity, with a more widely distributed solution set.
Table 2.
Comparison of normalized HV metrics of each algorithm in Map A.
The maximum, minimum, and mean values of the IGD metric serve as important indicators for assessing the performance of algorithms in generating solution sets. A lower IGD value suggests that the solutions are closer to the true Pareto front and exhibit better distribution uniformity. As shown in Table 3, ZAMOPSO demonstrates the best performance across all metrics compared with MOPSO, NSGA-II, and MO-DBO. Specifically, compared with MOPSO, NSGA-II, and MO-DBO. Specifically, the maximum IGD values of ZAMOPSO were reduced by approximately 20.05%, 26.46%, and 29.50%, respectively. The minimum IGD values reduced by approximately 21.91%, 25.82%, and 25.50%, respectively. The mean IGD values reduced by approximately 21.10%, 24.42%, and 28.41%, respectively. The 95% confidence interval of ZAMOPSO is also better than other algorithms. These results indicate that, for UAV path planning on Map A, ZAMOPSO generates solution sets with better convergence and diversity, closer to the true Pareto frontier, and more uniformly distributed.
Table 3.
Comparison of normalized IGD metrics of each algorithm in Map A.
Finally, the Wilcoxon signed-rank test was conducted on the normalized HV and IGD values of the algorithms at a significance level of 0.05 (). The results, summarized in Table 4 and Table 5, indicate that the HV and IGD distributions of ZAMOPSO differ significantly from those of MOPSO, NSGA-II, and MO-DBO (), with an effect size of , which is considered a large effect (). This indicates that ZAMOPSO can usually obtain a better solution set.
Table 4.
The Wilcoxon rank test results of the HV values of ZAMOPSO and the comparison algorithm in Map A.
Table 5.
The Wilcoxon rank test results of the IGD values of ZAMOPSO and the comparison algorithm in Map A.
In summary, ZAMOPSO demonstrates superior performance in UAV path planning on Map A, validating the proposed strategy’s effectiveness.
4.2.2. Map B Simulation Experiment
Map B is a virtual city environment with a symmetrical layout, where the distribution of building heights is relatively consistent, with tall buildings concentrated in certain areas, aiming to simulate a strictly planned urban core. The four algorithms were used for path planning in Map B. As shown in Figure 8 and Figure 9, each algorithm is capable of generating feasible paths. Figure 8 illustrates the three-dimensional views of the paths obtained by each algorithm, while Figure 9 presents their corresponding top-down views.
Figure 8.
Three-dimensional views of the paths.
Figure 9.
Top-down views of the paths.
Figure 10 illustrates the iterative variation curves of the HV metric for the four algorithms in the simulation experiment on Map B. As shown, ZAMOPSO, MOPSO, and NSGA-II converge to their optimal values after approximately 80 iterations. ZAMOPSO achieves the highest final HV value, followed by MOPSO and then NSGA-II. MO-DBO converges to the optimal value after approximately 170 iterations, and its final HV value is lower than that of ZAMOPSO. These results indicate that ZAMOPSO demonstrates superior overall performance compared with the other algorithms.
Figure 10.
The HV iterative change curve of each algorithm.
Figure 11 illustrates the iterative variation curves of the IGD metric for the four algorithms in the simulation experiment conducted on Map B. As shown, ZAMOPSO exhibits a rapid decline in IGD value during the initial iterations and converges to the optimal value after approximately 80 iterations. Its final IGD value is the lowest. The convergence curves of the IGD metric for the other three algorithms are nearly overlapping, with the final IGD value all higher than that of ZAMOPSO. These results indicate that ZAMOPSO demonstrates superior diversity and convergence compared with the other algorithms.
Figure 11.
The IGD iterative change curve of each algorithm.
Figure 12 illustrates the box plots of the HV value distributions for the four algorithms in the simulation experiment conducted on Map B. As shown, ZAMOPSO has the best extreme values, quartiles, and medians among the four algorithms, with a concentrated HV value distribution. The extrema, quartiles, and median of MOPSO, NSGA-II, and MO-DBO are all lower than those of ZAMOPSO. Specifically, MOPSO exhibits an outlier, NSGA-II shows a larger variation in extrema with a higher number of lower HV values. These results indicate that ZAMOPSO demonstrates superior stability compared to the other algorithms.
Figure 12.
Boxplots of HV value distributions of each algorithm.
The same evaluation metrics as those used in the simulation experiments on Map A are used to further evaluate the comprehensive performance of the four algorithms on Map B.
Table 6 presents the HV comparison results of the four algorithms on Map B, indicating that ZAMOPSO achieves significantly better performance than the others across all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, the maximum HV metric of ZAMOPSO improved by approximately 21.60%, 16.70%, and 16.94%, respectively. The minimum HV metric of ZAMOPSO improved by approximately 122.41%, 123.35%, and 76.63%, respectively. The mean HV metric of ZAMOPSO improved by approximately 40.01%, 35.83%, and 35.67%, respectively. The 95% confidence interval of ZAMOPSO is also better than other algorithms. These results indicate that, for UAV path planning on Map B, ZAMOPSO exhibits better convergence and diversity, with a more widely distributed solution set.
Table 6.
Comparison of normalized HV metrics of each algorithm in Map B.
Table 7 presents the IGD comparison results of the four algorithms on Map B, indicating that ZAMOPSO outperforms other algorithms in all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, the maximum IGD metric of ZAMOPSO was reduced by approximately 22.34%. The minimum IGD metric of ZAMOPSO reduced by approximately 23.06%. The mean IGD metric of ZAMOPSO reduced by approximately 22.44%. The 95% confidence interval of ZAMOPSO is also superior to that of other algorithms. These results indicate that, for UAV path planning on Map B, ZAMOPSO generates solution sets with better convergence and diversity, closer to the true Pareto frontier, and more uniformly distributed.
Table 7.
Comparison of normalized IGD metrics of each algorithm in Map B.
Finally, the Wilcoxon signed-rank test was conducted on the normalized HV and IGD values of the algorithms at a significance level of 0.05 (). The results, summarized in Table 8 and Table 9, indicate that the HV and IGD distributions of ZAMOPSO differ significantly from those of MOPSO, NSGA-II, and MO-DBO (), with an effect size of , which is considered a large effect (). This indicates that ZAMOPSO can usually obtain a better solution set.
Table 8.
The Wilcoxon rank test results of the HV values of ZAMOPSO and the comparison algorithm in Map B.
Table 9.
The Wilcoxon rank test results of the IGD values of ZAMOPSO and the comparison algorithm in Map B.
In summary, ZAMOPSO demonstrates superior performance in UAV path planning on Map B, validating the proposed strategy’s effectiveness.
4.2.3. Map C Simulation Experiment
Map C is constructed based on Map A by adding two cylindrical no-fly zones, with model parameters [30, 28, 6, 6, 30, 1] and [70, 55, 6, 6, 30, 1], respectively. The four algorithms were used for path planning in Map C. As shown in Figure 13 and Figure 14, each algorithm is capable of generating feasible paths. Figure 13 illustrates the three-dimensional views of the paths obtained by each algorithm, while Figure 14 presents their corresponding top-down views.
Figure 13.
Three-dimensional views of the paths.
Figure 14.
Top-down views of the paths.
Figure 15 illustrates the iterative convergence curves of the HV metric for the four algorithms in the simulation experiment conducted on Map C. As shown, the HV value of ZAMOPSO exhibits a stepwise and rapid increase during the iteration process, converging to the optimal value after approximately 120 iterations, with the highest final HV value. MOPSO shows a rapid increase in HV value at the early stage, converging to the optimal value after about 80 iterations, and its final HV value is lower than that of ZAMOPSO. NSGA-II demonstrates a relatively slow increase in HV value during the early stage, converging to the optimal value after around 80 iterations, and its final HV value is lower than that of MOPSO. The HV value of MO-DBO fluctuates repeatedly during the iteration process, resulting in the lowest final HV value. These results indicate that ZAMOPSO demonstrates superior overall performance compared with the other algorithms.
Figure 15.
The HV iterative change curve of each algorithm.
Figure 16 illustrates the iterative variation curves of the IGD metric for the four algorithms in the simulation experiment conducted on Map C. As shown, ZAMOPSO shows a rapid decrease in IGD value during the early iterations and converges to the optimal value after approximately 80 iterations, ultimately achieving the lowest IGD value. Both MOPSO and NSGA-II exhibit a relatively slow decrease in IGD value at the early stage, converging to the optimal value after around 80 iterations, with final IGD values that are similar to each other but higher than that of ZAMOPSO. MO-DBO converges to the optimal value after about 80 iterations but experiences slight fluctuations in the later iterations, ultimately resulting in the highest IGD value. These results indicate that ZAMOPSO demonstrates superior diversity and convergence compared with the other algorithms.
Figure 16.
The IGD iterative change curve of each algorithm.
Figure 17 illustrates the box plots of the HV value distributions for the four algorithms in the simulation experiment conducted on Map C. As illustrated, ZAMOPSO has the best extreme values, quartiles, and medians among the four algorithms, with a concentrated HV value distribution. MOPSO shows extreme values, quartiles, and median lower than those of ZAMOPSO. NSGA-II displays large variability in extreme values, with quartiles and median values lower than those of MOPSO, and contains two outliers. MO-DBO performs the worst among the four algorithms in terms of extreme values, quartiles, and median, also containing two outliers. These results indicate that ZAMOPSO demonstrates superior stability compared to the other algorithms.
Figure 17.
Boxplots of HV value distributions of each algorithm.
The same evaluation metrics used in the simulation experiments on Map A are applied to further evaluate the comprehensive performance of the four algorithms on Map C.
Table 10 presents the HV comparison results of the four algorithms on Map C, indicating that ZAMOPSO achieves significantly better performance than the others across all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, the maximum HV value of ZAMOPSO is improved by approximately 27.09%, 27.69%, and 31.11%, respectively; the minimum HV value is improved by about 43.38%, 104.69%, and 116.19%, respectively; and the average HV value is improved by around 29.63%, 39.51%, and 76.33%, respectively. The 95% confidence interval of ZAMOPSO is also superior to that of other algorithms. These results indicate that, for UAV path planning on Map C, ZAMOPSO exhibits better convergence and diversity, with a more widely distributed solution set.
Table 10.
Comparison of normalized HV metrics of each algorithm in Map C.
Table 11 summarizes the IGD comparison results of the four algorithms on Map C, indicating that ZAMOPSO outperforms other algorithms in all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, the maximum IGD value of ZAMOPSO is reduced by approximately 22.03%, 22.41%, and 26.66%, respectively; the minimum IGD value is reduced by about 23.17%, 23.77%, and 26.15%, respectively; and the average IGD value is reduced by around 22.33%, 22.89%, and 26.59%, respectively. The 95% confidence interval of ZAMOPSO is also better than that of other algorithms. These results indicate that, for UAV path planning on Map C, ZAMOPSO generates solution sets with better convergence and diversity, closer to the true Pareto frontier, and more uniformly distributed.
Table 11.
Comparison of normalized IGD metrics of each algorithm in Map C.
Finally, the Wilcoxon signed-rank test was conducted on the normalized HV and IGD values of the algorithms at a significance level of 0.05 (). The results, summarized in Table 12 and Table 13, indicate that the HV and IGD distributions of ZAMOPSO differ significantly from those of MOPSO, NSGA-II, and MO-DBO (), with an effect size of , which is considered a large effect (). This indicates that ZAMOPSO can usually obtain a better solution set.
Table 12.
The Wilcoxon rank test results of the HV values of ZAMOPSO and the comparison algorithm in Map C.
Table 13.
The Wilcoxon rank test results of the IGD values of ZAMOPSO and the comparison algorithm in Map C.
In summary, ZAMOPSO demonstrates superior performance in UAV path planning on Map C, validating the proposed strategy’s effectiveness.
4.2.4. Map D Simulation Experiment
Map D is constructed based on Map B by adding two cylindrical no-fly zones, with model parameters [50, 20, 6, 6, 30, 1] and [50, 60, 6, 6, 30, 1], respectively. The four algorithms were used for path planning in Map D. As shown in Figure 18 and Figure 19, each algorithm is capable of generating feasible paths. Figure 18 illustrates the three-dimensional views of the paths obtained by each algorithm, while Figure 19 presents their corresponding top-down views.
Figure 18.
Three-dimensional views of the paths.
Figure 19.
Top-down views of the paths.
Figure 20 illustrates the iterative variation curves of the HV performance metric for the various algorithms in the simulation experiment on Map D. As shown, the HV value of ZAMOPSO exhibits a stepwise and rapid increase during the iteration process, converging to the optimal value after approximately 100 iterations, and achieving the highest final HV value. The HV value of MOPSO increases gradually in the early stage, shows a slight decline after about 120 iterations, and then converges to the optimal value, with a final HV value lower than that of ZAMOPSO. The HV value of NSGA-II converges to the optimal value after around 80 iterations, and its final HV value is lower than that of MOPSO. The HV value of MO-DBO fluctuates repeatedly during the iteration process, resulting in the lowest final HV value. These results indicate that ZAMOPSO demonstrates superior overall performance compared with the other algorithms.
Figure 20.
The HV iterative change curve of each algorithm.
Figure 21 illustrates the iterative variation curves of the IGD performance metric for the various algorithms in the simulation experiment conducted on Map D. As shown, ZAMOPSO exhibits a rapid decrease in IGD value during the early iterations and converges to the optimal value after approximately 80 iterations, ultimately achieving the lowest IGD value. MOPSO and NSGA-II show a gradual decrease in IGD value at the early stage and converge to the optimal value after around 80 iterations, with final IGD values that are similar to each other but higher than that of ZAMOPSO. MO-DBO attains the highest final IGD value. These results indicate that ZAMOPSO demonstrates superior diversity and convergence compared with the other algorithms.
Figure 21.
The IGD iterative change curve of each algorithm.
Figure 22 illustrates the box plots of the HV value distributions for the four algorithms in the simulation experiment conducted on Map D. As shown, ZAMOPSO demonstrates the best performance among the four algorithms in terms of extreme values, quartiles, and median, with a relatively concentrated HV value distribution. MOPSO shows lower extreme values, quartiles, and median compared with ZAMOPSO, and contains two outliers. NSGA-II exhibits large variability in extreme values, with quartiles and median close to those of MOPSO, and contains one outlier. MO-DBO presents extreme values, quartiles, and median that are generally similar to those of MOPSO. These results indicate that ZAMOPSO demonstrates superior stability compared to the other algorithms.
Figure 22.
Boxplots of HV value distributions of each algorithm.
The same evaluation metrics as those used in the simulation experiments on Map A, the comprehensive performance of the four algorithms is further evaluated on Map D.
Table 14 presents the HV comparison results of the four algorithms on Map D, indicating that ZAMOPSO achieves significantly better performance than the others across all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, the maximum HV value of ZAMOPSO is improved by approximately 19.41%, 19.03%, and 16.05%, respectively; the minimum HV value is improved by about 119.23%, 94.50%, and 39.75%, respectively; and the average HV value is improved by around 29.95%, 30.15%, and 27.16%, respectively. The 95% confidence interval of ZAMOPSO is also superior to that of other algorithms. These results indicate that, for UAV path planning on Map D, ZAMOPSO exhibits better convergence and diversity, with a more widely distributed solution set.
Table 14.
Comparison of normalized HV metrics of each algorithm in Map D.
Table 15 summarizes the IGD comparison results of the four algorithms on Map D, indicating that ZAMOPSO outperforms the other algorithms across all metrics. Specifically, compared with MOPSO, NSGA-II, and MO-DBO, ZAMOPSO reduces the maximum IGD value by approximately 22.01%, the minimum IGD value by around 22.83%, and the average IGD value by about 22.22%. The 95% confidence interval of ZAMOPSO is also better than other algorithms. These results indicate that, for UAV path planning on Map D, ZAMOPSO generates solution sets with better convergence and diversity, closer to the true Pareto frontier, and more uniformly distributed.
Table 15.
Comparison of normalized IGD metrics of each algorithm in Map D.
Finally, the Wilcoxon signed-rank test was conducted on the normalized HV and IGD values of the algorithms at a significance level of 0.05 (). The results, summarized in Table 16 and Table 17, indicate that the HV and IGD distributions of ZAMOPSO differ significantly from those of MOPSO, NSGA-II, and MO-DBO (), with an effect size of , which is considered a large effect (). This indicates that ZAMOPSO can usually obtain a better solution set.
Table 16.
The Wilcoxon rank test results of the HV values of ZAMOPSO and the comparison algorithm in Map D.
Table 17.
The Wilcoxon rank test results of the IGD values of ZAMOPSO and the comparison algorithm in Map D.
In summary, ZAMOPSO demonstrates superior performance in UAV path planning on Map D, validating the proposed strategy’s effectiveness.
4.3. Ablation Experiments
An ablation study was performed to assess how the Zaslavskii chaotic sequence perturbation contributes to improving the overall performance of the ZAMOPSO algorithm. The comparison involved the ZAMOPSO, the AMOPSO, and the original MOPSO algorithm. On Map A, thirty independent experiments were performed for each algorithm, and the HV value was recorded for each run.
Figure 23 illustrates the iterative variation curves of the HV performance metric for the various algorithms in the simulation experiment on Map A. It can be observed that the HV value of ZAMOPSO is greater than that of AMOPSO, which is greater than that of MOPSO, indicating that ZAMOPSO has the best performance, followed by AMOPSO, which is better than MOPSO.
Figure 23.
Iterative convergence curves of the HV metric for the three algorithms.
Table 18 displays the comparative HV metric results for each algorithm. As shown, compared with AMOPSO, the maximum HV, minimum HV, and mean HV of ZAMOPSO increased by approximately 21.47%, 36.45%, and 20.79%, respectively, indicating that the particle update strategy based on the Zaslavskii chaotic sequence effectively improved the convergence and diversity of the algorithm. Furthermore, compared with MOPSO, AMOPSO achieved improvements of 5.22%, 48.97%, and 20.37% in the maximum HV, minimum HV, and mean HV, respectively, indicating that the dynamic parameter adjustment strategy and the crowdedness-based guiding particle selection strategy effectively enhance the algorithm’s performance.
Table 18.
Comparison of normalized HV metrics for the three algorithms.
In summary, the ablation experiment verified the effectiveness of the proposed algorithm mechanism.
4.4. Discussion
Based on the overall experimental results and analyses, it is evident that the proposed ZAMOPSO algorithm surpasses MOPSO, NSGA-II, and MO-DBO regarding convergence, solution diversity, and stability. Specifically, ZAMOPSO demonstrates a significant improvement in the HV metric with a more concentrated distribution and achieves lower IGD values, indicating that its solutions are nearer to the true Pareto front and exhibit a more uniform distribution. The paired Wilcoxon test further confirms the statistical significance of these differences. Therefore, it can be concluded that the incorporation of the Zaslavskii chaotic sequence, nonlinear decreasing inertia weight, asymmetric learning factors, and a crowding-distance-based guide particle selection strategy effectively improves the algorithm’s global exploration ability as well as its local convergence performance.
Although this study does not formally prove that ZAMOPSO converges to the Pareto front, previous research has shown that, under certain conditions, PSO-based algorithms can asymptotically converge to stable points or approximate the Pareto front []. Since ZAMOPSO is fundamentally built upon the standard MOPSO framework, its convergence properties are not weakened by the introduction of chaotic perturbations and dynamic parameter adjustment strategies. On the contrary, these mechanisms are designed to enhance search diversity and accelerate convergence. In future research, we will further explore the theoretical guarantees of different chaotic mappings and conduct comparative analyses.
Existing studies have shown that introducing chaotic sequences into particle swarm optimization algorithms can effectively improve population diversity and convergence speed. For example, the authors of [] proposed a chaotic PSO algorithm for UAV safe path planning, which employs chaos-based initialization and incorporates a Logistic chaotic map, ultimately yielding near-optimal solutions. In [], a UAV path planning approach based on Tent–PSO was introduced, where the Tent chaotic map was applied to regulate UAV velocity and position, enhancing the algorithm’s search efficiency. In comparison with these studies, the experimental results of this work align with the aforementioned findings, further verifying the universal advantage of chaotic sequences in UAV path planning. In addition, compared with certain precise three-dimensional radio environment maps [], the simulation environment in this study is a virtually constructed model. Future work will focus on UAV path planning within three-dimensional radio environment maps that incorporate channel shadowing.
5. Conclusions
The ZAMOPSO algorithm is applied in this work to address the limitations of conventional methods in urban UAV path planning. In ZAMOPSO, the Zaslavskii chaotic sequence is employed to generate random numbers, replacing the random factors and in the velocity update equation. This enhances the complexity and robustness of particle search behavior, thereby enhancing the algorithm’s global exploration ability, convergence speed, and solution set diversity. Furthermore, a dynamic parameter adjustment mechanism is introduced to balance global exploration and local exploitation. To improve the evenness of the solution set, a crowding distance–based guidance strategy is incorporated. Then, three-dimensional urban environment models with asymmetric layout, symmetric layout, and no-fly zones were constructed, and comparative and ablation experiments were conducted based on these models. he results of the comparative experiments indicate that ZAMOPSO exhibits superior performance in tackling UAV path planning challenges within urban environments. In comparison with MOPSO, NSGA-II, and MO-DBO, ZAMOPSO demonstrates enhanced convergence and greater robustness. The ablation experiments validated the effectiveness of the proposed mechanism.
Future research will focus on the following aspects: First, future work will construct more realistic urban environment models, introducing more specific risk disturbance factors such as moving obstacles, disturbed wind fields, and channel shielding, to simulate various challenges encountered in practical applications and enhance the adaptability of algorithms under real tasks. Second, exploring machine learning-based adaptive parameter adjustment mechanisms to reduce human intervention and enhance the algorithm’s generality and self-regulation capabilities. Additionally, further improving threat modeling methods to more accurately describe the geometric shapes and safety boundaries of urban buildings, thereby enhancing the practicality and reliability of path planning results.
Author Contributions
Conceptualization, C.L. and H.X.; methodology, C.L.; software, C.L.; validation, C.L., H.X., and X.C.; writing—original draft preparation, C.L.; writing—review and editing, H.X. and X.C.; visualization, C.L. All authors have read and agreed to the published version of the manuscript.
Funding
This research was funded by the National Natural Science Foundation of China under Grant 62103209, the Research Projects of Putian University under Grant 2024175, and the Natural Science Foundation of Fujian Province under Grant 2020J05213.
Data Availability Statement
The data presented in this study are available on request from the corresponding author.
Acknowledgments
This work was supported by the National Natural Science Foundation of China under Grant 62103209, the Research Projects of Putian University under Grant 2024175, and the Natural Science Foundation of Fujian Province under Grant 2020J05213.
Conflicts of Interest
The author declares no conflicts of interest.
References
- Jarašūnienė, A.; Išoraitė, M.; Petraška, A. Developing Small-Cargo Flows in Cities Using Unmanned Aerial Vehicles. Future Transp. 2024, 4, 450–474. [Google Scholar] [CrossRef]
- Kim, P.; Youn, J. Performance Evaluation of an Object Detection Model Using Drone Imagery in Urban Areas for Semi-Automatic Artificial Intelligence Dataset Construction. Sensors 2024, 24, 6347. [Google Scholar] [CrossRef] [PubMed]
- Liu, Y.V.; Kang, W.; Maskály, J.; Ivković, S.K. Policing from the Sky: A Case Study of the Police Use of Drones in South Korea. In Exploring Contemporary Police Challenges; Routledge: London, UK, 2022; pp. 167–180. [Google Scholar] [CrossRef]
- Mohamed, N.; Al-Jaroodi, J.; Jawhar, I.; Idries, A.; Mohammed, F. Unmanned aerial vehicles applications in future smart cities. Technol. Forecast. Soc. Chang. 2020, 153, 119293. [Google Scholar] [CrossRef]
- Messaoudi, K.; Oubbati, O.S.; Rachedi, A.; Lakas, A.; Bendouma, T.; Chaib, N. A survey of UAV-based data collection: Challenges, solutions and future perspectives. J. Netw. Comput. Appl. 2023, 216, 103670. [Google Scholar] [CrossRef]
- Chen, Y.; Zhu, Q.; Wang, J.; Jia, Z.; Wang, X.; Lin, Z.; Huang, Y.; Wu, Q.; Briso-Rodríguez, C. UAV-Aided Efficient Informative Path Planning for Autonomous 3D Spectrum Mapping. IEEE Trans. Cogn. Commun. Netw. 2025, PP (99), 1. [Google Scholar] [CrossRef]
- Yang, L.; Qi, J.; Song, D.; Xiao, J.; Han, J.; Xia, Y. Survey of Robot 3D Path Planning Algorithms. J. Control Sci. Eng. 2016, 2016, 1–18. [Google Scholar] [CrossRef]
- Babel, L. Three-Dimensional Route Planning for Unmanned Aerial Vehicles in a Risk Environment. J. Intell. Robot. Syst. 2013, 71, 255–269. [Google Scholar] [CrossRef]
- Zhang, Z.; Wu, J.; Dai, J.; He, C. Optimal Path Planning with Modified A-Star Algorithm for Stealth Unmanned Aerial Vehicles in 3D Network Radar Environment. Proc. Inst. Mech. Eng. G: J. Aerosp. Eng. 2021, 236, 1–10. [Google Scholar] [CrossRef]
- Nakayama, A.; Anazawa, T. Dijkstra-Based Algorithms for the Shortest Path Problem with Edges of Negative Length. J. Oper. Res. Soc. Jpn. 2013, 56, 137–154. [Google Scholar] [CrossRef]
- Zhou, X.; Yan, J.; Yan, M.; Mao, K.; Yang, R.; Liu, W. Path Planning of Rail-Mounted Logistics Robots Based on the Improved Dijkstra Algorithm. Appl. Sci. 2023, 13, 9955. [Google Scholar] [CrossRef]
- Candra, A.; Budiman, M.A.; Pohan, R.I. Application of A-Star Algorithm on Pathfinding Game. J. Phys. Conf. Ser. 2021, 1898, 012047. [Google Scholar] [CrossRef]
- He, Y.; Hou, T.; Wang, M. A New Method for Unmanned Aerial Vehicle Path Planning in Complex Environments. Sci. Rep. 2024, 14, 9257. [Google Scholar] [CrossRef] [PubMed]
- Duhé, J.-F.; Victor, S.; Melchior, P. Contributions on Artificial Potential Field Method for Effective Obstacle Avoidance. Fract. Calc. Appl. Anal. 2021, 24, 421–446. [Google Scholar] [CrossRef]
- Yao, Q.; Zheng, Z.; Qi, L.; Yuan, H.; Guo, X.; Zhao, M.; Liu, Z.; Yang, T. Path Planning Method with Improved Artificial Potential Field—A Reinforcement Learning Perspective. IEEE Access 2020, 8, 135513–135523. [Google Scholar] [CrossRef]
- Hao, G.; Lv, Q.; Huang, Z.; Zhao, H.; Chen, W. UAV Path Planning Based on Improved Artificial Potential Field Method. Aerospace 2023, 10, 562. [Google Scholar] [CrossRef]
- Primatesta, S.; Cuomo, L.S.; Guglieri, G.; Rizzo, A. An Innovative Algorithm to Estimate Risk Optimum Path for Unmanned Aerial Vehicles in Urban Environments. Transp. Res. Procedia 2018, 35, 44–53. [Google Scholar] [CrossRef]
- Véras, L.G.D.; Medeiros, F.L.; Guimarães, L.N. Systematic Literature Review of Sampling Process in Rapidly-Exploring Random Trees. IEEE Access 2019, 7, 50933–50953. [Google Scholar] [CrossRef]
- Kingston, Z.; Moll, M.; Kavraki, L.E. Sampling-Based Methods for Motion Planning with Constraints. Annu. Rev. Control Robot. Auton. Syst. 2018, 1, 159–185. [Google Scholar] [CrossRef]
- Noreen, I.; Khan, A.; Habib, Z. Optimal Path Planning Using RRT* Based Approaches: A Survey and Future Directions. Int. J. Adv. Comput. Sci. Appl. 2016, 7, 97–107. [Google Scholar] [CrossRef]
- Zhou, X.; Shi, G.; Zhang, J. Improved Grey Wolf Algorithm: A Method for UAV Path Planning. Drones 2024, 8, 675. [Google Scholar] [CrossRef]
- Xu, C.; Duan, H.; Liu, F. Chaotic Artificial Bee Colony Approach to Uninhabited Combat Air Vehicle (UCAV) Path Planning. Aerosp. Sci. Technol. 2010, 14, 535–541. [Google Scholar] [CrossRef]
- Koçyiğit, E.; Sonmez, A.; Kugu, E. Optimal path planning for UAVs using Genetic Algorithm. In Proceedings of the 2015 International Conference on Unmanned Aircraft Systems (ICUAS), Denver, CO, USA, 9–12 June 2015; IEEE: Piscataway, NJ, USA, 2015; pp. 715–2274. [Google Scholar] [CrossRef]
- Lv, F.; Jian, Y.; Yuan, K.; Lu, Y. Unmanned Aerial Vehicle Path Planning Method Based on Improved Dung Beetle Optimization Algorithm. Symmetry 2025, 17, 367. [Google Scholar] [CrossRef]
- Kennedy, J.; Eberhart, R. Particle Swarm Optimization. In Proceedings of the IEEE International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; pp. 1942–1948. [Google Scholar] [CrossRef]
- Li, H.; Liu, X.; Huang, Z.; Zeng, C.; Zou, P.; Chu, Z.; Yi, J. Newly Emerging Nature-Inspired Optimization Algorithm Review, Unified Framework, Evaluation, and Behavioural Parameter Optimization. IEEE Access 2020, 8, 72620–72649. [Google Scholar] [CrossRef]
- Duan, H.; Li, P. UAV Path Planning; Springer: Berlin, Germany, 2014; pp. 99–142. [Google Scholar] [CrossRef]
- Sharma, A.; Shoval, S.; Sharma, A.; Pandey, J.K. Path Planning for Multiple Targets Interception by the Swarm of UAVs Based on Swarm Intelligence Algorithms: A Review. IETE Tech. Rev. 2022, 39, 675–697. [Google Scholar] [CrossRef]
- Xin, J.; Li, Z.; Zhang, Y.; Li, N. Efficient Real-time Path Planning with Self-evolving Particle Swarm Optimization in Dynamic Scenarios. arXiv 2023, arXiv:2308.10169. [Google Scholar] [CrossRef]
- Yu, Z.; Si, Z.; Li, X.; Wang, D.; Song, H. A Novel Hybrid Particle Swarm Optimization Algorithm for Path Planning of UAVs. IEEE Internet Things J. 2022, 9, 22547–22558. [Google Scholar] [CrossRef]
- Phung, M.D.; Ha, Q. Safety-Enhanced UAV Path Planning with Spherical Vector-Based Particle Swarm Optimization. Appl. Soft Comput. 2021, 107, 107376. [Google Scholar] [CrossRef]
- Fu, Y.; Ding, M.; Zhou, C. Phase Angle-Encoded and Quantum-Behaved Particle Swarm Optimization Applied to Three-Dimensional Route Planning for UAV. IEEE Trans. Syst. Man Cybern. A 2012, 42, 511–526. [Google Scholar] [CrossRef]
- Li, W.; Xiong, Y.; Xiong, Q. Reinforcement Learning-Guided Particle Swarm Optimization for Multi-Objective Unmanned Aerial Vehicle Path Planning. Symmetry 2025, 17, 1292. [Google Scholar] [CrossRef]
- Wang, J.; Zhang, Y.; Zhu, S.; Wang, J. A Novel Multi-Objective Trajectory Planning Method for Robots Based on the Multi-Objective Particle Swarm Optimization Algorithm. Sensors 2024, 24, 7663. [Google Scholar] [CrossRef]
- Xia, S.; Zhang, X. Constrained Path Planning for Unmanned Aerial Vehicle in 3D Terrain Using Modified Multi-Objective Particle Swarm Optimization. Actuators 2021, 10, 255. [Google Scholar] [CrossRef]
- Ericson, C. Real-Time Collision Detection; Morgan Kaufmann: San Francisco, CA, USA, 2005. [Google Scholar]
- Coello, C.A.; Lechuga, M.S. MOPSO: A Proposal for Multiple Objective Particle Swarm Optimization. In Proceedings of the 2002 Congress on Evolutionary Computation, Honolulu, HI, USA, 12–17 May 2002; pp. 1051–1056. [Google Scholar] [CrossRef]
- Zaslavsky, G.M. The Simplest Case of a Strange Attractor. Phys. Lett. A 1978, 69, 145–147. [Google Scholar] [CrossRef]
- Farasana, F.J.; Gopakumar, K. A Novel Approach for Speech Encryption: Zaslavsky Map as Pseudorandom Number Generator. Procedia Comput. Sci. 2016, 93, 816–823. [Google Scholar] [CrossRef]
- Li, Z.; Han, Y.; Yang, Y. Multi-Objective Particle Swarm Optimization: A Survey of the State-of-the-Art. Preprints 2025, 2025022011. [Google Scholar] [CrossRef]
- Hong, C.; Jun, Y.; Fei, Y. Chaos Particle Swarm Optimization Enhancement Algorithm for UAV Safe Path Planning. Appl. Sci. 2022, 12, 8977. [Google Scholar] [CrossRef]
- Shu, L.; Wen, Z.; Ming, Q.; Xin, P. Tent–PSO-Based Unmanned Aerial Vehicle Path Planning for Cooperative Relay Networks in Dynamic User Environments. Sensors 2025, 25, 2005. [Google Scholar] [CrossRef]
- Jie, W.; Qiu, Z.; Zhi, L.; Jun, C.; Guo, D.; Qi, W.; Guo, G.; Qian, G. Sparse Bayesian Learning-Based Hierarchical Construction for 3D Radio Environment Maps Incorporating Channel Shadowing. IEEE Trans. Wirel. Commun. 2024, 23 Pt 2, 14560–14574. [Google Scholar] [CrossRef]
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).