Next Article in Journal
Development of an Energy Consumption Minimization Strategy for a Series Hybrid Vehicle
Previous Article in Journal
Optimizing EV Charging Station Carrying Capacity Considering Coordinated Multi-Flexibility Resources
Previous Article in Special Issue
Development of an EV Battery Management Display with CANopen Communication
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Efficient Path Planning Algorithm Based on Delaunay Triangular NavMesh for Off-Road Vehicle Navigation

1
School of Computer and Artificial Intelligence, Zhengzhou University, Zhengzhou 450001, China
2
School of Geo-Technology, Zhengzhou University, Zhengzhou 450001, China
*
Author to whom correspondence should be addressed.
World Electr. Veh. J. 2025, 16(7), 382; https://doi.org/10.3390/wevj16070382
Submission received: 13 June 2025 / Revised: 5 July 2025 / Accepted: 6 July 2025 / Published: 7 July 2025

Abstract

Off-road path planning involves navigating vehicles through areas lacking established road networks, which is critical for emergency response in disaster events, but is limited by the complex geographical environments in natural conditions. How to model the vehicle’s off-road mobility effectively and represent environments is critical for efficient path planning in off-road environments. This paper proposed an improved A* path planning algorithm based on a Delaunay triangular NavMesh model with off-road environment representation. Firstly, a land cover off-road mobility model is constructed to determine the navigable regions by quantifying the mobility of different geographical factors. This model maps passable areas by considering factors such as slope, elevation, and vegetation density and utilizes morphological operations to minimize mapping noise. Secondly, a Delaunay triangular NavMesh model is established to represent off-road environments. This mesh leverages Delaunay triangulation’s empty circle and maximum-minimum angle properties, which accurately represent irregular obstacles without compromising computational efficiency. Finally, an improved A* path planning algorithm is developed to find the optimal off-road mobility path from a start point to an end point, and identify a path triangle chain with which to calculate the shortest path. The improved road-off path planning A* algorithm proposed in this paper, based on the Delaunay triangulation navigation mesh, uses the Euclidean distance between the midpoint of the input edge and the midpoint of the output edge as the cost function g ( n ) , and the Euclidean distance between the centroids of the current triangle and the goal as the heuristic function h ( n ) . Considering that the improved road-off path planning A* algorithm could identify a chain of path triangles for calculating the shortest path, the funnel algorithm was then introduced to transform the path planning problem into a dynamic geometric problem, iteratively approximating the optimal path by maintaining an evolving funnel region, obtaining a shortest path closer to the Euclidean shortest path. Research results indicate that the proposed algorithms yield optimal path-planning results in terms of both time and distance. The navigation mesh-based path planning algorithm saves 5~20% of path length than hexagonal and 8-directional grid algorithms used widely in previous research by using only 1~60% of the original data loading. In general, the path planning algorithm is based on a national-level navigation mesh model, validated at the national scale through four cases representing typical natural and social landscapes in China. Although the algorithms are currently constrained by the limited data accessibility reflecting real-time transportation status, these findings highlight the generalizability and efficiency of the proposed off-road path-planning algorithm, which is useful for path-planning solutions for emergency operations, wilderness adventures, and mineral exploration.

1. Introduction

Path planning in off-road environments refers to finding safe and efficient paths for vehicles in areas lacking established roads, crucial for emergency response in disaster events [1,2]. Off-road environments, typically located in remote or rural areas, often present a variety of complex and natural features and obstacles posing challenges to successful vehicles passing through [3]. These challenges arise from two primary factors, including the complex nature of terrain features and the variability in the maneuverability of different vehicles under the complex and different land cover in off-road conditions (such as farmland, forest, grassland, shrubland, wetland etc.), complicating the developing generalizable and quantitative models for mobility analysis [4]. Thus, quantifying the impacts of geographical factors on off-road mobility, developing universal models to map passable areas, and establishing path-planning algorithms specifically designed for off-road environments become important for efficient path planning [5,6].
Terrain modeling for off-road mobility focuses on understanding how terrain factors impact vehicle performance. These algorithms consider factors complicating mobility analysis for vehicles, including varying elevations, slopes, vegetation, vehicle capability, and potential obstacles to generate optimal paths [7,8]. Using binary classification (passable zones suitable for vehicle movement and obstacle zones) based on different land types to represent the environment is a common approach in off-road navigation tasks [9,10,11,12,13]. Studies have emphasized the role of terrain attributes, such as Digital Elevation Models (DEMs) and soil types, in shaping off-road vehicle dynamics, while others systematically categorized these factors into six domains, including landforms, vegetation, land water systems, residential facilities, land transportation networks, and soil types [14]. These foundational studies underscore the demand for a universal standard to quantify cross-region mobility, addressing complex interactions among terrain features and vehicle capabilities.
How to accurately represent the natural environment in a navigation system presents unique challenges for path planning in off-road environments. Traditional road navigation systems rely on topological graphs composed of edges (road segments) and nodes (intersections) to represent road networks [15]. This approach cannot be directly applied to off-road settings due to the absence of a predefined road network. Although visibility graphs can be established by creating connectivity between significant landmarks, obstacles, or waypoints, the simplicity of topological graphs can lead to losses of details of the environment, potentially limiting the ability to find optimal paths or avoid obstacles that are not explicitly depicted in the graph [16,17]. Research has explored grid-based mesh and Voronoi diagrams to model off-road environments for path planning [18,19]. Grid-based models represent the environment as a grid of nodes and edges, where each grid cell corresponds to a node, and adjacent cells are connected by edges. Chen (2023) proposed a hexagonal grid-based approach for off-road path planning, highlighting its suitability for irregular terrains [20]. Wu et al. (2024) introduced a hierarchical environmental modeling strategy, combining elevation and land cover data to generate multi-layer grid-based models, improving mobility analysis for off-road areas [21]. Voronoi diagrams effectively partition free space into cohesive regions, where each region associates with a specific point or object, such as individual obstacles [22]. The diagram edges highlight the collision-free paths. However, the diagram structure may not always align well with the terrain field, leading to unnecessary complexity [23].
While 8-direction square grids have traditionally shown promise for off-road path planning [24], recent studies have highlighted the potential of Delaunay triangulation NavMeshes for large-scale environment representation [25]. Although studies have emphasized the effectiveness of grid-based systems on efficient grid connectivity and dynamic terrain adaptability for autonomous vehicles in rugged terrains [26], the method is sensitive to the efficiency of path planning and can struggle to represent irregular obstacles accurately. Grid cells intersecting with obstacles are often marked as impassable, potentially limiting the feasible path space [27]. A finer grid resolution offers a more detailed representation of the environment but demands greater computational resources, while a coarser resolution reduces storage and computational load but may fail to capture smaller obstacles [28,29]. Delaunay triangular NavMeshes, a well-established data structure in virtual environments, gaming, and indoor environments [30,31], offer a promising alternative for off-road path planning. By partitioning passable regions into convex polygons, Delaunay triangulation provides a more flexible and adaptive representation of terrain obstacles [31,32]. Constrained Delaunay triangular NavMeshes ensure accurate alignment with obstacle boundaries, improving the representation of complex terrains. The unique properties of Delaunay triangulation, such as empty circle and max-min angle, contribute to efficient NavMeshes generation and smaller data representations [33,34]. However, the application of Delaunay triangulation to off-road scenarios remains relatively unexplored.
Various algorithms have been developed for off-road path planning in natural environments, each with distinct advantages and challenges. The A* algorithm is a well-known search method that efficiently finds optimal paths in grid-based environments. However, its performance degrades in dynamic or highly complex terrains, and its reliance on grid representations limits scalability [35]. Variants like D* Lite improve on A* by enabling incremental updates for dynamic replanning, reducing computational costs in changing environments [36]. Researchers have also explored advanced algorithms like Theta* and particle swarm optimization to improve computational efficiency in off-road environments. Theta* enhances path quality by allowing smoother, more direct routes through continuous space [37]. Rapidly-Exploring Random Trees (RRT) excel in high-dimensional spaces but often produce suboptimal, winding paths [38], while Artificial Potential Field (APF) methods can lead to path oscillations, increasing computation time and path length [39]. Probabilistic Roadmaps (PRM) are useful for large spaces but suffer from inefficiency in complex environments [40]. The Funnel Optimization algorithm addresses these challenges by combining global search with local optimization, balancing exploration and exploitation to produce smoother, more efficient paths in constrained environments [41]. However, the application of Funnel Optimization to off-road scenarios remains relatively unexplored. Recently, several machine learning-assisted optimization methods have been introduced to enhance path planning performance in complex or unstructured environments. These include neural-network-based heuristics to accelerate search [42], learning-based trajectory prediction to mimic human driving behavior [43], and deep reinforcement learning for terrain-aware decision-making [44]. It can be seen from the above literature [42,43,44] that machine learning-based methods have great potential in off-road path planning. However, in emergency situations such as rescue operations, the shortest path needs to be found quickly. Path planning algorithms based on machine learning require high computational costs, which contradicts our scenario requirements. Additionally, due to the “black box effort” inherent in machine learning, it lacks the interpretability of the process.
Off-road path planning often suffers from inefficiencies in data processing and high computational costs, particularly in dynamic terrains. An efficient path-planning algorithm that balances path quality, computational efficiency, and scalability while being adaptive to real-time environmental changes is still absent. To address the limitations, an improved off-road path-planning algorithm was developed in this study, as follows: (1) A land cover mobility model was introduced to facilitate generalizability at the national scale; (2) A Delaunay triangular NavMesh-based environment model was introduced to make efficient off-road environment representation; (3) An improved A* algorithm was introduced to derive efficient path planning in off-road environments.
The key contribution of this study can be listed as below: (1) The paper innovatively integrates global-level LULC (land Use/land Cover) and DEM (Digital Elevation Model) datasets to model vehicle traversability in off-road environments, facilitating long-distance navigation at larger scales such as thousands of square kilometers (2). The paper innovatively adapts the Delaunay triangulation NavMesh model, an environment representation model commonly used in virtual gaming, to model real environments, which facilitates cost-effective off-road navigation. (3) The paper innovatively proposed an improved off-road path planning A* algorithm, based on the Delaunay triangulation navigation mesh, which uses the Euclidean distance between the midpoint of the input edge and the midpoint of the output edge as the cost function g ( n ) , and the Euclidean distance between the centroids of the current triangle and the goal as the heuristic function h ( n ) . The proposed algorithm will plan the optimized off-road mobility path from the start point to the end point, and determine a chain of path triangles that can be used to calculate the shortest path. (4) Given that the improved road-off path planning A* algorithm determines a chain of path triangles for calculating the shortest path, the funnel algorithm was then introduced to transform the path planning problem into a dynamic geometric problem, iteratively approximating the optimal path by maintaining an evolving funnel region, obtaining the shortest path closer to the Euclidean shortest path.

2. Methods

The proposed off-road path planning algorithm aims to provide optimal paths for vehicles navigating through complex terrains in natural environments (Figure 1). To establish uniform passable maps applicable to a national scale, land cover and terrain data were extracted from global-level datasets [45]. These datasets were integrated with mobility thresholds derived from prior literature reviews. This integration yielded a raw mobility map, reflecting potential passage areas across the region. Morphological operations were subsequently applied to eliminate noise and refine the map to represent the passable areas better. Delaunay triangulation was then employed to construct a triangular NavMesh, efficiently representing the study region’s structural characteristics. The final path planning results were computed using the improved A* algorithm and further optimized through the funnel algorithm.
Slope and land cover (vegetation, water systems, residential areas, roads) are the main factors affecting vehicle passing in an off-road environment. Due to the significant impact of slope and surface coverage on the off-road vehicle mobility, quantitative modeling of various land covers over different vehicles is relatively complex. The focus of this article is on exploring how to efficiently represent an off-road environment into a digital model that can accurately describe passable and obstacle areas for vehicles, by considering slope and surface coverage factors. A binary model relying on morphological analyses, classifying the off-road environment by 0 (obstacle area) and 1 (passable area) is adopted to generate a thematic map of the obstacle areas affecting off-road mobility.

2.1. Mobility Modeling in Off-Road Environments

Various geographic factors exert differing influences on the off-road mobility of vehicles. The core of off-road path planning involves identifying obstacles and passable areas to ensure safe and efficient vehicle mobility. Quantitative modeling of off-road mobility obstacles involves the quantitative modeling of environmental elements, based on fundamental DEM and land cover data. Mathematical morphology processing is applied to construct a thematic map delineating areas that impact off-road mobility. Generally, topography, roads, vegetation, water bodies, and settlements all significantly impact vehicle mobility [46].

2.1.1. Vehicle Mobility Quantification of Terrain Factors

Terrain features exert the most significant influence on vehicle mobility, such as slope and surface conditions in off-road environments. The slope is commonly used to quantify its impact on mobility, as increasing the slope angle directly leads to greater slope resistance, thereby reducing mobility. Generally, areas with slopes exceeding 30 degrees can be classified as obstructed, while those with slopes less than 30 degrees are considered passable [47].
A 3 × 3 moving window was applied to DEM data to derive the slope at the center cell relative to its eight surrounding cells [48] (Figure 2). Specifically, the slope value in each direction is calculated as the ratio of the elevation difference between the center cell and its neighboring cells to the horizontal grid distance. The mobility of each grid cell can be determined by comparing this slope map with the maximum climbing capacity of a vehicle. A grid cell will be considered impassable if the slope exceeds the vehicle’s maximum climbing capacity. To simplify subsequent analysis, areas with slopes greater than 30 degrees are defined as obstacles, while areas with slopes less than 30 degrees are defined as passable areas.
According to the elevation information, the slope in X-direction and Y-direction can be calculated in Equations (1) and (2), and the slope can be calculated in Equation (3).
S x = ( H i + 1 , j 1 + 2 H i , j 1 + H i 1 , j 1 ) ( H i + 1 , j + 1 + 2 H i , j + 1 + H i 1 , j + 1 ) 8 R
S y = H i + 1 , j + 1 + 2 H i + 1 , j + H i + 1 , j 1 ( H i 1 , j + 1 + 2 H i 1 , j + H i 1 , j 1 ) 8 R
S h = a r c t a n S x 2 + S y 2
where   S h is the slope of the current grid, H h is the elevation of the neighboring cell, H i , j is the elevation of the center cell, and R represents the resolution of DEM data.

2.1.2. Vehicle Mobility Quantification of Land Cover Factors

Vegetation, including forests, grasslands, shrublands, and crop fields, significantly influences vehicle mobility in off-road environments due to varying vegetation characteristics. This research leverages GlobeLand30 to obtain detailed land cover characteristics within this study area. The concept of “land cover mobility” from reference [20] was employed to quantify the impact of various land cover types on vehicle mobility. Land cover types, including, farmland, forest, grassland, shrubland, wetland, and water body, were extracted from the GlobeLand30 dataset and assigned mobility to each land cover from previous studies (Table 1) [49].
Forests pose the most significant obstacles to vehicle mobility and visibility [50]. Grasslands generally have a minor impact on vehicle mobility, often being considered passable areas for off-road vehicles [51]. The mobility coefficient for crop fields is commonly defined as 0.6 [20]. The density and distribution of shrublands are the primary factors affecting vehicle mobility, where sparse shrublands have a mobility coefficient of 0.4, and dense shrublands are considered impassable areas [20]. Dense residential areas are typically regarded as impassable obstacles [20]. Water body characteristics, including rivers, lakes, and wetlands, significantly influence vehicle mobility. The mobility of wetlands is closely related to mud depth. Mud depths exceeding 40 cm are considered impassable, and those less than 10 cm are considered passable [20]. The distribution and density of lakes are essential indicators for analyzing mobility obstacles [47].
Q = S / A
where S represents the total area of the study area, and A represents the area occupied by lakes and reservoirs within the study area (Table 1).
Assuming there are m × n grid cells of land cover data within the off-road area, the mobility of any given grid cell is denoted as r g r i d . Based on reference [20], a grid cell is defined as an obstacle if   r g r i d < 0.6 . In other words, the land cover types will be utilized and integrated into two categories based on a passability threshold to define the obstacle and passable areas.

2.1.3. Off-Road Passable Area Mapping and Morphological Process

The algorithm for off-road path planning involves dividing roadless areas into passable zones suitable for vehicle movement and obstacle zones unsuitable for traffic through a quantitative analysis of geographical environmental elements, enabling the planning of optimal routes for vehicle movement within the passable areas. These elements include terrain, vegetation, hydrographic features, and settlements that potentially affect vehicle trafficability. Terrain is the primary factor that affects a vehicle’s off-road mobility, where vehicles are usually unable to pass when the ground slope exceeds 30 degrees. The slope is usually calculated based on DEM data of the study area is encountered, resulting in the generation of a slope map for the region. The calculated slope level of one grid cell is denoted as a r c t a n ( S i , j ) . Besides topographic slope, land cover types significantly influence vehicle off-road mobility. Scholars have developed a coefficient system to quantify the surface trafficability of different land covers, through expert scoring or analytical hierarchy methods [9,10,11,12,13].
The land cover in the GLC data was employed to measure the mobility of the cell g r i d i , j . The mobility was derived based on the spatial resolution at 4 m in which the land cover was unsampled from 30 m to 4 m denoted as r g r i d ( i , j ) . As depicted in Table 1, this includes 13 land covers, including crop, forest, grassland, shrubland, wetland, river, bare land, and snow. The mobility of one grid cell is denoted as r g r i d .
r g r i d = i = 1 m r i / m
where m indicates the number of geographical elements in the grid and r i indicates the mobility coefficient of a grid retrieved from Table 1.
For an off-road region represented by an m × n grid of surface coverage cells, any cell g r i d ( i , j ) is considered as passable if r g r i d ( i , j ) 0.6 and a r c t a n ( S i , j ) < 30 ° . The collection of all passable cells constitutes the passable area, with all other non-passable cells forming the obstacles. Due to the complex features and varied terrain in off-road environments, the obstacle regions generated using this method inevitably exhibit irregularities such as boundary noise, internal holes, and object adhesion, significantly impacting the accuracy and efficiency of subsequent path planning. Therefore, it is necessary to apply morphological analysis to generate clean and precise passable mapping, including noise removal, hole filling, and separating connected objects (Figure 3).

2.2. Delaunay Triangular NavMesh-Based Environment Representation

A novel navigation model is developed based on the Delaunay triangulation, specializing in off-road environment navigation. The model relies on Delaunay triangulation, incorporating obstacle constraints to construct a grid structure suitable for path planning in off-road terrain. Navigation meshes are a classic data structure for path planning, commonly used in virtual environments [52]. Navigation meshes simplify the representation of environmental obstacles and involve partitioning passable regions into a collection of convex polygons [53]. Each convex polygon serves as a node, and adjacent nodes are connected by edges, forming a navigation graph. Since any line segment connecting two points within a convex polygon lies entirely within that polygon, path planning algorithms can guarantee that the computed path remains confined to the navigation mesh, thereby enhancing both efficiency and accuracy (Figure 4)
A constraint-based Delaunay triangular NavMesh is constructed through an iterative process [54]. Initially, all edges of the obstacle and boundary polygons are collected into a Constraint-Set, and all vertices into a V -Set. An edge is randomly selected from the Constraint-Set and added to a Processing-Set. An edge p is then chosen from Processing-Set, and a vertex v is identified in V -Set such that the triangle formed by p and v adheres to the empty circle property. It does not intersect any obstacle’s interior. Edges not in Constraint-Set and Processing-Set are added to Processing-Set for further processing. This process repeats until the Processing-Set is empty. This iterative refinement yields a Delaunay triangulation that satisfies the given constraints, forming the basis of the navigation mesh. Figure 4 depicts the Delaunay triangular NavMesh, the constraint edges in obstacle areas, and the concept of visible points. One vertex is considered visible from a common edge if an obstacle lies to the right (clockwise) of the edge. The arrow indicates the clockwise direction to determine the visibility of the points.

2.3. A* Algorithm Improvement and Funnel Optimization

2.3.1. Improved A* Algorithm

When performing path planning, except for the start triangle and the end triangle, the path intersects both the entry and exit edges of each triangle it passes through. The cost from the starting point of the path to the current triangle should be equal to the cost from the starting point to a certain node P on the exit edge of the current triangle (node P is essentially the intersection between the path and either the entry or exit edge of the triangle). In practical calculations, when the algorithm expands to a particular triangle, the destination has not yet been reached, so it is impossible to determine the exact path that connects the start and end points and passes through that triangle. As a result, the coordinates of the intersection node P (i.e., the entry or exit point of the path within the triangle) cannot be determined. Therefore, a reasonable approximation of node P must be selected instead. In practice, characteristic nodes of the triangle are commonly used as substitutes for node P, such as the triangle’s vertices, centroid, or the midpoints of the input and output edges (Figure 5).
According to Figure 4 in this paper, the Delaunay triangular NavMesh model incorporates obstacle constraints. This paper selects the midpoints of the input and output edges as characteristic nodes. The reason why the improved A* algorithm proposed in this paper uses the middle line of the Delaunay triangle to connect the entry and exit edges for planning is that it makes full use of the properties of the Delaunay triangulation based on the obstacle constraint edges, and generates the safest (maximizing the distance from the), most natural (fitting the centerline of the channel), and the best initial smoothness (path continuity) path network. This is the core value of the Delaunay navigation mesh model applied in path planning.
The improved road-off path planning A* algorithm proposed in this paper, based on the Delaunay triangulation navigation mesh, uses the distance between the midpoint of the input edge and the midpoint of the output edge as the cost function g ( n ) , and the distance between the centroids of the current triangle and the goal as the heuristic function h ( n ) .
A path chain of triangles refers to a sequence of triangles, connected by shared edges, that extends from the triangle containing the start point to the triangle containing the goal point, such that the path traverses all these triangles (Figure 5b). The A* algorithm is a classic path-planning algorithm designed for navigation meshes. Its core component is the heuristic function [55,56].
f ( n ) = g ( n ) + h ( n )
where g n is the actual cost specifying the distance between start point to the midpoint of the input edge and the midpoint of the output edge of the current triangle, the current node n is the midpoint of the output edge, and h n is the Euclidean distance from the midpoint of the current triangle’s output edge to the destination. The g n was employed to compute the following:
g n = w k 1 , k
where the g n at the current triangle is calculated as the sum of the accumulated cost of the previous triangle and the Euclidean distance between the midpoints of the input and output edges; w k 1 , k is the length of the path through the current triangle.
h n = c e n t r o i d s g o a l 2
where c e n t r o i d s represents the c e n t r o i d s coordinates of the current triangle’s out edge, and goal represents the coordinates of the end point.

2.3.2. Funnel Optimization Algorithm

The key concept of the funnel optimization algorithm is to approximate the shortest path in a triangular structure by dynamically constricting the funnel region.
The key concept of the funnel optimization algorithm is to approximate the shortest path in a triangular structure by dynamically constricting the funnel region. Paths produced by the improved A* algorithm on navigation meshes do not necessarily correspond to the Euclidean shortest path but rather represent a series of connected midpoints of triangular edges that form a chain of triangular paths (Figure 6a). To obtain a path closer to the Euclidean shortest path, the funnel algorithm was introduced to transform the path planning problem into a dynamic geometric problem, iteratively approximating the optimal path by maintaining an evolving funnel region (Figure 6b). Key concepts of the funnel algorithm include paths, funnels, and vertices. A path represents a partially found shortest path, while a funnel is defined by two edges—a clockwise and a counterclockwise edge—enclosing the potential region of the remaining shortest path. Starting from the origin node, the algorithm gradually expands the funnel and updates it based on the relationship between the current vertex and the funnel. Specifically, if the newly added vertex lies within the funnel, the funnel is updated; otherwise, it remains unchanged. The funnel will be reconstructed if the funnel’s shape is altered. By iteratively applying this process, a path approximating the Euclidean shortest path is obtained, with all turning points coinciding with the funnel’s vertices (Figure 6c).
The overall funnel optimization operation can be expressed by the pseudo-code in Algorithm 1.
Algorithm 1: Funnel optimization
Input: Apex point = Start of path P s , Path A* = Results of A*;
Output: Shortest path = P a t h .
1. path = P s ;
2. The vertex of the current funnel: a p e x = P s
3. l e f t _ b o u n d = P s
4. r i g h t _ b o u n d = P s
5. for each triangle in channel:
6.    a , b = get_edges(triangle)
7.   if a at the right side of l e f t _ b o u n d or align with l e f t _ b o u n d :
8.      if a = = a p e x or the direction from apex to at the right of side of apex to l e f t _ b o u n d :
9.         l e f t _ b o u n d = a
10.      else:
11.       Continue
12.   else:
13.       l e f t _ b o u n d = a
14.   if b at the left side of or align with the right_bound:
15.     if b == apex or the direction from apex to b at the left side of the edge from apex to r i g h t _ b o u n d
16.       right_bound = b
17.     else:
18.        continue
19.   else:
20.        right_bound = b
21.   if l e f t _ b o u n d interact with r i g h t _ b o u n d :
22.      if distance(apex, left_bound) < distance(apex, right_bound):
23.        path.append( l e f t _ b o u n d )
24.        apex = l e f t _ b o u n d
25.      else:
26.      path.append( r i g h t _ b o u n d )
27.      apex = right_bound
28.       l e f t _ b o u n d = apex
29.       r i g h t _ b o u n d = apex
30.   Path.append(end)
31.   Return Path

2.3.3. Path Planning for Off-Road Navigation

The objective function can be denoted as follows:
P a t h = F u n n e l ( A * ( C D T V , E c ) , S t a r t , G o a l )
where V represents the vertex of multi-polygon, E C represents the constraints edge of the multi-polygon; C D T represents the operation of Delaunay triangulation; S t a r t is the starting point of path planning and the G o a l is the endpoint of path planning; A * ( . ) represents the A* algorithm and F u n n e l ( . ) represents the Funnel optimization; P a t h represents the planned path.
The overall navigation operation can be expressed by the pseudo-code in Algorithm 2. As depicted in Figure 7, the path is first improved by the improved A* algorithm (Figure 7a), and then further refined by the funnel algorithm (Figure 7b) to produce the optimal paths. In future work, the heuristic function could be extended to incorporate terrain difficulty metrics such as slope or land cover resistance, to further improve path accuracy in heterogeneous off-road environments.
Algorithm 2: The path planning algorithm based on the Delaunay Navmesh
Input: GlobaLand 30 dataset, 4 m DEM data, each land cover type area, each grid area, Start
Point A ; End Point B
Output: the Shortest path, Path length, running time
1. Load GlobaLand 30 dataset;
2. Load 4 m DEM data;
3. Passable_area = [], Obstacle_area = [], S = [], r_grid = [];
4.  For each grid i in the research area:
5.   For each land element in all m land cover types, do:
6.       Obtain the mobility coefficient r i from Table 1.;
7.       Calculate the r g r i d ( i ) from Equation (5);
8.       Calculate the slope for each grid from Equations (1) to (3);
9.       If r g r i d i > 0.6     and slope < 30 ° :
10.        Passable_area.add( i );
11.      Else:
12.        Obstacle_area.add( i );
13.      Passable_area = Morphological_analysis(Passable_area);
14.      Passable_area = Delaunay(Passable_area);
15.      A* path search from A to B ;
16.      If the A* path search end, then:
17.        Funnel optimization;
18.      Else repeat (16);
19.      Return: the shortest path, Path length, running time

2.3.4. Complexity Analysis

(1) Improved A* algorithm complexity analysis
In the improved A * algorithm, the number of access nodes and edges depends on the design of the heuristic function h ( n ) . When h   ( n ) = 0 , all nodes and edges need to be accessed. The highest memory complexity of the improved A* algorithm is O ( V + E ) , which represents the number of nodes and the number of edges accessed. V represents the number of nodes, and E represents the number of edges accessed.
In the improved A* algorithm, the heap operation is used to manage the nodes in the open list, to quickly access and update the nodes with the minimum estimated total cost. The time complexity required for a heap operation is O ( log V ) . The highest time complexity of the improved A* algorithm is O ( ( V + E ) log V ) .
(2) Funnel optimization complexity analysis
The time complexity of the funnel optimization is usually related to the number of polygons in the path chain, assuming that the path found by improved A * contains m polygons. The time complexity of the funnel algorithm is O   ( m ) .
The funnel optimization usually needs to store the current funnel state, including the left and right boundaries and vertices. The memory complexity is O ( k ) , k   indicating the number of vertices in the funnel.
Since the funnel optimization is optimized on the basis of the A* algorithm, thus k V , m E .
The complexity analysis of improved A* and A* + Funnel optimization is listed in Table 2.
Without significantly increasing the complexity, the proposed algorithm can significantly reduce the search path length, which will be validated in subsequent experiments.

2.4. Experiment Design

A thorough experiment was designed to examine the effectiveness of the proposed NavMesh and funnel optimization algorithm (Table 3). The effectiveness of Delaunay triangulation was examined using two different types of meshes, including an 8-directional grid and a hexagonal mesh. The effectiveness of funnel optimization was examined by comparing it with the well-established Dijkstra algorithm, and an ablation experiment was also conducted with the improved A* algorithm.
The key parameters that need to be set in the Dijkstra algorithm are the weights used for edge selection, which are determined by the edge length. The key parameters that need to be set in the A* algorithm are the weights and the heuristic function. The weights are similar to those in the Dijkstra algorithm, determined by the edge length, and the heuristic function is Euclidean distance. The funnel algorithm is a fully automatic function.

3. Results

3.1. Experiment Settings

To simulate the rescue operation of emergency response teams in urgent events for path planning in an off-road environment, four regions with complex land cover and land use were selected as experiment areas. Experiment site A specifies a 2400 km2 region, and site B specifies a 960 km2 region. Site C and Site D specify 1620 km2 and 672 km2 regions, respectively. Four sites are typical off-road environments in China (Figure 8). As depicted in Figure 8, site A is a densely populated region located in the central plains and hills, characterized by large urban settlements. The terrain is highly fragmented, and the area is intersected by a significant river system, most notably the Yellow River and its tributaries. Due to the complex topography and hydrological conditions, the road network is relatively underdeveloped. Site B is a representative mountainous region with dense vegetation cover. The area is characterized by significant elevation differences and a well-developed river network. The rugged terrain and dense vegetation make the construction of transportation infrastructure challenging, resulting in a sparse road network. The population density in this region is low. Site C and Site D are lakeside and coastal areas with dense water bodies. The basic dataset used for obstacle mapping and navigation representations includes the 4-m resolution DEM and 30-m resolution Global Land Cover (GLC) dataset. The 4-m resolution DEM datasets are sufficient for the study areas, according to earlier literature research [57,58]. Sometimes, a DEM with 4-m resolution may not explicitly capture elevation variations smaller than this threshold. However, in off-road path planning, what primarily affects vehicle mobility is the slope rather than absolute elevation differences. The proposed method incorporates slope analysis and morphological processing to ensure that significant terrain constraints, such as steep inclines or impassable obstacles, are effectively represented. In addition, the selection of a 4-m DEM balances terrain detail and computational efficiency. While finer resolutions (e.g., 1-m LiDAR) provide more precise topographical data, they significantly increase processing costs, which can be prohibitive for real-time applications. Coarser resolutions may fail to capture essential mobility constraints. Therefore, the choice of the 4-m resolution DEM datasets ensures sufficient detail for vehicle path planning while maintaining a feasible computational workload. The GLC dataset consists of both artificial land use and natural land cover on a global scale. In this study, all data were sampled to 4 m and unified by the year 2000 coordinate system to facilitate consistent space. All experiments were implemented with the configuration shown in Table 4. The hardware and software specifications were selected based on the laboratory’s available computing environment and to meet the computational requirements of spatial data processing and visualization tasks.

3.2. Passable Area Mapping

As depicted in Table 5, the vehicle mobility model effectively and clearly illustrates passable and obstacle areas by considering terrain and land cover characteristics. Terrain is the primary aspect that impacts a vehicle’s ability to move off-road. When the land slopes more than thirty degrees, vehicles typically cannot pass. Moreover, different geographical elements, such as crops, forests, shrublands, wetlands, bare land, and so on, exhibit varying impacts on off-road vehicle mobility. Urban elements such as buildings and residential urban blocks inherently function as artificial obstacles to vehicle movement. For Site A, crops, built-up, and forests dominate the land cover, occupying 60.1%, 16.6%, and 16.5% of the total landscape, respectively. As the site is located in a relatively flat area, the majority of the crop area, along with portions of the built-up and forest areas, are classified as passable. In Site B, forest and crop cover dominate the land cover, occupying 61.2% and 34.7%, respectively. Given the area’s mountainous terrain with rugged features, the majority of the forest and part of the crop cover are classified as obstacles, with only 27.6% of the land cover classified as passable. The proportion of obstacle area and passable area at sites A, B, C, and D in Table 5 is consistent with the distribution of land cover type in this area. These results demonstrate the obstacle model’s effectiveness and generalizability in detecting passable and obstacle areas based on real terrain characteristics.
As depicted in Figure 9, the Delaunay triangular NavMesh effectively represents the off-road environment by triangulating the space. Large triangles cover areas with uniform and regular shapes, indicating a passable area. Conversely, smaller triangles delineate areas with irregular shapes, suggesting regions with dense obstacles. In Figure 9b, each colored triangle represents a navigable unit, forming a compact mesh structure over the passable terrain. In Figure 9c, the planned paths, marked from yellow start points to red end points, demonstrate how the algorithm efficiently navigates through the triangular mesh while avoiding obstacles. This triangulation visually and intuitively simplifies the data structure, reducing the complexity of representing the off-road environment. As a result, the path planning algorithm can generate more efficient and accurate paths, a claim that will be further supported by the results presented in Section 3.3.

3.3. Path Planning Comparison

According to previous research [49,59,60], the core of off-road path planning is to quickly plan a path that meets the requirements of real-time performance and minimal travel costs. Therefore, this article uses path planning time and planned path length as indicators for algorithm evaluation. To validate the effectiveness of the proposed path planning algorithm in off-road environments, a comparison experiment is conducted with the 8-directional grids and hexagonal grids from the literature [21,59]. In the 8-directional grid approach, each grid cell is considered a potential unit for path searching. In the hexagonal grid approach, the environment is divided into uniform hexagons with a 120 m radius. In contrast, the navigation mesh approach uses triangles of varying sizes to fit the terrain closely, making it more adaptable to complex off-road environments. The path planning results are shown in Figure 10 and Table 6. The running time (denoted as ms) refers to the total computation time in milliseconds for each path planning method.
Experimental results demonstrate that the proposed navigation mesh algorithm exhibits significant advantages in both path length and running time. Specifically, in site A, the navigation mesh algorithm generated a path length of 29.65 km, which was approximately 5% shorter than the 31.34 km path generated by the hexagonal grid-based algorithm and 20% shorter than the path generated by the 8-directional grid-based algorithm. As for the running time, the navigation mesh algorithm spent 170 ms, which was approximately 500 times faster than the hexagonal grid-based algorithm and 133 times faster than the 8-directional grid-based algorithm. In site B, the proposed algorithm required only 153 milliseconds to find the optimal path with a length of 26.61 km. Compared to the conventional method, the proposed algorithm is 7% shorter than the 28.67 km of the hexagonal grid-based method and 20% shorter than the 35.62 km of the 8-directional grid-based method. The proposed navigation mesh algorithms are 641 and 437 times faster than the 8-directional grid and hexagonal grid algorithms, respectively. Table 6 demonstrates the generalizability of the proposed algorithm across various off-road environments. In these diverse settings, the algorithm consistently outperforms the hexagonal grid-based approach and the 8-directional grid-based approach in terms of both computational efficiency and path length [49,59,60]. Specifically, these results indicate that the navigation mesh-based algorithm is not only faster but also capable of generating shorter paths.

4. Discussion

The proposed framework includes innovations in both terrain-based mobility modeling and efficient environment representation. The following discussion elaborates on each component.

4.1. Off-Road Mobility Modeling and Environment Representation

This study provides a new perspective and a uniform framework for quantifying off-road mobility modeling of geographic factors nationally. Off-road mobility assessments require the rapid identification of passable areas, necessitating an accurate quantitative analysis of the impact of regional geographic factors on vehicle performance. However, the significant variability in geographic environments, such as land cover and terrain features, across different regions makes it challenging to develop a universally applicable national mobility analysis model [61]. This study addresses this challenge by leveraging the 30 m resolution land cover dataset of China, which includes both artificial built-up surface and vegetation cover data, in conjunction with publicly available global-scale DEMs. This integration enables a consistent classification standard, spatial-temporal resolution, coordinate system, and data accuracy for off-road mobility assessment across the entire China. This concept and method are consistent with studies indicating that a uniform classification baseline is necessary for application domains [62], especially for navigation systems. In addition, due to the complex features and varied terrain in off-road environments, the obstacle regions generated inevitably exhibit irregularities such as boundary noise and internal holes, significantly impacting the accuracy and efficiency of subsequent path planning. Therefore, additional morphological analysis is necessary to refine the obstacle map to a cleaner and more precise passable map. Figure 11 presents the obstacle distribution map generated for a specific region using the land cover and corresponding mobility parameters. White areas in (a–f) represent obstacles, while in (g) indicate passable regions. The obstacle regions in (b) appear fragmented and require mathematical morphology processing to form clean passable area mapping, consistent with demand in many public utility sectors where a cohesive and clean map is necessary for practical usage [63]. The obstacle mapping framework with these morphological procedures not only facilitates a uniform classification standard for off-road environments but also ensures an efficient searching process for subsequent path planning.
The navigation mesh model proposed in this study facilitates efficient data loading and computational performance for path planning usage. In traditional grid-based path planning in off-road environments, where road networks are absent, the choice of grid size significantly impacts path planning efficiency [64]. The characteristics of Delaunay triangulation are used to substantially reduce the number of triangular elements required to cover the target area, leading to fewer neighboring nodes loading. This technique mitigates the issue of excessive obstacle region expansion standards in regular grid-based methods, as the Delaunay triangulation dynamically adjusts triangle sizes to conform to the shape of obstacles [65]. The number of polygons, including units or triangles, was used to assess the data efficiency of the navigation meshes compared to other path-planning database types. This can be proved by Table 7, which indicates that the navigation meshes yielded significantly fewer units than the 8-directional grids and hexagonal grids. As depicted in Table 7, the grid cell counts in 8-directional, hexagonal, and navigation mesh grids are determined by the underlying geometric structures: pixel cells, hexagonal cells, and triangles, respectively. In site A, the navigation mesh produced 10,523 units, which is only 21.2% of the units of hexagonal grids and 0.6% of the units of 8-directional grids. In site B, the navigation mesh produced 5120 units, which is only 56.7% of the units of the hexagonal grids and less than 1% of the 8-directional grids. Although Site A is clearly far more complex than Site B, as indicated by the number of units in 8-directional grids and hexagonal grids (with a ratio of 2.49 to 5.49 times more complex), the navigation mesh yielded significantly simpler units in both sites (with a ratio of 2.1 times more complex), further proving that navigation meshes can produce simple and concise navigation systems. By eliminating unnecessary obstacle data in large, unobstructed areas, this approach significantly reduces the number of triangles and neighboring nodes to be explored during path planning. This reduction not only simplifies the search process but also improves computational efficiency, a critical factor in real-time applications for autonomous vehicles operating in off-road environments.
According to the previous research [66,67], the time complexity of the Navmesh is O ( m log m ) , while the time complexity of the grid is O ( n 2 log n ) . Here, m   represents the number of polygons in the navigation mesh, and n represents the grids in a map. As can be seen from Table 7, m n . Therefore, the complexity of the Navmesh is much lower than the computational complexity of the grid. This also theoretically proves that the proposed algorithm in this article has high efficiency in path planning compared with grid-based methods.
The proposed optimized A* algorithm, coupled with a funnel algorithm, yields significantly shorter paths and improved computational efficiency compared to conventional methods. Traditionally, path planning algorithms in continuous spaces require paths to traverse through the midpoints of shared edges in a triangle path chain. However, this constraint often leads to sub-optimal solutions, particularly in navigation mesh-based path planning. To address this limitation, the proposed algorithm leverages the navigation mesh structure and employs a novel cost function based on the distance between the midpoints of shared edges in the path chain. Additionally, a heuristic function, utilizing the distance between the triangle centroid and the goal, guides the path search process. To further refine the generated paths, a funnel algorithm is integrated. Extensive experiments conducted in diverse off-road environments demonstrate that the algorithm consistently produces shorter paths and significantly outperforms conventional methods in terms of computational efficiency. This improvement is primarily attributed to the inherent advantages of navigation mesh-based path planning, which allows for efficient exploration of the searching space within triangular regions, eliminating the need for exhaustive cell-by-cell traversal and searching in conventional grid-based searching algorithms. Thus, the algorithm can quickly identify sub-optimal solutions, thereby meeting the stringent timing requirements of real-time path planning applications. The experimental results demonstrate the superiority of the proposed algorithm in terms of path quality and computational efficiency for off-road scenarios.
To verify the effect of the funnel algorithm, an ablation experiment is conducted; results are shown in Table 8 and Figure 12.
From Figure 12, it could be seen that the path obtained by the improved A* algorithm on navigation meshes is relatively rugged and does not necessarily correspond to the Euclidean shortest path. In contrast, the improved A* path planning algorithm optimized by the funnel algorithm outperformed the improved A* algorithm, achieving much distance savings in total path distance.
Table 8 demonstrates that although the funnel algorithm can prolong the running time by about 1~5%, the path obtained is significantly shorter than the improved A* algorithm.

4.2. Structural and Algorithm Efficiency Validation Through Comparative Experiment

To further demonstrate the structural and algorithmic advantage of the proposed Delaunay triangular NavMesh and improved A*+Funnel optimization, a supplementary comparison was conducted using the well-established Dijkstra algorithm.
Table 9 shows the path length and computation time for both structures using Dijkstra. It can be seen that the NavMesh model produced a slightly longer path (2.61 km vs. 2.74 km), but the computation time was drastically lower—only 5 ms, compared to 3430 ms under the grid model. This illustrates that even under identical search logic, the NavMesh achieves superior computational efficiency by reducing the number of nodes and avoiding unnecessary expansions. This substantial speedup is attributed to the adaptive and sparse triangulation of the NavMesh. Unlike fixed-size grids that generate uniform dense nodes—regardless of terrain complexity—the NavMesh dynamically adjusts triangle sizes, using large triangles in open areas and smaller ones near obstacles. This significantly reduces the number of searchable units and accelerates node expansion.
Figure 13 further illustrates this structural difference. In Figure 13a, the path over the grid appears rigid and inefficient due to fixed cell directions. In contrast, Figure 13b shows how the NavMesh structure enables smoother and more realistic traversal, tightly conforming to passable regions without redundant detours. Additionally, Table 10 presents the experimental results of different algorithms applied to the NavMesh. Both Dijkstra and A* algorithms yield the same shortest path, which corresponds to the result shown in Figure 13b, and thus is not repeated here; the red path in Figure 13b indicates the Dijkstra and A* algorithms. The only difference lies in the computation time: A* achieves a shorter runtime—1 millisecond, compared to 5 milliseconds for Dijkstra. This further demonstrates the effectiveness of the NavMesh model proposed in this study.
These results collectively support a key insight: that efficient off-road path planning does not solely rely on the complexity of the search algorithm, but significantly benefits from the underlying environmental representation. By leveraging the structural flexibility of Delaunay triangulation, our NavMesh model inherently reduces node complexity and enables faster, smoother path computation. This structural advantage remains evident across both heuristic-based (A*) and non-heuristic (Dijkstra) algorithms, underscoring its robustness and generalizability.
In order to further prove the efficiency of the proposed algorithm, the proposed improved A*+Funnel optimization algorithm is compared with the Dijkstra algorithm in Sites (a) and (b). The results in Figure 14 further illustrate the differences between the two algorithms. The algorithm proposed in this paper realizes a smoother path. On the contrary, the paths generated by the Dijkstra algorithm are more redundant. Table 11 shows the experimental results of different algorithms applied to Navmesh. Compared with the Dijkstra algorithm, the algorithm proposed in this paper can produce the shortest path, which corresponds to the blue line shown in Figure 14. Compared with Dijkstra’s 8 milliseconds, the proposed algorithm only needs 2 milliseconds. Additionally, the path length planned by the algorithm proposed in this paper has been shortened by nearly half compared with the Dijkstra algorithm (2.95 km vs. 4.85 km), which further proves the effectiveness of the proposed algorithm.

4.3. Advantages, Limitations, and Recommendations

This study introduces a novel off-road path planning algorithm utilizing a navigation mesh model to model the complex off-road environments using Delaunay triangulation. The method was established in a database concentrating on a national scale, in which its effectiveness was proved by 4 cases with typical natural and social landscapes. While the proposed off-road path planning algorithm significantly increases accuracy and efficiency, there are still some limitations. Firstly, the current mobility assessment is based on a binary classification of passable and non-passable areas, failing to adequately take into consideration the continuous and multi-layered nature of geographic environments. Real-world terrain generally exhibits a continuous spectrum of mobility influenced by multiple geographical conditions and the mobility parameters of the vehicles. Secondly, it is difficult to precisely characterize particular topographic features in various regions due to the land cover data used in this study’s weak classification accuracy at small scales. These mapping products, while providing a generalized global classification for China, are limited by the complexity of global geographic environments and lack the granularity to represent regional variations accurately. In addition, the proposed approach does not account for vehicle dynamic constraints, which can affect the realism and safety of the generated paths.
In the future, the research could incorporate multi-scale terrain analysis, soil types, vegetation cover, and vehicle factors to capture the interactive effects of various geographic elements on vehicle mobility, thereby establishing a more refined mobility model and further enhancing the algorithm’s feasibility and applicability. Furthermore, the subsequent research could integrate high-resolution remote sensing imagery and field survey data to construct more region-specific land cover classification systems, thereby improving path planning accuracy. Future research should consider vehicle dynamic constraints to develop more realistic path planning models. Additionally, multi-objective path planning, which simultaneously considers factors such as path length, energy consumption, and safety, represents an important direction for future exploration. This optimization achieved in off-road path planning has the potential for a wide range of similar applications, including autonomous vehicle navigation in rugged terrains [6,20] and virtual nuclear facility simulations, where precise path planning is essential to minimize exposure [61].

5. Conclusions

This study introduces a novel off-road path planning algorithm that utilizes a navigation mesh model and an optimized A* algorithm, effectively modeling complex off-road environments using Delaunay triangulation and obstacle constraints in a compact database. The A* search algorithm, enhanced with a funnel algorithm, is employed to efficiently find optimal paths within the navigation mesh. Experimental results show that this method significantly outperforms grid-based approaches, achieving a 5% to 20% reduction in total path distance and a planning time of 150 to 170 milliseconds, which is significantly faster than the conventional 8-directional and hexagonal grid method, indicating a substantial improvement in computational efficiency. The navigation mesh requires less than 1% of the original data volume, highlighting its computational efficiency and potential applications in enhancing off-road vehicle capabilities and aiding disaster response operations. By employing a navigation mesh, the algorithm successfully captures intricate terrain details. The profound impacts of the algorithm proposed in this paper can be summarized as follows: (1) Using Delaunay Navmesh achieves environmental modeling of passable areas with only 1% of the data compared with grid-based methods, which demonstrates its high data-model efficiency; (2) The algorithm proposed in this paper can obtain the shortest path and effectively support decision-making in path planning.
Nonetheless, limitations remain, including a binary representation of terrain traversability, simplistic land cover classification, and a lack of consideration for vehicle kinematics. To address these, future work should focus on enhancing the environmental representation by integrating high-resolution land cover maps, vehicle dynamic models, and elevation-based terrain detail. Moreover, with the increasing availability of high-frequency remote sensing imagery and geospatial big data, there is significant potential to adapt this framework for near-real-time, large-scale operations. Incorporating temporally dynamic and data-driven terrain assessments will further enhance the robustness and adaptability of the algorithm, particularly in rapidly changing conditions such as natural disasters or extreme weather events.

Author Contributions

Conceptualization, T.T.; Methodology, T.T.; Software, T.T.; Validation, H.W. (Huijing Wu); Investigation, H.W. (Huijing Wu) and H.W. (Haitao Wei); Resources, J.S.; Writing—original draft, T.T.; Writing—review & editing, F.W.; Supervision, F.W. and J.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Li, K.; You, X.; Zhang, X.; Tang, F. Soil Data Construction Method for Cross-Country Trafficability Analysis. J. Syst. Simul. 2019, 31, 158–165. [Google Scholar]
  2. Zhao, J.; Li, Y.; Tong, J.; Zhu, B.; Wu, W.; Sun, B.; Han, J. Cross-Country Road Classification Method Based on Vehicle Dynamic Response Characteristics. Automot. Eng. 2022, 44, 909–918. [Google Scholar]
  3. Ramirez-Robles, E.; Starostenko, O.; Alarcon-Aquino, V. Real-Time Path Planning for Autonomous Vehicle Off-Road Driving. PeerJ Comput. Sci. 2024, 10, e2209. [Google Scholar] [CrossRef] [PubMed]
  4. Peng, L.; Zhou, Y.; Zhang, M. A Study of Lateral Trajectory Tracking Control under Fused Slip Rate and Road Random Inputs. J. Phys. Conf. Ser. 2023, 2451, 012007. [Google Scholar] [CrossRef]
  5. Li, J.; Ling, M.; Zang, X.; Luo, Q.; Yang, J.; Chen, S.; Guo, X. Quantifying Risks of Lane-Changing Behavior in Highways with Vehicle Trajectory Data under Different Driving Environments. Int. J. Mod. Phys. C 2024, 1, 1. [Google Scholar] [CrossRef]
  6. Chen, X.; Zheng, J.; Li, C.; Wu, B.; Wu, H.; Montewka, J. Maritime Traffic Situation Awareness Analysis via High-Fidelity Ship Imaging Trajectory. Multimedia Tools Appl. 2023, 83, 48907–48923. [Google Scholar] [CrossRef]
  7. Stavrinidis, S.; Zacharia, P. An ANFIS-Based Strategy for Autonomous Robot Collision-Free Navigation in Dynamic Environments. Robotics 2024, 13, 124. [Google Scholar] [CrossRef]
  8. Mishra, D.K.; Thomas, A.; Kuruvilla, J.; Kalyanasundaram, P.; Prasad, K.R.; Haldorai, A. Design of mobile robot navigation controller using neuro-fuzzy logic system. Comput. Electr. Eng. 2022, 101, 108044. [Google Scholar] [CrossRef]
  9. Frederick, P.; Kania, R.; Rose, M.D.; Ward, D.; Benz, U.; Baylot, A.; Willis, M.J.; Yamauchi, H. Spaceborne path planning for unmanned ground vehicles (UGVs). In Proceedings of the MILCOM 2005—2005 IEEE Military Communications Conference, Atlantic City, NJ, USA, 17–20 October 2005; Volume 5, pp. 3134–3141. [Google Scholar]
  10. Eder, M.; Steinbauer-Wagner, G. Why Did My Robot Choose This Path? Explainable Path Planning for Off-Road Navigation. In Proceedings of the 2024 33rd IEEE International Conference on Robot and Human Interactive Communication (ROMAN), Pasadena, CA, USA, 26–30 August 2024; pp. 139–145. [Google Scholar]
  11. Zhao, D.; Ni, L.; Zhou, K.; Lv, Z.; Qu, G.; Gao, Y.; Yuan, W.; Wu, Q.; Zhang, F.; Zhang, Q. A Study of the Improved A* Algorithm Incorporating Road Factors for Path Planning in Off-Road Emergency Rescue Scenarios. Sensors 2024, 24, 5643. [Google Scholar] [CrossRef]
  12. Zhang, Y.; Song, D.; Li, C. Energy-Efficient Shortest Path Planning Based on Improved D* Lite Algorithm in Large-Scale Off-Road Environments. In Proceedings of the 2023 3rd International Conference on Electronic Information Engineering and Computer (EIECT), Shenzhen, China, 17–19 November 2023; pp. 168–173. [Google Scholar]
  13. Philip, A.F.; Bernard, L.T.; Derek, W. Remote imagery for unmanned ground vehicles: The future of path planning for ground robotics. Proc. SPIE 2006, 6384, 638405. [Google Scholar]
  14. Liu, Y.; Gao, X.; Wang, B.; Fan, J.; Li, Q.; Dai, W. A Passage Time–Cost Optimal A* Algorithm for Cross-Country Path Planning. Int. J. Appl. Earth Obs. Geoinf. 2024, 130, 103907. [Google Scholar] [CrossRef]
  15. Renzer, G.; de Almeida Ribeiro, I.; Guo, H.-B.; Fröhlich-Nowoisky, J.; Berry, R.J.; Bonn, M.; Molinero, V.; Meister, K. Hierarchical Assembly and Environmental Enhancement of Bacterial Ice Nucleators. Proc. Natl. Acad. Sci. USA 2024, 121, e2409283121. [Google Scholar] [CrossRef]
  16. Zhang, X.C.; Zhang, X.Y. Based on NavMesh to Implement AI Intelligent Pathfinding in Three-Dimensional Maps in UE4. In Proceedings of the Proceedings of the 2022 5th International Conference on Algorithms, Computing and Artificial Intelligence, Sanya, China, 23–25 December 2022; pp. 1–6. [Google Scholar]
  17. Lozano-Pérez, T.; Wesley, M.A.; Fritsch, F.N. An Algorithm for Planning Collision-Free Paths Among Polyhedral Obstacles. Commun. Assoc. Comput. Mach. 1979, 22, 560–570. [Google Scholar] [CrossRef]
  18. Kim, M.-J.; Kang, T.Y.; Ryoo, C.-K. Real-Time Path Planning for Unmanned Aerial Vehicles Based on Compensated Voronoi Diagram. Int. J. Aeronaut. Space Sci. 2025, 26, 235–244. [Google Scholar] [CrossRef]
  19. Bajpai, P.; Bansal, J.C. Voronoi Tessellations-Based Simple Optimizer. Inf. Sci. 2024, 676, 120795. [Google Scholar] [CrossRef]
  20. Chen, Z.; Wu, B.; Wang, R.; Dai, W.; Xu, D.; Ma, C. Multi-Hierarchy Hexagonal Grid Traffic Model for Off-Road Path Planning. Acta Geod. Cartogr. Sin. 2023, 52, 1562–1573. [Google Scholar]
  21. Wu, B.; Chen, Z.; Lu, X.; Xiao, B. A Hierarchical Model with Hexagon Grids for Multi-Objective Route Planning in Large-Scale Off-Road Environments. Int. J. Geogr. Inf. Sci. 2024, 38, 1388–1413. [Google Scholar] [CrossRef]
  22. Zhou, M.; Li, J.; Wang, C.; Wang, J.; Wang, L. Applications of Voronoi Diagrams in Multi-Robot Coverage: A Review. J. Mar. Sci. Eng. 2024, 12, 1022. [Google Scholar] [CrossRef]
  23. Hausken, L. Navigating the Complex Terrain of Photography and Temporality. Philosophies 2024, 9, 60. [Google Scholar] [CrossRef]
  24. Xu, H.; Yu, G.; Wang, Y.; Zhao, X.; Chen, Y.; Liu, J. Path Planning of Mecanum Wheel Chassis Based on Improved A* Algorithm. Electronics 2023, 12, 1754. [Google Scholar] [CrossRef]
  25. Bonichon, N.; Bose, P.; de Carufel, J.-L.; Despré, V.; Hill, D.; Smid, M. Improved Routing on the Delaunay Triangulation. Discrete Comput. Geom. 2023, 70, 495–549. [Google Scholar] [CrossRef]
  26. Badar, T.; Backman, J.; Visala, A. Vehicle Modeling and State Estimation for Autonomous Driving in Terrain. Control Eng. Pract. 2024, 152, 106046. [Google Scholar] [CrossRef]
  27. Chu, K.; Lee, M.; Sunwoo, M. Local Path Planning for Off-Road Autonomous Driving with Avoidance of Static Obstacles. IEEE Trans. Intell. Transp. Syst. 2012, 13, 1599–1616. [Google Scholar] [CrossRef]
  28. Lazarowska, A. Impact of the Grid Size on the Performance of Ant Colony Optimization-Based Algorithm for Ship Safe Path Planning. Lect. Notes Netw. Syst. 2023, 709, 371–381. [Google Scholar]
  29. Gao, H.; Zhang, C.; Pei, S.; Wu, X. Region of Interest Analysis Using Delaunay Triangulation for Facial Video-Based Heart Rate Estimation. IEEE Trans. Instrum. Meas. 2024, 73, 1–12. [Google Scholar] [CrossRef]
  30. Dai, S.; Wu, T. Rigidity of the Delaunay Triangulations of the Plane. Adv. Math. 2024, 456, 109910. [Google Scholar] [CrossRef]
  31. Miky, Y.; Kamel, A.; Alshouny, A. A Combined Contour Lines Iteration Algorithm and Delaunay Triangulation for Terrain Modeling Enhancement. Geo-Spat. Inf. Sci. 2022, 26, 1–19. [Google Scholar] [CrossRef]
  32. Li, Y.; Yang, L. Based on Delaunay Triangulation DEM of Terrain Model. Comput. Inf. Sci. 2009, 2, 137. [Google Scholar] [CrossRef]
  33. Mikula, J.; Kulich, M. Optimizing Mesh to Improve the Triangular Expansion Algorithm for Computing Visibility Regions. SN Comput. Sci. 2024, 5, 262. [Google Scholar] [CrossRef]
  34. Jiang, S.; Jiang, W. Robust Image Matching Constrained by Delaunay Triangulation. Acta Geod. Cartogr. Sin. 2019, 49, 322–333. [Google Scholar]
  35. Li, Y.; Dong, X.; Ding, Q.; Xiong, Y.; Liao, H.; Wang, T. Improved A* Algorithm for Power Line Inspection UAV Path Planning. Energies 2024, 17, 5364. [Google Scholar] [CrossRef]
  36. Li, Y.; Yang, F.; Zhang, X.; Yu, D.; Yang, X. Improved D* Lite Algorithm for Ship Route Planning. J. Mar. Sci. Eng. 2024, 12, 1554. [Google Scholar] [CrossRef]
  37. Yuan, M.-S.; Zhou, T.-L.; Chen, M. Improved Lazy Theta* Algorithm Based on Octree Map for Path Planning of UAV. Def. Technol. 2022, 23, 8–18. [Google Scholar] [CrossRef]
  38. Li, B.; Chen, B. An Adaptive Rapidly-Exploring Random Tree. IEEE/CAA J. Autom. Sinica 2022, 9, 283–294. [Google Scholar] [CrossRef]
  39. Suo, Y.; Chen, X.; Yue, J.; Yang, S.; Claramunt, C. An Improved Artificial Potential Field Method for Ship Path Planning Based on Artificial Potential Field—Mined Customary Navigation Routes. J. Mar. Sci. Eng. 2024, 12, 731. [Google Scholar] [CrossRef]
  40. Ramirez, M.; Selvaratnam, D.; Manzie, C. Kinodynamic Motion Planning via Branch-and-Cut Over Probabilistic Roadmaps. IEEE Robot. Autom. Lett. 2024, 9, 247–254. [Google Scholar] [CrossRef]
  41. Verginis, C.K.; Dimarogonas, D.V.; Kavraki, L.E. KDF: Kinodynamic Motion Planning via Geometric Sampling-Based Algorithms and Funnel Control. IEEE Trans. Robot. 2023, 39, 978–997. [Google Scholar] [CrossRef]
  42. Ji, L.; Sun, H.; Ma, X. NNPP: A Learning-Based Heuristic Model for Accelerating Optimal Path Planning on Uneven Terrain. Robot. Auton. Syst. 2025, 193, 105084. [Google Scholar] [CrossRef]
  43. Wang, K.; Zhou, Y.; Yang, M. Motion Planning for Off-Road Autonomous Driving Based on Human-Like Cognition and Weight Adaptation. J. Field Robot. 2024, 41, 401–422. [Google Scholar] [CrossRef]
  44. Yang, R.; Zhang, L. Rough-Terrain Path Planning Based on Deep Reinforcement Learning. Appl. Sci. 2025, 15, 6226. [Google Scholar] [CrossRef]
  45. Wang, Y.; Jiang, R.; Yang, M.; Xie, J.; Zhao, Y.; Li, F.; Lu, X. Spatiotemporal Characteristics and Driving Mechanisms of Land Use/Land Cover (LULC) Changes in the Jinghe River Basin, China. J. Arid Land 2024, 16, 91–109. [Google Scholar] [CrossRef]
  46. Yamashita, H.; Martin, J.E.; Tison, N.; Grunin, A.; Jayakumar, P.; Sugiyama, H. Modeling of Vehicle Mobility in Shallow Water with Data-Driven Hydrodynamics Model. J. Comput. Nonlinear Dynam. 2024, 19, 071010. [Google Scholar] [CrossRef]
  47. Zhang, D.; Zhang, Y.; Huang, L.; Yuan, B. Trafficability Analysis of Digital Cross-country Maneuver Zone. Geomat. Sci. Eng. 2017, 2, 44–48. [Google Scholar]
  48. Jiang, S.; Wang, C.; Zhang, C.; Bai, H.; Xu, L. Adaptive Estimation of Road Slope and Vehicle Mass of Fuel Cell Vehicle. eTransportation 2019, 2, 100023. [Google Scholar] [CrossRef]
  49. Arsanjani, J. Characterizing and Monitoring Global Landscapes Using GlobeLand30 Datasets: The First Decade of the Twenty-First Century. Int. J. Digit. Earth 2019, 12, 642–660. [Google Scholar] [CrossRef]
  50. Mikita, T.; Rybansky, M.; Krausková, D.; Dohnal, F.; Vystavěl, O.; Hollmannová, S. Mapping Forest Parameters to Model the Mobility of Terrain Vehicles. Forests 2024, 15, 1882. [Google Scholar] [CrossRef]
  51. Yan, X.; Du, W.; Shi, A. Research on Hierarchical Off-Road Path Planning Method Based on Trafficability Analysis. Fire Control Command Control 2022, 47, 153–158. [Google Scholar]
  52. Ben Salah, I.; Kramm, S.; Demonceaux, C.; Vasseur, P. Summarizing Large Scale 3D Mesh for Urban Navigation. Robot. Auton. Syst. 2022, 152, 104037. [Google Scholar] [CrossRef]
  53. Briones, J.L.; Chhabra, T. Navigation Mesh for Missing Persons Search: Student Mobile Application Competition: Smart Cities and Internet of Things Category. In Proceedings of the 23rd International Conference on Distributed Computing and Networking, Delhi, India, 4–7 January 2022; pp. 252–253. [Google Scholar]
  54. Yu, H.; Wang, T.; Li, H.; Zhang, Y.; Li, X.; Liu, B.; Wang, G. Delaunay Mesh Construction and Simplification with Feature Preserving Based on Minimal Volume Destruction. Appl. Sci. 2022, 12, 1831. [Google Scholar]
  55. Sun, X.; Shen, Y.; Zhang, H. A Stable Satellite Routing Algorithm Based on A-Star Algorithm in Dynamic Networks. J. Phys. Conf. Ser. 2024, 2807, 012026. [Google Scholar] [CrossRef]
  56. Martínez-Vargas, A.; Gómez-Avilés, J.A.; Cosío-León, M.A.; Andrade, Á.G. Explaining the Walking Through of a Team of Algorithms. Computers 2023, 56, 67–81. [Google Scholar] [CrossRef]
  57. Zheng, X.; Ma, M.; Zhong, Z.; Yang, A.; Chen, L.; Jing, N. Two-Stage Path Planning for Long-Distance Off-Road Path Planning Based on Terrain Data. ISPRS Int. J. Geo-Inf. 2024, 13, 184. [Google Scholar] [CrossRef]
  58. Hong, Z.; Sun, P.; Tong, X.; Pan, H.; Zhou, R.; Zhang, Y.; Han, Y.; Wang, J.; Yang, S.; Xu, L. Improved A-Star Algorithm for Long-Distance Off-Road Path Planning Using Terrain Data Map. ISPRS Int. J. Geo-Inf. 2021, 10, 785. [Google Scholar] [CrossRef]
  59. Zhang, X. Cross-Country Maneuver Path Network Analysis of the Computer Wargame. Geospat. Inf. 2017, 15, 14–16. [Google Scholar]
  60. Zhu, C.; Liu, L. Research on Improved A-Star Algorithm Based on Polygon Navigation Mesh Map. Softw. Guide 2019, 18, 17–21. [Google Scholar]
  61. Dietz, J.; Treydte, A.C.; Lippe, M. Exploring the Future of Kafue National Park, Zambia: Scenario-Based Land Use and Land Cover Modelling to Understand Drivers and Impacts of Deforestation. Land Use Policy 2023, 126, 106535. [Google Scholar] [CrossRef]
  62. Oktavia, D.; Pratiwi, S.D.; Kamaludin, N.N.; Widiawaty, M.A.; Dede, M. Dynamics of Land Use and Land Cover in Belitung Island, Indonesia. Heliyon 2024, 10, e3329. [Google Scholar] [CrossRef]
  63. Wang, X.; Sun, M.; Li, X.; Zhou, H.; Zhao, R. Grid A*: A Fast Path Planning Algorithm for Air-Ground Cooperative Response of Emergency Rescue in the Field. Nat. Remote Sens. Bull. 2024, 28, 767–780. [Google Scholar] [CrossRef]
  64. Alotaibi, A.; Chatwin, C.; Birch, P. Aerial Surveillance Leveraging Delaunay Triangulation and Multiple-UAV Imaging Systems. Appl. Syst. Innov. 2024, 7, 23. [Google Scholar] [CrossRef]
  65. Ebbens, M.; Parlier, H.; Vegter, G. Minimal Delaunay Triangulations of Hyperbolic Surfaces. Discrete Comput. Geom. 2023, 69, 568–592. [Google Scholar] [CrossRef]
  66. Cao, X.; Wu, K.; Geng, X.; Wang, Y. Indoor fire emergency evacuation path planning based on improved NavMesh algorithm. J. Intell. Fuzzy Syst. 2023, 45, 10757–10768. [Google Scholar] [CrossRef]
  67. Grant, D.; Garcia, J.; Raffe, W. Leaving the NavMesh: An Ablative Analysis of Deep Reinforcement Learning for Complex Navigation in 3D Virtual Environments. In Australasian Joint Conference on Artificial Intelligence; Lecture Notes in Computer Science (including subseries Lecture Notes in Artificial Intelligence and Lecture Notes in Bioinformatics); Springer: Singapore, 2024; Volume 14472, pp. 286–297. [Google Scholar]
Figure 1. Research workflow.
Figure 1. Research workflow.
Wevj 16 00382 g001
Figure 2. A 3 × 3 moving window in DEM.
Figure 2. A 3 × 3 moving window in DEM.
Wevj 16 00382 g002
Figure 3. Morphological process for passable area mapping.
Figure 3. Morphological process for passable area mapping.
Wevj 16 00382 g003
Figure 4. The Delaunay triangular NavMesh.
Figure 4. The Delaunay triangular NavMesh.
Wevj 16 00382 g004
Figure 5. The improved A* algorithm. (a) Selection of feature points within a triangle. (b) Improved A* Algorithm in a triangular Mesh. The blue line indicates the path generated by the improved A* algorithm. Figure 5a illustrates the relationship between the path planning distance calculated using the navigation mesh and the shortest Euclidean distance between two points. The edge through which a path enters a triangle is defined as the “input-edge,” and the edge through which it exits is defined as the “output-edge.” Each triangle of the Path triangle chain is allowed at most one input edge and one output edge. The cost (g-value) of a triangle is defined as the Euclidean distance between the midpoints of its input edge and output edge. The green triangle indicates the current position and the red triangle indicates the goal position.
Figure 5. The improved A* algorithm. (a) Selection of feature points within a triangle. (b) Improved A* Algorithm in a triangular Mesh. The blue line indicates the path generated by the improved A* algorithm. Figure 5a illustrates the relationship between the path planning distance calculated using the navigation mesh and the shortest Euclidean distance between two points. The edge through which a path enters a triangle is defined as the “input-edge,” and the edge through which it exits is defined as the “output-edge.” Each triangle of the Path triangle chain is allowed at most one input edge and one output edge. The cost (g-value) of a triangle is defined as the Euclidean distance between the midpoints of its input edge and output edge. The green triangle indicates the current position and the red triangle indicates the goal position.
Wevj 16 00382 g005
Figure 6. The figure illustrates how the funnel region evolves step by step. The funnel region is specified by the blue and green edges. (a) is the initial state of funnel optimization, and (bd) is the process of funnel optimization. The blue line is the left funnel and the green line is the right funnel.
Figure 6. The figure illustrates how the funnel region evolves step by step. The funnel region is specified by the blue and green edges. (a) is the initial state of funnel optimization, and (bd) is the process of funnel optimization. The blue line is the left funnel and the green line is the right funnel.
Wevj 16 00382 g006
Figure 7. The effectiveness of path planning improved by the A* and funnel algorithm. (a) is the improved A* algorithm and (b) is the improved A*+funnel optimization. The red point and the yellow point indicate the start and end points. The yellow path means the path planning by the improved A* algorithm. The purple path indicates the path improved by the funnel algorithm.
Figure 7. The effectiveness of path planning improved by the A* and funnel algorithm. (a) is the improved A* algorithm and (b) is the improved A*+funnel optimization. The red point and the yellow point indicate the start and end points. The yellow path means the path planning by the improved A* algorithm. The purple path indicates the path improved by the funnel algorithm.
Wevj 16 00382 g007
Figure 8. Land cover and terrain for the study areas.
Figure 8. Land cover and terrain for the study areas.
Wevj 16 00382 g008
Figure 9. Delaunay triangular NavMesh and Path planning.
Figure 9. Delaunay triangular NavMesh and Path planning.
Wevj 16 00382 g009
Figure 10. Off-road path planning analyses. Red dashed line is the path planning results and the different colors indicates the Dealunay triangular Navmesh.
Figure 10. Off-road path planning analyses. Red dashed line is the path planning results and the different colors indicates the Dealunay triangular Navmesh.
Wevj 16 00382 g010
Figure 11. Effect of the morphological procedure in passable area mapping.
Figure 11. Effect of the morphological procedure in passable area mapping.
Wevj 16 00382 g011
Figure 12. The funnel optimization and the improved A* comparison. The red dashed line indicates the path planning results.
Figure 12. The funnel optimization and the improved A* comparison. The red dashed line indicates the path planning results.
Wevj 16 00382 g012
Figure 13. Comparative results of different data models. (a) Grid; (b) Delaunay NavMesh.
Figure 13. Comparative results of different data models. (a) Grid; (b) Delaunay NavMesh.
Wevj 16 00382 g013
Figure 14. Comparative results in different algorithms in site (a,b).
Figure 14. Comparative results in different algorithms in site (a,b).
Wevj 16 00382 g014
Table 1. Land cover mobility.
Table 1. Land cover mobility.
IDTypes r i
1Crop0.6
2Forest0.5
3Grassland0.7
4Sparse shrubland0.4
5Wetland0.1
6River0.0
7Lake0.0
8Sparse residential area1.0
9Dense residential area0.0
10Artificial hard surface1.0
11Bare soil0.9
12Gobi0.9
13Snow field0.6
Table 2. Complexity analysis.
Table 2. Complexity analysis.
AlgorithmsImproved A* Improved A* + Funnel Optimization
Memory complexityMax O ( V + E ) O V + E + m O ( V + E )
Time complexityMax O ( V + E log V )   O ( ( V + E ) log V + k ) O ( V + E log V )
Table 3. Experimental design.
Table 3. Experimental design.
ExperimentsMethodsGoal
Data Models8-directional gridExamine the effectiveness of the Delaunay triangular NavMesh with A* algorithm by searching distance and time
Hexagonal grid
Delaunay triangular
Path planning algorithmsDijkstra algorithmExamine the effectiveness of improved A* + funnel optimization under Delaunay triangular mesh by searching distance and time
Improved A* algorithm
Improved A* + Funnel optimization algorithm
Table 4. The experimental condition.
Table 4. The experimental condition.
Configuration and DatabaseVersion
Operation systemWindows 11
CPUIntel i7
GPUNVIDIA 2070
Memory32G
Database management toolsNavicat Premium
Hard disk1T SSD
Program language and platformC++/QT Creator
Table 5. Passable and obstacle area analysis.
Table 5. Passable and obstacle area analysis.
ClassificationGeographic FactorsSite A (%)Site B (%)Site C (%)Site D (%)
Land coverWater4.30.434.631.7
Grassland1.70.70.91.2
Built-up16.62.927.829.5
Forest16.561.228.30.3
Wetland0.80.00.00.0
Crop60.134.78.237.2
Slope>30°0.450.8503.04
≤30°99.5599.1510096.96
MobilityObstacle32.472.357.858.7
Passable67.627.642.241.3
Table 6. Performance comparison.
Table 6. Performance comparison.
Site8-Directional GridHexagonal GridDelaunay NavMesh
Path (km)Running (ms)Path (km)Running (ms)Path (km)Running (ms)
A34.3628,40031.3472,65629.65170
B35.6298,10528.6766,79626.61153
C12.9425410.433566.655
D8.859175.662574.177
Table 7. Grid unit analysis of the off-road environment representation.
Table 7. Grid unit analysis of the off-road environment representation.
IDOff-Road Environment RepresentationSite ASite BSite CSite D
18-directional grid1,784,951715,4761,204,382405,307
2Hexagonal grid49,580903733,5407462
3Delaunay triangular NavMesh10,523512073183905
Table 8. Ablation experiment results.
Table 8. Ablation experiment results.
SiteImproved A*Improved A* + Funnel Optimization
Path (km)Running (ms)Path (km)Running (ms)
A29.6517017.76172
B26.6115313.24158
C6.6553.925
D4.1772.437
Table 9. Comparative experiment results in different data models.
Table 9. Comparative experiment results in different data models.
IndicatorsPath (km)Running (ms)
Grid2.613430
Delaunay NavMesh2.745
Table 10. Comparative experiment results of different path planning algorithms.
Table 10. Comparative experiment results of different path planning algorithms.
MethodsPath (km)Running (ms)
Dijkstra2.745
Improved A*2.741
Table 11. Comparative experiment results of path planning algorithms.
Table 11. Comparative experiment results of path planning algorithms.
SiteDijkstraImproved A* + Funnel Optimization
Path (km)Running (ms)Path (km)Running (ms)
A4.8582.952
B2.7451.781
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.

Share and Cite

MDPI and ACS Style

Tian, T.; Wu, H.; Wei, H.; Wu, F.; Shang, J. An Efficient Path Planning Algorithm Based on Delaunay Triangular NavMesh for Off-Road Vehicle Navigation. World Electr. Veh. J. 2025, 16, 382. https://doi.org/10.3390/wevj16070382

AMA Style

Tian T, Wu H, Wei H, Wu F, Shang J. An Efficient Path Planning Algorithm Based on Delaunay Triangular NavMesh for Off-Road Vehicle Navigation. World Electric Vehicle Journal. 2025; 16(7):382. https://doi.org/10.3390/wevj16070382

Chicago/Turabian Style

Tian, Ting, Huijing Wu, Haitao Wei, Fang Wu, and Jiandong Shang. 2025. "An Efficient Path Planning Algorithm Based on Delaunay Triangular NavMesh for Off-Road Vehicle Navigation" World Electric Vehicle Journal 16, no. 7: 382. https://doi.org/10.3390/wevj16070382

APA Style

Tian, T., Wu, H., Wei, H., Wu, F., & Shang, J. (2025). An Efficient Path Planning Algorithm Based on Delaunay Triangular NavMesh for Off-Road Vehicle Navigation. World Electric Vehicle Journal, 16(7), 382. https://doi.org/10.3390/wevj16070382

Article Metrics

Back to TopTop