1. Introduction
In recent years, Unmanned Aerial Vehicles (UAVs) have been widely deployed in complex operational environments, such as localized warfare, post-disaster rescue, and mountainous logistics, due to their high maneuverability, cost-effectiveness, and reusability [
1,
2]. As a core technology for autonomous UAV missions, path planning algorithms play a critical role in ensuring mission success [
3]. However, existing classical path planning methods (e.g., Artificial Potential Field (APF), Particle Swarm Optimization (PSO), enhanced A* algorithm) fail to achieve universally optimal performance for all real-world scenarios due to the inherent complexity, dynamism, and diversity of UAV operating environments [
4,
5]. For instance, APF is prone to local minima in cluttered environments; simultaneously, PSO and A* struggle with real-time performance in highly dense obstacle fields [
6]. To address these limitations, a viable solution lies in the integration and combination of multiple path planning algorithms that are tailored to specific environmental conditions and optimization objectives [
7].
Under complex environmental conditions, the combination of various UAV path planning algorithms allows the planning task to fully leverage the advantages of each algorithm, enabling the efficient generation of low-energy, obstacle-free, and real-time flight paths [
8,
9]. This combination is not a fusion of multiple algorithms but a combination of flight strategies and mechanisms that are based on the environment [
10]. One algorithm combination method is the traditional multi-algorithm approach, which is based on classical graph search. Mengying and others, by analyzing the advantages, disadvantages, and applicable scenarios of online algorithms such as APF and the improved A*, concluded that a combined algorithm framework can overcome the limitations of single algorithms in real time and achieve better performance [
11]. Lai Rongshen proposed an A* algorithm combined with the Dynamic Window Method (DWM) for flight safety in path planning algorithms [
12]. Gómez Arnaldo and others, based on 3D terrain mapping applications, achieved reasonable building shooting angle coverage via the rapidly exploring random tree (RRT) combined with angle information guidance, optimizing routes and calculation speeds [
13]. Longyan Xu and others proposed a strategy integrating the expanded A*, circular path optimization, and APF methods, balancing global and dynamic planning scenarios and avoiding local optimal situations. However, none of the verifications were conducted in complex environments [
14]. The advantage of such algorithms is that route consumption and solution efficiency are generally superior to a single algorithm, but as the size of the global graph and the scene’s complexity increase, the increase in computational load after 3D expansion can affect the real-time performance of the algorithm.
Another approach is based on biomimetic intelligence methods for algorithm integration. Yan and others combined various heuristic strategies, such as genetic algorithms and PSO, optimizing multiple objectives, including time and cost, and making the strategies suitable for complex scenarios in post-disaster resource scheduling [
15]. Zhen et al. enhanced planning efficiency in complex scenarios by integrating PSO with vibration functions and introducing a Reference Point Method (RPM), achieving optimal paths, although the results depend heavily on initial parameter settings [
16]. Chen et al. transformed the inertia parameter w and learning parameters c1 and c2 in the PSO algorithm from fixed values to nonlinear values that are related to iteration counts, enabling adaptive parameters and accelerating convergence [
17]. Hao et al. divided the population into multifunctional subgroups and introduced a migration mechanism to increase diversity, effectively alleviating homogenization. However, local search capabilities remain limited, and high computational costs are still incurred [
18]. Li Xianqiang combined the Ant Colony Algorithm (ACA) with the APF method and achieved efficient three-dimensional trajectory planning. This approach produces smoother paths compared to ACA alone but comes at the expense of higher computational complexity [
19]. The A* algorithm combined with the Gray Wolf Optimizer (A*-GWO) proposed by Haidar Ahmad et al. can produce safer and shorter paths in environments where wind influence is considered compared to the traditional A* algorithm. However, it cannot guarantee superiority over the A* algorithm in all scenarios [
20]. Deng et al. proposed the Sand Cat Swarm Optimization (SCSO) algorithm, which combines spiral search, Lévy flight [
21], tent chaotic mapping [
22], and mechanisms such as adaptive sparrow warnings—among other random search strategies—to adapt to dynamic environmental changes [
23]. The advantage of this type of algorithm lies in its ability to further optimize the performance of a single intelligent algorithm through algorithmic combinations. It enables dynamic obstacle avoidance in complex environments and supports the optimization of multiple planning objectives. However, its convergence performance is highly sensitive to initial parameter settings, resulting in suboptimal real-time performance.
There is another approach that combines neural-network-based algorithms with reward designs to adapt to specific scene applications. Lee et al., using a Deep Reinforcement Learning (DRL) framework combined with Independent Proximal Policy Optimization (IPPO) and employing Reference Signal Receiving Power (RSRP) as a criterion, planned UAV trajectories suitable for complicated scenarios; however, this algorithm is specifically designed for communication applications [
24]. Chen achieved autonomous UAV flight trajectory planning in unknown environments by designing the current reward value and state-action value selection strategy, combined with DRL algorithms; however, the scenarios are limited to indoor settings [
25]. Liu et al. used a residual convolutional network to learn environmental features offline and predict heading in real time, improving online planning speed; however, this method heavily depends on training data, and its generalization capability still requires validation [
26]. Yan et al. used a Dual Double Deep Q-Network (D3QN) algorithm, combining a greedy strategy, heuristic search rules, and contextual graph Q-values for flight action selection. The method considers safe flights in a radar-detected but threat-prone environment, although it has high computational costs [
27]. Castro et al. proposed an online adaptive path planning solution based on the fusion of RRT and DRL algorithms, achieving fast planning and dynamic obstacle avoidance. It has been successfully applied in the agricultural monitoring field, but flight verification is limited to small-scale areas, requiring further resolutions of real-world scenario generalization and computational efficiency issues [
28]. Algorithms based on DRL perform exceptionally well in dynamic adaptability and autonomous decision-making. However, they are currently constrained by data and perform poorly with respect to computational power, generalization ability, and explainability. As a result, they are more suitable for a specific scenario as supplements rather than a complete replacement of traditional route planning methods.
The review demonstrates that effective UAV path planning requires careful algorithm selection and combination tailored to specific mission scenarios. For time-critical applications, like disaster rescue and logistics delivery, the computational efficiency of path planning algorithms becomes a paramount performance metric.
Recent studies have demonstrated the effectiveness of Voronoi diagrams as a fundamental tool in path planning, serving both as a tool for initial route generation and as a basis for hybrid algorithms. For instance, in urban low-altitude logistic UAV path planning, Zhang et al. utilized Voronoi diagrams to construct initial route networks, which were subsequently optimized through the A* algorithm for obstacle avoidance, demonstrating significant reductions in total route length and improvements in airspace coverage; however, this method is based on 2D maps [
29]. Similarly, in energy-efficient path planning for unmanned surface vehicles (USVs), the integration of Voronoi diagrams and Dijkstra’s algorithm effectively minimized navigation energy consumption [
30]. Furthermore, Voronoi diagrams have been innovatively applied to enhance optimization algorithm initialization. Ayawli et al. developed a multi-frequency vibrational genetic algorithm (mVGA) that incorporates Voronoi diagrams to improve population diversity, substantially reducing computational time for 3D path planning [
31]. In complex dynamic environments, Voronoi diagrams have been synergistically combined with reinforcement learning techniques, such as Q-learning for multi-UAV obstacle avoidance path optimization [
32], and enhanced through morphological dilation (MVDRM algorithm) to improve real-time obstacle avoidance capabilities for mobile robots [
33]. These applications collectively highlight Voronoi diagrams’ versatility and computational efficiency across autonomous systems.
The A* algorithm serves as a core algorithm in the field of UAV route planning and is widely adopted due to its unique advantages in balancing global optimality and efficient search capabilities. By employing a heuristic search mechanism, it significantly reduces computational complexity while ensuring path quality, making it an essential tool for path planning in complex environments. However, when confronted with dynamic environments and challenging terrain, the standalone A* algorithm still exhibits limitations in real-time performance and local adaptability. As shown in
Table 1, A* is often applied in combination with other methods to preserve its inherent advantages in path optimality while leveraging complementary strengths from other approaches, thereby substantially enhancing the overall system stability and scenario adaptability [
34,
35,
36].
Building upon the algorithmic analysis, we propose a hybrid approach that synergistically combines Voronoi diagrams’ environmental abstraction capability with A*’s optimal search properties for UAV 3D path planning in complex mountainous terrain. First, by combining the key feature points of the Voronoi diagram with the vertex heuristic function, an initial flight path network is quickly generated. For paths that cannot be directly generated, A* is used to close gaps, and path points are optimized to ensure the generation of efficient, flyable paths. Secondly, building upon the hierarchical flight concept of UAVs [
37], an adaptive layering strategy is designed based on drone flight performances and Digital Elevation Model (DEM) data, transforming 3D planning into a layer-switching method between adjacent planes and significantly reducing computational complexity. Furthermore, a flight path point optimization mechanism is introduced to avoid terrain obstacles while enhancing both path efficiency and safety. The simulation of real mountain scenarios with multiple sets of test cases shows that, compared to traditional methods such as A*, PSO, and RRT, this method has significant advantages in terms of planning success rates, path lengths, and computation times.
The remainder of this study is organized as follows:
Section 2 reviews the foundational methodologies relevant to the proposed algorithm, encompassing DEM-based adaptive layering strategies, regional Voronoi vertex search diagrams, A* searches, and their hybrid integration for trajectory planning.
Section 3 elaborates on the framework and operational workflow of the proposed algorithm, which enables rapid trajectory planning through a combination of multiple algorithms.
Section 4 presents simulation experiments that validate the efficacy and computational efficiency of the fusion algorithm in mountainous terrain. The subsequent sections comparatively analyze algorithmic performance and explore potential research extensions. Finally, the conclusive findings are summarized.
2. Methodology
2.1. Adaptive DEM Flight Space Layering Model
DEM is a mathematical expression of the true three-dimensional shape of Earth’s surface. It is a type of physical ground model that represents ground elevation information through a set of ordered numerical arrays. In the field of UAV flight path planning, it serves as fundamental data. It can intuitively and realistically depict the geographical features of the UAV’s flight environment. The DEM represents terrain surface features through a discrete elevation data matrix, and its mathematical expression can be defined as follows:
In this context, represents the height value of the grid points i and j in the matrix, and represent the spatial resolution of the regular grid. Compared to Digital Terrain Models (DTMs), DEMs specifically refer to elevation datasets without features, whereas DTMs also include derived terrain parameters, such as the slope and aspect. This distinction is particularly important in complex navigation, as pure elevation data are more conducive to geometric calculations for real-time path planning.
By incorporating DEM data, three-dimensional path planning can be achieved. However, due to the expansion of the search space dimensions, a significant increase in computational load occurs. In cases in which the scale of regional drones is controllable or the flying altitude is substantially higher than the obstacle requirements, DEM layering operations can transform the three-dimensional planning into two-dimensional planning, thereby simplifying the computational load. However, when drones fly through complex mountainous environments, this simplification results in increased path searching consumption due to insufficient two-dimensional information. Based on this, this study combines the flight performance of drones with an adaptive optimal flight level selection method, using adjacent higher layers as alternative obstacle avoidance layers to enable three-dimensional planning. This approach can minimize the computational load while retaining the advantages of three-dimensional paths.
For a given drone flight altitude range [
] and the stratified altitude
, a set of drone flight stratification thresholds is defined as follows:
As indicated by the formula, the selection of
directly determines the number of vertical layers. This parameter should be maximized under the constraint that the aircraft’s inter-layer transition capability must be satisfied within a unit distance, thereby minimizing the computational and memory overhead caused by excessive layering, as shown in
Figure 1.
Among them, N represents the number of layers, and its mathematical expression is shown as follows:
If the drone is flying at the k-th level, this means its flight altitude
lies between two adjacent height planes.
The mathematical expression for the set of terrain obstacles at flight level k is as follows:
There are two criteria for selecting the flight level: on the one hand, the flight level should be as low as possible to minimize energy consumption; on the other hand, obstacles should be avoided. However, these two points are contradictory in real-world scenarios. To solve this problem, this study proposes selecting the optimal drone cruising altitude based on the obstacle density value. The definition of obstacle density at a given altitude is as follows:
The physical meaning of the above equation refers to the percentage of the obstacle occupying the assigned cruising altitude.
The threshold parameter exhibits the following trade-offs:
A higher threshold prioritizes stealth by selecting flight planes closer to the terrain base, but this increases obstacle density and may render path planning infeasible.
A lower threshold improves path optimality by selecting higher-altitude flight planes (reducing obstacles) at the cost of increased detection risks.
By reasonably selecting the threshold, the corresponding optimal fly_plane can be obtained, with b representing the serial number of the best cruising level. The next higher level serves as the backup_plane used for obstacle avoidance when crossing mountainous terrain. To reduce the computational load, the layered obstacle density calculation begins at and approaches in increments of .
2.2. Voronoi Vertex-Based Search Model Based on Weight-Based Heuristic
A Voronoi diagram is used to divide space into several regions based on the principle of minimum distance. The core idea is that any point within a region should be closer to its corresponding generating object than to any other generating object [
38]. In this design, obstacles within the flight layer selected through the adaptive DEM method are utilized as Voronoi objects for vertex generation. The Voronoi vertex generation algorithm proceeds through the following steps.
In the corresponding 2D terrain profile of the flight level, obstacles are classified according to their position , and Voronoi vertices are generated at loci equidistant to multiple obstacles, which are defined by the following.
For any pixel
in the image,
where
is the Euclidean distance between
and obstacle pixel
.
is equidistant to at least two obstacles and lies at the local maxima of DT.
is the gradient field at point .
Candidate vertices,
, are then identified, where the gradient magnitude approaches zero, shown as follows:
Finally, vertices that only retain the local maxima in
are filtered as follows:
where
denotes the 8-neighborhood value of
.
The proposed method’s advantage in trajectory planning is a result of its ability to generate a trajectory in a two-dimensional plane with distances equal to the obstacles, a feature that is particularly important in mountainous environments. Typically, there are valleys and plains between two mountain peaks, which means that the generated route points will have the maximum distance from the obstacles, thus avoiding collisions and ensuring higher safety in the generated flight path.
There are two key elements in the planar image processed using the Voronoi algorithm. One is the set of edges that divides the obstacles, and the other is the set of vertices where these edges intersect. In the field of route planning, the traditional approach is to generate trajectories along the Voronoi edges, followed by turn optimization. This method often results in longer and less-direct routes. We construct a new discrete search space based on the vertices of the Voronoi diagram formed at the flight altitude, assigning weights to all points within this search space and then performing a ranked search. The discrete search space
is defined as follows:
Among them, represents the starting point of the flight plan, represents the ending point of the flight plan, and refers to the number of vertices in the set after Voronoi processing.
Based on the current step’s starting and ending point information, the heuristic weight values for all vertices, , are calculated. Then, all feature points that have no obstacles along the line connecting them to the current starting point are filtered out, and they are subsequently sorted according to their weights. The feature point with the highest weight is selected, and it is connected to the starting point, rendering this vertex the new starting point for the next iteration.
The heuristic weight value
of each Voronoi vertex
in the computational graph is calculated, and verification is carried out to ensure that there is no obstruction in the line connecting the vertices and the current planning starting point. The weight formula is defined as follows:
If there is any obstruction, then .
Among them, represents the distance from the current vertex to the planned starting point, represents the distance between the start and end points, represents the distance from the vertex to the end point, and represents the angle between the vector from the current vertex to the starting point and the vector from the current vertex to the ending point. pi is a constant, represents the height from the vertex to the ground, and represents the maximum flying height of the drone.
The weighting parameters are defined as follows:
: Path proximity-to-origin weight.
Increasing this value prioritizes waypoints closer to the starting point, preventing premature deviations from the initial heading.
: Path proximity-to-goal attenuation weight.
Higher values emphasize feature points near the destination, accelerating the terminal approach.
: Path directional consistency weight.
Enhanced weighting selects waypoints that maintain heading alignments, reducing course oscillations.
: Flight altitude safety margin weight.
Increased weighting favors waypoints with greater vertical clearance from terrain/obstacles.
The sum of the four weights is designed to equal 1. In this algorithm, is 0.1, is 0.3, is 0.5, and is 0.1.
The Voronoi vertex corresponding to the largest value in the sequence is selected, and is the next waypoint connected to the current starting point. The Euclidean distance between this vertex and the planned endpoint is recorded as . Then, this vertex is updated as the new search starting point, the original starting point is removed from the search space, the weights are recalculated, and the vertex with the decreased is selected; this process is then repeated until the planned endpoint is found.
The schematic of the rapid path search method using Voronoi vertices is shown in
Figure 2. By iteratively selecting
as waypoints, a quick generation of the UAV’s trajectory within the flight plane is achieved.
2.3. A* Algorithm for Route Segment Connection
By utilizing Voronoi-vertex-based search models, drones can already plan feasible flight routes in certain scenarios. For instance, in
Figure 3, a flyable path can be determined using only three line segments. However, as the complexity of obstacles increases, situations where it is impossible to quickly generate paths using existing vertices may arise. In such cases, all Voronoi vertices within the known search space have a weight value of 0, or the distance values,
, no longer decrease. Typically, at this point, the starting point has advanced closer to the planned endpoint from its initial position, necessitating an extension of the trajectory to obtain new connectable Voronoi vertices and thereby transforming the problem into a local trajectory search method.
The A* algorithm is a classic heuristic search algorithm. The heuristic function is calculated based on the minimum objective function value from the starting point to the current node combined with the estimated function value from the current node to the target point [
39]. The entire trajectory search relies on this heuristic function. In a two-dimensional plane, the search space of the A* algorithm typically consists of the 8 pixels surrounding the current point. For each pixel in the search space, the cost is computed, and the node with the lowest cost is selected and added to the path as the new starting point. The cost function for node M in the search space is defined as follows:
where,
represents the heuristic factor, indicating the true cost from the initial node to the current node M, and
represents the minimum cost estimate from the current node M to the target node. The search principle is to prioritize expanding nodes with lower
values, which guarantees finding the optimal path. Generally, the A* algorithm demonstrates superior pathfinding performance and high robustness. However, in global route planning, due to the increase in search area, obtaining an optimal path requires a long convergence time and substantial memory space. However, by introducing a quick search strategy based on Voronoi vertices, the search and computation time can be significantly reduced. At this point, the A* algorithm serves as a localized searching algorithm for existing segments. As the search principle of the A* algorithm is well-established, this study does not elaborate on this topic further. We only provide an example of the initiation timing of the A* algorithm as a connection algorithm for route segments.
The connection of flight route segments using the A* algorithm is shown in
Figure 4. After the UAV reaches the point
by rapidly searching the path through the Voronoi vertices, with point
as the new starting point, the only directly connectable Voronoi vertices are
. By comparing the distance to the endpoint vector, point
is already the nearest connectable Voronoi vertex to the end point. At this point, the A* search mechanism is introduced, and the local path toward the endpoint is generated as a connection path, continuing until a new starting point appears in the A* path, where a new quick connection path can be generated in the search space.
2.4. Optimization of Flight Path
The standard process for general UAV flight path planning typically consists of the following three steps: (1) modeling the flight environment space, (2) connecting the starting point and endpoint using a routing algorithm to form an initial flight path, and (3) further optimizing the initial flight path [
40].
The fast search based on Voronoi vertices is a sparse search process with the advantage of high search speeds; this is highly practical when the UAV has sufficient endurance. However, the disadvantage is that it cannot compare with heuristic algorithms in generating flight paths with optimization goals. However, the waypoints based on the fast search model still have significant optimization potential.
The flight path generated after the search is as follows:
where
is the line segment connecting the points
and
.
Fixed-distance interpolation is performed on this segment to generate a new set of interpolation points, as follows:
where
represents the direction of the unit vector, and
represents the number of points after the interpolation of the line segment.
The sequence of the flight path segment is followed to detect the point in the area. If there is no collision in , then point is added to list . If no values meet the conditions, then is retained and added to the list.
The value of is updated to , and interpolation searches are continually performed on until the endpoint is added to .
Compared to the initial flight path, this optimization method allows for the reconstruction of the path, ensuring that the new trajectory connects both the starting and ending points, with each segment of the sub-path avoiding obstacles; moreover, the total path is as short as possible, as illustrated in
Figure 5.
- 2.
Optimization of the Position of Voronoi Vertices
In theory, the vertices obtained after Voronoi division are the farthest from obstacles in the horizontal space, providing a higher safety margin. However, this approach does not take into account the altitude relative to the ground when UAVs fly in complex mountainous environments. Height measurements can be carried out at the vertices and their neighbors using planar detection, and the point with the largest height margin can be selected as the optimized point for use.
The vertex optimization method involves generating a candidate set
for each initial vertex
by performing a plane rasterization process.
Here, represents the neighborhood search radius, represents the elevation data scale, and represents the number of search points.
The safety margin for elevation is calculated at each point in the search area as follows:
where
is the height value corresponding to the point in the DEM, while
denotes the height of the current flight plane.
The principle of safety margin maximization is adopted as follows:
The optimized vertices are then updated to the new Voronoi vertex set. By establishing the vertex optimization mechanism, the altitude margin for drone flights is significantly improved, making the flight path more reliable. However, the optimization process is computationally intensive and dependent on the search design, introducing additional computational loads. In time-sensitive planning scenarios, this optimization option can be disabled.
2.5. Complexity Analysis
According to the algorithm’s design, the proposed method primarily consists of the following key components: Voronoi vertex acquisition, heuristic-based vertex selection, A* connection, and interpolation-based path optimization. The theoretical computational complexity analysis of these components is as follows.
The computational complexity of Voronoi vertex acquisition is , where and denote the width and height of the flight plane map, respectively, corresponding to a space complexity of .
Assuming that the number of vertices in the Voronoi diagram on the map is , the heuristic-based vertex selection method exhibits a computational complexity of and a space complexity of .
The A* connection algorithm exhibits a computational and space complexity of , where denotes the branching factor (number of expanded nodes per level) and represents the depth of the optimal path segment. The proposed Voronoi–A* framework strategically applies A* only to short path segments, where the limited depth guarantees low computational complexity.
The interpolation-based path optimization has a computational complexity of and a space complexity of , where denotes the number of interpolation points along the path.
The algorithm demonstrates well-bounded computational and space complexity. The Voronoi vertex acquisition stage dominates the overall cost with a time complexity of and a space complexity of . Subsequent heuristic-based vertex selection operates at time complexity and space complexity, while localized A* connections maintain manageable complexity through constrained path segments. The final path optimization only requires linear time/space complexity. This phased complexity design ensures efficient scalability, while initial map processing requires more computation, with subsequent steps slowly increasing in computational demands, maintaining high efficiency even when handling large-scale problems.
4. Implementation and Results
The algorithm’s simulation environment is configured on a laptop equipped with an Intel Core i9-10900K CPU and 64 GB of memory, using Windows 10 as the operating system and MATLAB R2023a as the programming environment for simulation experiments.
To evaluate the performance of the newly proposed Voronoi–A* fusion algorithm, we carry out a comparison with the following algorithms in simulation tests across several complex mountainous environments: APF, traditional A*, and RRT. The three real elevation map scenarios include mountainous, hilly, and canyon terrain, which represent typical complex mountainous features. In each of the three terrains, a drone uses different algorithms to plan the flight path from the same starting point to the same destination. The comparison is based on factors such as the success of path planning, the number of waypoints, path length, and planning time, evaluating the performance of each algorithm in different terrains and obstacle environments. All DEM data employed in the experiments were obtained through Global Mapper v19.1.
To ensure experimental design fairness, we conducted 20 repeated trials for each comparative method under the same scenario and statistically analyzed the key performance metrics, including the success rate of the flight path’s generation, the planned path length, the number of critical waypoints, and the required computational time.
For a consistent comparison, all algorithms (A*, RRT, APF, etc.) were simplified to 2D trajectory planning by adopting the same flight altitude level as the proposed method. The computational time measurement started after DEM-based layered 2D flight-level map generation (a preprocessing step that can be performed offline) and ended upon the completion of the planning process.
4.1. Scene 1: Mountainous Terrain
The same starting and ending points are set with a map scale of 1:0.2. In the simulation, the position of the UAV is represented by discrete coordinates. The top-left corner of the top–down view serves as the coordinate’s origin, and the bottom-left corner of the 3D view also serves as the coordinate’s origin. Therefore, the sum of the Y-coordinate values of the same point in both views corresponds to the image’s width. The simulation results of five algorithms under this terrain are as follows.
- (a)
The planning path under the Voronoi–A* fusion algorithm simulation environment, as shown in
Figure 1, features a UAV flight path with DEM cross-layer flights, enabling 3D obstacle traversal and successfully overcoming a mountain peak obstacle. This scenario’s planning process includes all steps, such as Voronoi vertex selection, A* search expansion, cross-layer flight, and interpolation optimization.
Figure 7a illustrates the first step of the algorithm’s search for Voronoi vertices, while
Figure 7b describes the algorithm’s rapid path search from the starting point to the endpoint. In this step, an A* expansion search is performed after crossing layers, resulting in the unoptimized search path. The blue line indicates a climb during this segment of the flight, the red * marks the start of the flight, and the green * marks the endpoint.
Figure 7c shows the optimized flight path after interpolation optimization.
Figure 7d presents the final 3D flight path.
- (b)
The APF algorithm’s planned path in the simulation environment is shown in
Figure 8, where the algorithm’s attraction coefficient is 15, the repulsion coefficient is 5, and the influence radius is 10 pixels. Due to the potential field balance issue in complex environments, it is clearly evident that the aircraft’s flight path directly passes through high mountains, resulting in a crash. Therefore, in terrains with complex topography and numerous three-dimensional obstacles, this method is not feasible.
- (c)
The planned path of the RRT algorithm in the simulation environment is shown in
Figure 9. Compared to the Voronoi–A* fusion algorithm, the path is noticeably more winding and complex. Additionally, due to the introduction of random factors, the consistency of the path planning is poor each time.
- (d)
The planned path of the A* algorithm in the simulation environment is shown in
Figure 10. It can be observed that the A* algorithm successfully plans a path that bypasses obstacles. In comparison to
Figure 7, due to the influence of the A* search range, the number of planned path points increases, which results in higher computational complexity, longer calculation times, and a significantly longer total flight distance.
The test results of the four algorithms in this scenario, in addition to the start point (5, 177) and end point (351, 51), are compared, with statistics shown in
Table 2. ± represents the average value of the statistical results of 20 tests carried out for each algorithm.
Figure 11a shows 2D simulation results, with four algorithms’ paths color-coded, while
Figure 11b presents the statistical analysis results of 20 RRT trials, comparing time, waypoint count, and path length against their respective averages. The green line represents the self-developed Voronoi–A* fusion algorithm, the red line represents the A* algorithm, the magenta line represents the APF algorithm, and the blue line represents the RRT algorithm. The red * above the magenta line indicates the position where the obstacle was hit.
The simulation results of the mountainous terrain clearly show that the Voronoi–A* fusion algorithm has significant advantages in path planning. By combining Voronoi layering with A* search, inter-layer flights are enabled. The number of path points is only 4.9% of that of the A* algorithm (17 vs. 349), and the planning time is reduced by 96.1% (3.36 s vs. 85.14 s). This is the only method that fully implements three-dimensional obstacle avoidance.
Limitations of Traditional Algorithms: APF causes collisions with mountains due to the imbalance of the potential field; RRT has high path complexity and unstable path costs.
4.2. Scene 2: Hilly Terrain
The same starting and ending points are set with a map scale of 1:0.2. The simulation results of the four algorithms under this terrain are as follows.
- (a)
The planned path in the Voronoi–A* fusion algorithm simulation environment is shown in
Figure 12. It can be observed that the aircraft’s flight path includes an alternate flight level after climbing, enabling it to cross mountainous terrain and successfully avoid obstacles.
- (b)
The APF algorithm’s planned path in the simulation environment is shown in
Figure 13. The algorithm sets initial parameters with a gravity coefficient of 15, a repulsion coefficient of 5, and an influence of 10 pixels. In a complex environment with mountainous terrain and numerous obstacles, it is clearly evident that the aircraft’s flight path directly passes through the mountains, causing the plane to crash. Moreover, the algorithm is sensitive to parameter settings. Therefore, the simulation results in this scenario indicate that the APF method is not feasible.
- (c)
The RRT algorithm’s planned path in the simulation environment is shown in
Figure 14. In comparison to the self-developed Voronoi–A* fusion algorithm, the path is noticeably more convoluted and complex. Moreover, across multiple simulation scenarios, the outcome of planning—success or failure—is uncertain. In cases of successful planning, the path is complex, and computational efficiency is relatively low.
- (d)
The planned path of the A* algorithm’s simulation environment is shown in
Figure 15. In this scenario, the A* algorithm has an advantage over the Voronoi–A* fusion algorithm in terms of the total path length. However, the number of planned path points and the computation time are both inferior to those of the Voronoi–A* fusion algorithm. In practical engineering applications, in terrain with relatively more obstacles, the flight complexity of the A* algorithm increases.
The test results of the four algorithms in this scenario with start point (50, 55) and end point (200, 120) are compared, with statistical data shown in
Table 3. ± represents the average value of the statistical results of the 20 tests carried out on each algorithm.
The 2D simulation planning path in this scenario is shown in
Figure 16.
From the hilly terrain simulation results, it is evident that the path planning efficiency of the Voronoi–A* hybrid algorithm is significantly superior, with the number of path points being only 2.6% of that in the A* algorithm (4 vs. 151), and the planning time is reduced by 76.3% (0.81 s vs. 3.42 s). Additionally, the path length is nearly optimal (159.72 vs. 155.37). The failure of the APF is due to its sensitivity to parameters (gravitational coefficient of 15/repulsive coefficient of 5), which results in the flight path’s collision with obstacles, rendering it ineffective in a complex scenario.
4.3. Scene 3: Canyon Terrain
The same starting and ending points are set with a map scale of 1:0.2, and the test results of the four algorithms are as follows.
- (a)
The planned path in the Voronoi–A* fusion algorithm simulation environment is shown in
Figure 17. It can be observed that the aircraft only requires three key waypoints to successfully navigate over obstacles at the same flight altitude, realizing successful path planning.
- (b)
The APF algorithm’s planned path in the simulation environment is shown in
Figure 18. The parameter settings are consistent with those of the previous scene’s setup. As the middle portion of the canyon terrain is relatively open, the APF computes the gravitational field to guide obstacle avoidance. Path planning is successful. The planned path is short, and time costs are relatively low. Therefore, the APF algorithm is also applicable in certain open environments.
- (c)
The path planning of the RRT algorithm in the simulation environment is shown in
Figure 19. Compared to the Voronoi–A* fusion algorithm, the path is noticeably more winding and complex, resulting in higher computational complexity and longer computation times for real-world applications.
- (d)
The planned path for the A* algorithm simulation environment is shown in
Figure 20. The traditional A* algorithm can successfully navigate around obstacles. Compared to
Figure 17, the number of planned path points increases, resulting in longer computation times.
The test results of the four algorithms in this scenario with start point (10, 74) and end point (128, 170) are compared, with data summarized in
Table 4. ± represents the average value of the statistical results of the 20 tests carried out on each algorithm.
The 2D simulation planning path in this scenario is shown in
Figure 21.
From the simulation results of the canyon terrain, it can be observed that the Voronoi–A* fusion algorithm for path planning has the advantage of producing extremely simplified paths. Voronoi–A* enables horizontal obstacle avoidance using only three key points, and its planning time is 13.8% of that of the RRT algorithm (0.81 s vs. 5.88 ± 3.47 s), demonstrating its efficiency in open scenarios. The APF algorithm is sporadically applicable, successfully navigating only in canyon scenes with sparse obstacles, but the number of path points is 63 times greater than that of Voronoi–A* (190 vs. 3).
4.4. Analysis of Simulation Results in Multiple Scenarios
The comprehensive performance comparison of the simulation results across multiple scenarios is shown in
Table 5.
The summary in
Table 5 indicates that the Voronoi–A* fusion algorithm significantly outperforms traditional algorithms in path planning performance within complex mountainous environments, as evidenced in the following aspects.
Path Planning Success Rate: The Voronoi–A* fusion algorithm successfully avoided obstacles and had no collisions in all test scenarios, while the APF algorithm failed to handle three-dimensional obstacles, resulting in crashes in mountainous and hilly terrain (success rate of only 33%). The RRT algorithm exhibited unstable performance, with planning failures occurring.
Path Efficiency:
- (a)
Path Length: The Voronoi–A* path length is shorter than that of the traditional A* algorithm. For example, in mountainous terrain, the length is reduced by 0.5% (373.78 vs. 375.56 units), and in canyon terrain, it remains more efficient (132.12 vs. 134.28 units).
- (b)
Number of Waypoints: The number of waypoints is reduced by an average of 92% compared to the A* algorithm (for example, in mountainous terrain, only 17 points are needed, whereas the A* algorithm requires 349 points), significantly reducing flight complexity.
Computational Efficiency:
The path planning time of Voronoi–A* is significantly superior to that of all the comparison algorithms:
- (a)
Voronoi–A* has a faster average of 96.1% compared to the A* algorithm (e.g., in mountainous terrain, 3.36 s vs. 85.14 s).
- (b)
It is 7.2 times faster than the RRT algorithm in canyon terrain (0.81 s vs. 5.88 ± 3.47 s).
- (c)
The APF algorithm is fast (2.41 s) in open areas (such as canyons), but it completely fails in complex environments with dense obstacles.
Three-Dimensional Adaptability:
Voronoi–A* enables 3D obstacle avoidance through multi-layered flights, whereas APF and RRT only support 2D planning in certain scenarios. For example, in mountainous terrain, APF fails to cross peaks, causing the path to collide with obstacles, while Voronoi–A* successfully navigates around them in 3D.
In summary, the Voronoi–A* fusion algorithm, by combining the hierarchical strategy of Voronoi diagrams with the A* heuristic search, demonstrates significant advantages in path planning success rates, path optimality, computational efficiency, and three-dimensional obstacle avoidance. It provides an efficient and reliable solution for drone path planning in complex mountainous environments.