Next Article in Journal
Electricity Cost Forecasting in the South African Mining Industry: A Gap Analysis
Next Article in Special Issue
Real Time Mining—A Review of Developments Within the Last Decade
Previous Article in Journal / Special Issue
Slope Stability Monitoring Methods and Technologies for Open-Pit Mining: A Systematic Review
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment

by
Abdurauf Abdukodirov
* and
Jörg Benndorf
Department of Mine Surveying and Geodesy, TU Bergakademie Freiberg, 09599 Freiberg, Germany
*
Author to whom correspondence should be addressed.
Mining 2025, 5(2), 33; https://doi.org/10.3390/mining5020033
Submission received: 31 March 2025 / Revised: 18 May 2025 / Accepted: 19 May 2025 / Published: 21 May 2025
(This article belongs to the Special Issue Mine Automation and New Technologies)

Abstract

The navigation of Unmanned Ground Vehicles (UGVs) in underground mining environments is critical for enhancing operational safety, efficiency, and automation in hazardous and constrained conditions. This paper presents a thorough review of path-planning algorithms employed for the navigation of UGVs in underground mines. It outlines the key components and requirements that are essential for an effective path planning framework, including sensors and the Robot Operating System (ROS). This review examines both global and local path-planning techniques, encompassing traditional graph-based methods, sampling-based approaches, nature-inspired algorithms, and reinforcement learning strategies. Through the analysis of the extant literature on the subject, this study highlights the strengths of the employed techniques, the application scenarios, the testing environments, and the optimization strategies. The most favorable and relevant algorithms, including A*, Rapidly-exploring Random Tree (RRT*), Dijkstra’s, Ant Colony Optimization (ACO), were identified. This paper acknowledges a significant limitation: the over-reliance on simulation testing for path-planning algorithms and the computational difficulties in implementing some of them in real mining conditions. It concludes by emphasizing the necessity for full-scale research on path planning in real mining conditions.

1. Introduction

In the age of technological advancement, automation has permeated almost all industries, including underground mining [1]. The high risk and challenges inherent in traditional mining have precipitated the introduction of automation measures. The elevated probability of injury in such a harsh environment poses a significant threat to workers’ lives [2]. In addition, survey accuracy is affected by worker fatigue, which impacts measurement accuracy and increases survey time.
Underground automation heavily depends on efficient and reliable navigation systems, serving as a key enabler for autonomous operations in complex and hazardous environments [3]. Autonomous navigation is applicable in various environments, including outdoor, indoor, underground mines, and even underwater [4]. Beyond improving precision and reliability, effective navigation reduces the risks associated with manual operations, making it a fundamental component of underground automation.
Compared to other environments, navigation in underground mining presents unique challenges, including the unpredictable nature of underground terrain, such as irregular surfaces, narrow passages, and dynamic obstacles, as listed in Table 1, requiring robust navigation to ensure safety and efficiency [5]. Additionally, the absence of GPS signals necessitates advanced techniques like Simultaneous Localization and Mapping (SLAM) and Dead-reckoning methods [6,7].
Navigation in mining is crucial for enabling autonomous vehicles and systems to perform various tasks efficiently and safely in challenging underground environments. The following are examples:
  • For surveying and mapping. Autonomous vehicles equipped with LiDAR and SLAM systems navigate the mine to generate 3D maps for planning and operational purposes [8];
  • Transportation. Autonomous haul trucks navigate predefined routes to transport ore, minerals, or waste material between loading and dumping points in underground mines [9];
  • Drilling and Blasting Operations. Navigation systems guide autonomous drilling machines to precise coordinates within the mine for efficient drilling [10];
  • Inspection and Maintenance. Autonomous robots navigate mine tunnels to detect structural integrity issues and gas leaks [11];
  • Search and Rescue Operations (SARs). Navigation enables unmanned vehicles to explore hazardous or collapsed mine areas where human entry is unsafe [12].
Underground navigation in autonomous vehicle applications involves several key steps to ensure safe and efficient operation, as outlined below:
  • Localization, where the vehicle determines its position and orientation within its environment using techniques like SLAM or dead-reckoning;
  • Perception, which involves sensing and mapping the surroundings using Light Detection and Ranging (LiDAR), cameras, or radar to detect obstacles and terrain features;
  • Path planning, which determines the optimal route to reach a destination while avoiding obstacles and adapting to environmental changes;
  • Motion control executes the planned path by steering, accelerating, or braking, ensuring precise and smooth movement.
These steps are supported by sensor integration and real-time decision-making to handle dynamic conditions effectively [13].
In the context of autonomous underground navigation, a variety of platforms assume significant roles in enhancing efficiency, safety, and productivity. Unmanned Ground Vehicles (UGVs) and Unmanned Aerial Vehicles (UAVs) are among the key technologies driving automation in underground mining operations. Both of them are essential for surveying, exploration, inspection, and SAR tasks, where human intervention is either constrained or infeasible. UGVs with high power and payload capacity have advantages in long-duration missions and transportation, but they are limited in mobility. UAVs, on the other hand, are good at quick inspections and can reach areas that are difficult to access [14]. Beyond unmanned vehicles, many mining machines, including Load-Haul-Dump (LHD) machines, are being redesigned for full automation, further enhancing the efficiency and safety of underground operations [15].
As one of the crucial components of navigation, path planning might be modified or enhanced with optimization strategies to achieve efficient and accurate navigation in the underground mining environment. While extensive research has been conducted on surface-level path planning [16], underground navigation remains a critical and evolving research area due to its unique environmental challenges and constraints. This paper provides a comprehensive review of recent advancements in underground UGV path planning. The structure of this paper is as follows:
  • Section 2 (Requirement Analysis and Methodological Basis for Path Planning in Underground Mining Environments) outlines the key requirements and methodology for successful navigation and path planning of UGVs in underground mining environments;
  • Section 3 (Materials) discusses the essential components for UGV operation, including environmental sensors and operational framework;
  • Section 4 (Path Planning Framework) presents a general overview of path planning frameworks, algorithms, and optimization strategies, highlighting their respective advantages and limitations;
  • Section 5 (Related Works on Underground Mining Path Planning with UGVs) reviews related research, identifies emerging trends, and examines methodological improvements in path planning algorithms, as well as existing research gaps;
  • Section 6 (Discussion) analyzes the results of the reviewed algorithms, highlights the main limitations of this study, and proposes directions for future research based on these findings;
  • Finally, Section 7 (Conclusion) provides a summary of this research.
The analysis aims to offer insights into current limitations and identify opportunities for future research and development in optimizing autonomous navigation for underground mining applications.

2. Requirement Analysis and Methodological Basis for Path Planning in Underground Mining Environments

The requirements outlined in this section serve as a key consideration for navigation and the evaluation of existing path planning research in underground mining using UGVs. General requirements for underground navigation are as follows:
  • UGVs must operate autonomously in GPS-denied environments;
  • Performing effectively in low-light, high-dust, and uneven terrain conditions with the help of advanced sensors such as LiDAR, cameras, radars, Inertial Measurement Unit (IMU), and motor encoders for accurate environmental mapping and obstacle detection;
  • UGVs must be compatible with the Robot Operating System (ROS) framework, enabling modular communication, multi-sensor integration, and scalability;
  • UGVs must reliably detect and avoid both static and dynamic obstacles, generating accurate and efficient paths in real-time while incorporating recovery behaviors to handle unexpected environmental changes;
  • Adaptability to environmental complexity, such as dynamic obstacles and sudden changes in tunnel structures, is necessary for reliable underground navigation;
  • Energy-efficient operation is also essential to prolong the operational lifespan of UGVs in an underground mine [17].
Path planning requirements are primarily determined by the algorithms employed. The selection of an appropriate algorithm is based on an analysis of environmental and vehicle parameters. To evaluate path planning algorithms and review existing research, the key requirements and evaluation criteria for planned paths are summarized in Table 2.
Considering the above-mentioned requirements, this review paper aims to address the following key questions:
  • What types of sensors and an operational framework are used in underground mining navigation?
  • How can alternative algorithms be compared and classified based on their strengths and application scenarios?
  • Which path planning algorithms are most frequently applied in underground mining scenarios?
  • What optimization techniques are commonly used to meet the requirements for successful path planning?
  • What kinds of experimental methods are employed in the literature to assess how well these techniques reflect real-world mining conditions?
To address these questions, relevant studies were selected from major academic databases based on relevance to underground mine UGV path planning. Algorithms were categorized by type (graph-based, sampling-based, nature-inspired, etc.), and their implementation details, optimization strategies, testing environments, and limitations were comparatively analyzed.
This analysis enables the identification of research gaps between theoretical models and practical deployment challenges in path planning for underground mining UGVs.

3. Materials

3.1. Sensors to Perceive the Environment

Sensors are critical components in underground mining applications, enabling UGVs to perceive their surroundings, detect obstacles, and generate optimal paths in challenging environments. Considering the different operating conditions in underground mines, the selection of suitable sensors depends on the specific navigation requirements of the UGV. The following sensors are frequently employed for navigation purposes in mining operations:
  • LiDAR (Light Detection and Ranging);
  • Depth Camera;
  • Radar;
  • IMUs (Inertial Measurement Units);
  • Motor encoders.
LiDAR is a widely utilized technique for 3D mapping and obstacle detection in which precise point clouds of the surroundings are generated. Laser scanners, on the other hand, operate similarly but offer high-resolution scans for detailed surface analysis. Depth cameras capture depth information to identify variations in terrain and assist in real-time object detection. Radar is effective in low-visibility conditions such as dust and fog, using radio waves to detect obstacles beyond the limitations of optical sensors. IMUs enhance localization accuracy by tracking motion changes through accelerometers and gyroscopes. In addition, motor encoders, which measure wheel rotation, provide odometry data to estimate the vehicle’s displacement and support dead reckoning-based navigation [19]. Each sensor has its strengths and weaknesses in different applications, depending on the environment and accuracy required, as described in Table 3.
For robust underground mine path planning, sensor fusion (combining multiple sensors) is often necessary. A typical UGV utilizes LiDAR or scanners, along with IMUs and motor encoders. Additionally, radar complements LiDAR in harsh conditions, while depth cameras are used for object recognition and enhanced depth sensing [26].
Although sensor types do not directly determine the optimal path planning algorithm, there is an indirect relationship between sensor accuracy and planning performance. Inaccurate or sparse sensor data can lead to uncertain obstacle maps, limiting the planner’s ability to generate smooth or efficient paths, particularly in constrained underground environments with narrow corridors and sharp turns. Conversely, more accurate sensing allows planners to exploit available space more effectively, potentially improving path smoothness and reducing the need for overly conservative maneuvers.
In underground navigation, the ROS (Robot Operating System) plays a key role as a middleware, facilitating communication between sensors, data acquisition, and processing in UGVs. It provides a structured framework for integrating multiple sensors, ensuring synchronized data flow for perception, localization, and navigation.

3.2. ROS as Main Operating System

ROS is a flexible framework used primarily in robotics for developing robot software. Despite its name, ROS is not a traditional operating system but rather a middleware framework that provides tools, libraries, and conventions for creating complex and robust robot applications [27]. There are several advantages that ROS can provide, including the following:
  • ROS is open source, so it can be augmented by developers;
  • It is a modular and flexible framework that allows researchers to customize and adapt it for a wide range of applications;
  • Cross-platform compatibility and hardware-agnostic design, which supports diverse robotic systems, from drones and robotic arms to autonomous vehicles;
  • Robust built-in libraries for computer vision, motion planning, and navigation;
  • Simulation tools, such as Gazebo and RViz, allow researchers to efficiently prototype, test, and refine robots;
  • Integration with AI and machine learning technologies extends its usefulness in creating intelligent and autonomous systems [28].
ROS has evolved through two major generations. ROS 1 (2007) laid the foundation for robotics development with modularity and ease of use, being widely adopted for research and non-critical applications. Key versions include ROS Kinetic (2016) and ROS Melodic (2018). However, it faced limitations in real-time performance and scalability. On the other hand, ROS 2 (2017) addressed these issues with parallel processing, secure communication, and real-time support, making it ideal for industrial use. Built on a Data Distribution Service (DDS), ROS 2 ensures robust communication and scalability, with key releases like Foxy (2020) and Humble (2022). Although ROS 1 is still in use, the focus is gradually shifting to ROS 2 as the emerging industry standard [29].
In ROS, a node is a fundamental building block that represents a single process performing a specific task, such as controlling a sensor or executing a robot’s movement logic. Nodes communicate with each other using topics, which are named channels for message passing. A node can publish messages to a topic or subscribe to a topic to receive messages, enabling modular and scalable communication between different parts of a robot’s system. For instance, a camera node might publish image data to a topic, while another node subscribes to process that data. The ROS file system provides a structured way to organize resources and facilitate development within the ROS framework. It is designed to manage the various components of a robotics project, including nodes, packages, messages, and configurations.
The key components of ROS file systems are as follows:
  • Packages are the fundamental unit of software organization in ROS. They contain all the necessary files for a specific functionality, such as nodes, libraries, configurations, and launch files. Each package is self-contained, enabling easy reuse and sharing;
  • Metapackages are collections of related packages grouped together under a common purpose, such as ros_base or desktop_full;
  • Workspaces are directories where ROS packages are developed and built.
Each package has a standardized directory structure, as outlined below:
  • src/: Source code for nodes and other scripts;
  • launch/: Launch files to start nodes and set parameters;
  • config/: Robot description configuration files to manage its behavior;
  • msg/ and srv/: Definitions for custom message and service types;
  • CMakeLists.txt and package.xml: Build system and package metadata files.
ROS defines specific file types for communication between two nodes, as shown in Figure 1:
  • Messages: Define data structures for node-to-node communication;
  • Services: Specify request-response structures for synchronous interactions;
  • Actions: Provide a framework for long-running tasks with feedback.
Figure 1. ROS communication types between two nodes.
Figure 1. ROS communication types between two nodes.
Mining 05 00033 g001
The ROS file system ensures consistency, modularity, and ease of collaboration. By organizing code and resources into packages, it simplifies sharing, testing, and scaling across projects [30].
The operating system requirements for ROS vary depending on the generation. ROS 1 is primarily designed for Ubuntu Linux, as it leverages Ubuntu’s package management system and development ecosystem. In contrast, ROS 2 offers broader compatibility and can be installed on multiple operating systems, including Ubuntu and Windows.
ROS is also ideal for underground and mining applications due to its modular and flexible architecture, enabling customization for navigation, mapping, and inspection in challenging environments. It enables UGVs to perform essential tasks, including SLAM, path planning, and visualization. In addition, it supports multi-sensor integration, such as LiDAR, radar, and cameras, for reliable operation in low-light and dusty conditions. ROS facilitates real-time data processing, remote operation, and multi-robot coordination, enhancing safety and efficiency. Numerous completed and ongoing ROS-based projects focus on automating mining operations and conducting rescue missions in mining disasters. Take, as an example, the successful completion of the DARPA Subterranean Challenge in 2021 [31], which was a robotics competition aimed at pushing the boundaries of autonomous navigation and exploration in complex underground environments. The challenge sought innovative approaches to quickly and effectively map, navigate, and search through difficult subterranean environments such as caves, tunnels, and urban underground structures.

4. Path Planning Framework

Path planning is a fundamental component of autonomous UGV navigation, responsible for determining an optimal or feasible path from a starting position to a destination while avoiding obstacles and considering environmental constraints. Developing a path planning framework is inherently complex, as it encompasses environment representation, localization and perception, path planning algorithms, obstacle avoidance, and motion control. This framework ensures that UGVs can safely and efficiently navigate underground environments, where GPS is unavailable and traditional navigation methods are ineffective [32].
The environment representation plays a crucial role in path planning, as it defines how the UGV perceives and interacts with its surroundings. The various representation methods include grid-based maps, topological maps, point cloud maps, and hybrid maps, each of which offers different advantages depending on the navigation requirements and computational constraints [33]. For localization in a known environment, sensor-based techniques such as Monte Carlo Localization (MCL) and feature-based localization are commonly employed [34]. However, in unknown environments, SLAM is required to build a map while simultaneously determining the UGV’s position. Once the UGV has identified its start or current position, it can execute path planning algorithms to navigate efficiently toward the target location. After that, motion control manages the vehicle’s movement.
Path planning algorithms can be broadly classified into global and local planning approaches, each serving a specific role in navigation, as described in Figure 2.

4.1. Global Path Planning Algorithms

Global path planning operates with a pre-existing map and computes a path before execution. These algorithms are suitable for structured environments where a detailed representation of the terrain is available. The global planner gives information about obstacles, the positions of the robot and targets, as well as the environment represented in the map. It creates a global path to reach the target position within this environment. Based on how they model the environment and search strategies for an optimal path, global path planning algorithms are divided into Graph-based, Sampling-based, Nature-Inspired, Reinforcement learning (RL)-based, and Hybrid algorithms [35].
1.
Graph-Based algorithms. These algorithms model the environment as a graph and find the shortest path using various search techniques and algorithms, including the following:
  • Dijkstra’s algorithm. It is an exact algorithm designed to determine the minimum-cost path from a source vertex to all other vertices in a directed graph. The algorithm operates by iteratively selecting the closest unvisited node, updating the shortest known distances to its neighboring vertices, and continuing this process until the destination node is reached or all reachable nodes have been explored. Since Dijkstra’s algorithm follows a breadth-first search-like approach, it systematically expands the search from the starting node outward. However, this leads to relatively high time and space complexity, especially in large graphs, as it requires maintaining and updating distance information for multiple vertices throughout the execution [36];
  • A and A* algorithms. The algorithm, often linked to Dijkstra’s approach, identifies the shortest path between nodes in a weighted graph by evaluating all possible routes based on cumulative cost. However, it lacks heuristic guidance, which can make it inefficient in larger environments. The A* algorithm improves upon this by integrating a heuristic function with cost-based search, allowing it to prioritize more promising paths. It evaluates the total estimated cost from the start node and estimates the remaining cost to the goal [37];
  • D* and D* Lite. The D* algorithm is an incremental path-planning method designed for dynamic environments, where obstacles or terrain conditions may change over time. It initially computes an optimal path from the start position to the goal under the assumption of a static environment. When the robot moves and encounters updated information, D* efficiently recalculates only the affected portions of the path instead of recomputing from scratch, making it suitable for real-time applications in navigation and robotics. D* Lite, a simplified version of D*, follows a similar approach but computes paths in reverse, from the goal to the start. This backward search allows for efficient path updates when obstacles appear or disappear. By maintaining a cost-efficient priority queue and selectively updating affected nodes, D* Lite reduces computational complexity while pursuing a near-optimal solution [38].
2.
Sampling-Based Algorithms. These algorithms generate a path by randomly sampling points in the environment. Some important sample algorithms are as follows:
  • Rapidly-exploring Random Tree (RRT). It is designed to efficiently navigate complex, high-dimensional spaces. It incrementally builds a tree by randomly sampling points within the search space and connecting them to the nearest existing node, effectively exploring feasible paths in environments with numerous obstacles. While RRT is proficient at quickly finding a viable path, it doesn’t guarantee optimality [39]. To mitigate this limitation, RRT* was developed as an improvement over the original algorithm. It aims to enhance path quality through iterative refinement, where the tree structure is rewired to explore shorter or more efficient paths as new samples are added. While RRT* improves performance compared to RRT, it does not guarantee exact optimality. Rather, it is asymptotically optimal, meaning it can approach an optimal solution given sufficient sampling and time under certain conditions [40];
  • Probabilistic Roadmap (PRM). This method efficiently navigates high-dimensional spaces. It works in two phases: first, the construction phase generates random collision-free nodes and connects them to form a roadmap; and, second, the query phase links the starting and goal positions to the roadmap, using graph search algorithms like Dijkstra’s to determine the optimal path. PRM is particularly effective in static environments where multiple queries are needed, as the roadmap can be reused, reducing computational complexity [41].
3.
Nature-Inspired Algorithms. These algorithms are modeled after biological processes and use mathematical optimization techniques to find the best path. Some examples of these algorithms are as follows:
  • Genetic Algorithm (GA). It is an evolutionary optimization technique inspired by the principles of natural selection. It begins with a randomly generated population of candidate solutions, which evolve over multiple iterations through selection, crossover, and mutation. A fitness function evaluates each candidate, so a parent selection operator favors the best solutions for reproduction. The algorithm applies crossover to combine parent solutions, thus generating children, and then it applies mutation to introduce small variations to these children, generating the mutated children that will become the parents of the next generation. This iterative framework introduces diversity to the search space, continuing until a stopping criterion is reached. GA is widely used in complex optimization problems where traditional methods struggle with large or nonlinear search spaces [42];
  • Particle Swarm Optimization (PSO). An algorithm that is a population-based optimization technique inspired by the collective movement of birds and fish. It initializes a group of candidate solutions, called particles, which explore the search space by updating their positions based on both their individual best-known solution and the globally best-known solution within the swarm. This dynamic adjustment allows particles to converge toward near-optimal solutions over multiple iterations. PSO is particularly useful for solving high-dimensional and nonlinear optimization problems due to its simplicity and efficiency in navigating complex search spaces [43];
  • Ant Colony Optimization (ACO). It mimics the foraging behavior of ants to find near-optimal paths in a graph. Artificial ants explore potential routes, depositing virtual pheromones that influence the decisions of subsequent ants. Pheromones evaporate at a certain rate, but over successive iterations, paths with stronger pheromone trails will outpace evaporation and become more favorable, leading the swarm toward convergence and efficient solutions [44].
4.
Reinforcement learning (RL)-based algorithms. RL-based methods learn optimal paths through trial-and-error interactions with the environment, refining their policies over time based on cumulative rewards, consisting of an approach that does not require a predefined model [45]. Sample algorithms are as follows:
  • Q-Learning algorithm. It builds a Q-table where each state-action pair is assigned a value, which is then updated iteratively using the Bellman equation. By maximizing cumulative rewards, the algorithm ensures efficient obstacle avoidance and goal-reaching, making it particularly useful in dynamic or uncertain environments [46];
  • Deep Q-Networks (DQN). It employs a Deep Neural Network (DNN) to approximate Q-values for state-action pairs, enabling the robot to learn an optimal policy through continuous interaction with the environment. This approach is particularly beneficial in dynamic, uncertain, or partially observable settings where traditional methods struggle. Additionally, experience replay and target networks stabilize training, mitigating the overestimation of Q-values and improving convergence [47].
5.
Hybrid Algorithms. These algorithms combine two or more of the mentioned approaches to improve efficiency and robustness. Examples of hybrid algorithms used for path planning of Autonomous Mobile Robots are the A-RRT* and D-lite with RRT* [48].

4.2. Local Path Planning Algorithms

Local path planning algorithms are crucial for UGVs, especially in dynamic environments. The global path planner determines the overall trajectory for vehicle motion but lacks efficient real-time obstacle avoidance. Therefore, direct execution of the global path often results in suboptimal performance. Additionally, as the search space expands, the computational time required for global path planning algorithms increases significantly [49]. Local planning adapts a planned path based on real-time data, ensuring that the robot can navigate effectively while considering its physical limitations and avoiding obstacles. They work within the framework established by the global planner but have a more dynamic role that involves constant adjustments rather than a strictly defined trajectory generation. Among the common local path planning algorithms, the following can be mentioned:
  • Dynamic Window Approach (DWA). It is a real-time motion planning algorithm that ensures both collision avoidance and adherence to dynamic constraints. It evaluates a range of possible velocities within a short time horizon and selects the trajectory that optimally balances safety, efficiency, and goal direction. By considering the kinematic limitations of the robot and environmental obstacles, DWA enables smooth and reactive navigation in dynamic environments [50];
  • Artificial Potential Field (APF). In this approach, the robot is influenced by an artificial force field composed of attractive forces, which pull it toward the goal, and repulsive forces, which push it away from obstacles. The robot navigates by following the resultant force vector, aiming for a collision-free path to reach the target. While APF is computationally efficient and straightforward to implement, it can encounter issues such as trapping in local minima, where the robot becomes trapped in a position that is not the goal. Various modifications have been proposed to address these limitations and enhance the effectiveness of this method [51];
  • Vector Field Histogram (VFH). This approach constructs a two-dimensional Cartesian histogram grid using range sensor data. This grid is continuously updated to reflect the environment of the robot. The algorithm reduces this grid to a one-dimensional polar histogram centered on the current position of the robot, where each sector represents the obstacle density in a specific direction. By analyzing these sectors, VFH identifies obstacle-free paths and determines the most suitable steering direction, allowing the robot to navigate toward its target while avoiding collisions. This method effectively balances reactive obstacle avoidance with goal-oriented navigation [52];
  • Model Predictive Control (MPC). It is an advanced control strategy that utilizes a dynamic model system to predict and optimize its future behavior over a specified time horizon. In the context of mobile robot local path planning, MPC involves formulating an optimization problem that accounts for the kinematic constraints of the robot, environmental obstacles, and a predefined cost function. At each time step, the controller solves this optimization problem to determine the optimal control inputs, resulting in a trajectory that guides the robot toward its target while avoiding collisions. This process is repeated in a receding horizon manner, allowing the robot to adapt its path in real-time to dynamic changes in the environment. MPC’s ability to handle multivariable control problems and incorporate constraints makes it particularly effective for complex path planning tasks in uncertain environments [53];
  • Timed Elastic Band (TEB). This algorithm optimizes the trajectory of the robot by considering both spatial and temporal constraints. Starting with an initial path, TEB refines it into a time-parametrized trajectory by adjusting the positions and velocities of intermediate points, ensuring adherence to the robot’s kinematic constraints and obstacle avoidance. This optimization process allows the robot to navigate efficiently in dynamic environments, responding adaptively to changes while maintaining smooth and feasible motion [54].
Several algorithms, such as ACO, RRT*, A*, and RL, can be utilized for both global and local path planning after appropriate optimization [55].
However, despite the existence of a wide range of path-planning algorithms, their practical implementation often reveals specific limitations in meeting all operational requirements. These limitations are dependent on the testing environment and the characteristics of the UGV. As a result, many algorithms require optimization or fusion with other approaches to enhance efficiency, adaptability, and robustness. Table 4 presents a detailed comparison of the advantages and limitations of each algorithm.
Global path-planning algorithms differ significantly in efficiency and adaptability based on the environment and constraints. Graph-based methods, such as A* and Dijkstra, work well in structured environments but are computationally expensive, while sampling-based approaches, like RRT* and PRM, offer better scalability in high-dimensional spaces but may require additional smoothing. Nature-Inspired Algorithms, like GA and ACO, are useful for solving complex optimization problems, but may suffer from slower convergence. RL techniques, including DQN, provide adaptability in dynamic and unknown environments, but require computational resources.
Local path planning algorithms also offer common and distinct advantages and drawbacks. DWA, APF, and VFH are prone to local minima; however, they are good at real-time obstacle avoidance. Moreover, DWA, MPC, and TEB ensure smooth and optimized paths, but MPC and TEB demand high computational power. TEB is excellent for dynamic trajectory adjustments but requires fine-tuned parameters. In the field of practical robotics, a universal algorithm that is best suited for all applications is not available. Consequently, there is a preference for hybrid methods that integrate multiple classical or RL-based approaches, particularly in the context of efficient path planning. Alternatively, the existing algorithms may be modified through the implementation of optimization strategies [56].
In terms of using path planning algorithms in underground mines, the evaluation criteria mentioned in Section 2. The Requirement Analysis and Methodological Basis for Path Planning in Underground Mining Environments will be selected based on key operational and environmental requirements, including the optimality of the path, computational demand, robustness, and obstacle avoidance. Additionally, the variability in excavation methods influences the requirements for these algorithms.

4.3. Optimization Strategies in Underground Path Planning

To improve path quality, safety, and computational efficiency in underground environments, numerous optimization strategies are employed within path planning algorithms. These techniques address specific issues such as jagged trajectories, redundant nodes, slow convergence, or collision risks. The strategies reviewed in the literature can be broadly categorized into several functional groups:
  • Curve and Spline-Based Path Smoothing [57]. Path smoothing techniques, such as Gaussian filtering, B-spline curves, and Bessel curves, are widely used to convert discrete waypoints into smooth, continuous trajectories, which are essential for navigating narrow underground tunnels. As one of the common smoothing technique, Gaussian filtering applies a weighted average to a set of neighboring points using a Gaussian kernel [58]. The filtered position P i is computed as shown in Equation (1):
    P i = j = k k w j P i + j  
    where P i is the filtered waypoint, w j are the weights from the Gaussian kernel, and 2k + 1 is the size of the window. This method reduces noise and sharp transitions in the path, making it more navigable for UGVs in confined underground environments;
  • Search Space or Node optimization. These techniques aim to reduce computational load and improve planning efficiency by refining how nodes are generated or selected. These strategies include key node selection, adaptive step size expansion, and articulation-angle-based expansion. Each method seeks to avoid oversampling in open areas and prioritize exploration in more constrained regions. One example is adaptive step size expansion [59], which adjusts the growth rate of the tree based on environmental feedback or remaining distance to the goal. A common form to calculate the step size for node expansion is shown in Equation (2):
    δ step = min δ max , α d goal
    where δ step is the current expansion step size, δ max is a predefined upper limit, α is a scaling factor, and d goal is the Euclidean distance to the goal. This approach helps maintain planning accuracy near the target while speeding up search in free space;
  • Evolutionary optimization. This category encompasses bio-inspired and probabilistic methods, such as the pheromone updating model, entropy increase strategy, and ant retreat strategy, which enhance path planning by optimizing path quality and computational efficiency.
A representative mechanism is the pheromone updating rule used in ACO [60]. After each iteration, the pheromone levels τ i j on the path between nodes i and j are updated to reflect the quality of the solutions found. The update equation is calculated as Equation (3):
τ i j 1 ρ τ i j + Δ τ i j
where:
  • τ i j is the pheromone value on edge (i, j);
  • ρ is the evaporation rate (0 < ρ < 1);
  • Δ τ i j is the amount of pheromone deposited, often defined by Equation (4):
    Δ τ i j = Q L ,                   i f   e d g e   i , j   i s   i n   t h e   b e s t   p a t h 0 ,                         o t h e r w i s e
Here, Q is a constant, and L is the length of the path. This mechanism reinforces efficient paths while allowing less optimal ones to fade, balancing exploration and exploitation in the search process.

5. Related Works on Underground Mining Path Planning with UGVs

The automation of underground mining vehicles has been the focus of research and industry for several decades. However, path planning for autonomous navigation remains a critical challenge and an active area of investigation. Despite several studies have been conducted on the review of path planning algorithms on the ground [16,35], a limited number of studies have successfully addressed optimal path planning for mining vehicles and robotic applications in underground environments.
Effective path planning allows UGVs to traverse complex, unstructured terrains while ensuring efficiency, safety, and adaptability. Researchers have explored various techniques, ranging from classical graph-based methods to modern metaheuristic and RL-based approaches, each aiming to optimize path efficiency, obstacle avoidance, and computational feasibility. These approaches have been validated in real underground mines, controlled indoor environments, and virtual simulation frameworks implemented in environments such as MATLAB, Python, and Gazebo. Table 5 reviews key contributions by researchers in the field, categorizing existing studies based on algorithmic approaches, testing strategies, and demonstrated advantages in underground mining applications.
A thorough analysis of the data presented in Table 5 indicates that several underground mining operations are being targeted by UGV navigation systems. The majority of research in path planning focused on mine transportation, which is primarily carried out using LHD. Additionally, mine exploration and inspection tasks with mobile robots equipped with specialized sensors emerged as a significant area of research interest. SAR is another critical topic for underground mining operations, and numerous researchers are exploring optimal path planning algorithms for successful rescue operations after disasters. It is notable that coal mines are considered to be high-risk environments due to their potential for accidents.
Despite the limited research in this area, existing studies have employed all types of environment representation and search strategy models. The most prevalent techniques employed in underground mining environments include classical approaches such as graph-based and sampling-based algorithms, as illustrated in Figure 3a, which is based on an analysis of the existing research.
It is illustrated that the A* algorithm is the most prevalent global path planning algorithm in the field, with approximately one in three studies utilizing this approach. This method incorporates a range of optimization strategies, including Gaussian filtering, quadratic programming, expanding and selecting nodes, collision threat cost, exponential function weighting, splines, and other features. These techniques ensure safe, smooth, and optimal paths for UGVs in mining transportation and inspection tasks [61,62,63,64,65,66]. Graph-based algorithms have also demonstrated a high level of efficiency in hybrid contexts. For example, the utilization of A* with VFH employing Bazier interpolation and Dijkstra’s with ACO and PSO employing curve strategies have been shown to enhance search efficiency, smoothness, and accelerated calculation in mining operations and SAR [67,68,69]. Dijkstra’s algorithm also demonstrated strong performance in path planning within 3D environments [70], representing 14% of the analyzed studies.
Sampling-based methods have gained significant attention, with the RRT accounting for 18% of all research in the field. Optimized versions incorporating vectorized map, optimal tree reconnection, and line corner for narrow passages have demonstrated superior path smoothness and shorter path lengths in operating mining transports [72,73]. A hybrid RRT*—PRM model integrating fan-shaped goal orientation, adaptive step-size expansion, and Bessel curve has been shown to enhance success rates and smoothness for mining inspection robots [74]. Similarly, the incorporation of ray-tracing and next-best-view methods into the RRG has been applied to mine rescue operations, achieving shorter path generation and faster computational speed [75].
Nature-inspired approaches have been frequently explored, with ACO accounting for approximately 18% of applications for underground mining navigation and rescue applications. Studies have employed retreat-punishment mechanisms, serial numbering and Cartesian coordinates, along with a 16-directional, 24-neighborhood ACO approach. Other implementations incorporated techniques such as the ant retreat strategy, annealing algorithms, pheromone updating models, and entropy-increasing strategies to reduce consumption costs, overcome U-shaped obstacle traps, and enhance convergence speed, efficiency, and robustness [76,78,79,80].
The last 18% of the analyzed research is primarily divided between various types of nature-inspired and RL-based algorithms. For example, the hybrid approaches BFA combined with PSA, tested when solving the traveling salesman problem, and AFSA with an improved genetic algorithm, demonstrated fast convergence, better robustness, and shorter paths in SAR applications [81,82]. Additionally, RL algorithms, such as Q-learning, combined with the Even Gray Model and Multi-Attribute Intelligent Decision-Making, demonstrated smoother convergence and high robustness in SAR operation [83].
Unlike global path planning, local path planning involves fewer algorithms. As illustrated in Figure 3b, the DWA is the most favorable method for adjusting the kinematics of UGVs. In the second place stands APF, which could be modified with global potential field line and genetic Trust Region strategies to overcome local minima and dynamic collision in coal mine rescue tasks [85]. Moreover, membrane computing-based ACO enhances robustness and convergence speed [77], while skeleton-based thinning algorithms provide high stability and robustness [84]. Additionally, the TEB method was also utilized for local path planning.
The test environments used in the reviewed studies highlight the progression from simulation-based validation to real-world implementation. Many algorithms have been tested in MATLAB and Python simulations, providing controlled conditions for evaluating path efficiency, convergence, and obstacle avoidance. However, some studies extend their validation to indoor lab environments, where methods have been tested in structured, tunnel-like settings, enabling real-time sensor fusion and navigation performance analysis. The most reliable assessments come from real underground mining experiments. Only a few algorithms have been deployed to evaluate practical feasibility, adaptability to real-world constraints, and system robustness.

6. Discussion

The analysis of various path planning algorithms for underground mining UGVs highlights significant trends and challenges in achieving efficient, safe, and adaptive autonomous navigation. Most existing research is focused on transportation, inspection, and SAR operations in mines. The comparison of graph-based, sampling-based, nature-inspired, RL-based, and local path planning approaches demonstrates that each method has unique advantages and limitations depending on the operational environment and constraints.
Graph-based approaches, such as A* and Dijkstra’s, remain widely used due to their deterministic nature and best performance in structured environments. However, these algorithms often struggle with real-time adaptability, particularly in dynamic underground environments where sudden obstacles and unpredictable conditions are common. To overcome these drawbacks, especially for the A* collision threat cost and repulsion potential field correction factor, strategies are used. Furthermore, A* typically produces paths that can be jagged or not smooth, especially in complex environments. Techniques like cubic spline interpolation and B-spline curves provide a way to refine paths.
The most commonly used sampling-based method, which is the RRT, is effective in exploration tasks and offers better adaptability in large-scale environments. However, it can suffer from path irregularities and challenges in collision detection. To address these issues, several strategies have been proposed, including vectorized maps, line corner handling, and third-order Bessel curves.
Nature-inspired approaches, particularly ACO, improve search efficiency, robustness, and obstacle avoidance but require higher computational resources. To mitigate this problem, the 16-Directional 24-Neighbourhood Ant Search Approach and the Pheromone Updating Model were used.
RL-based approaches, such as grey Q-Learning, have demonstrated potential in adaptive decision-making, but their practical implementation is still limited by computational complexity and training data requirements.
Among local path planning algorithms, DWA has been identified as the most favorable. To address its limitations, the Adaptive Trajectory Evaluation Function and Fuzzy Control were employed.
Analyzing the current research, it is notable that some hybrid algorithms also demonstrated effective and optimal path planning, such as VFH-A*, Dijkstra-ACO, Dijkstra-PSO, RRT-PRM, and BFA-PSA.
Several limitations persist in analyzing the existing research studies on the selected topic, as outlined below:
  • Over-reliance on simulation environments, which do not fully replicate the complexity of real underground mining conditions;
  • Limited real mine experiments—only a small number of studies have been conducted in actual underground mines;
  • Insufficient consideration of real-time constraints, such as sensor delays, terrain irregularities, and power limitations, which are critical for full-scale deployment in mining operations;
  • High algorithmic complexity, particularly in hybrid, nature-inspired, and reinforcement learning (RL)-based approaches, which can hinder implementation and real-world adaptation;
  • Lack of interpretability, as many advanced algorithms lack transparency, making them hard to evaluate or debug in applications.
Based on the analyzed research data and identified limitations, several future research directions are proposed:
  • Bridging the gap between simulation and real-world implementation by testing algorithms not only in simulation environments such as Gazebo but also in modeled indoor labs and actual underground mines;
  • Evaluating both common and reinforcement learning (RL)-based path planning algorithms using UGVs in underground mining environments to assess their real-time performance and adaptability;
  • Investigating the effectiveness of common path optimization techniques and improving existing planning algorithms to address their current limitations in path smoothness, efficiency, and robustness.

7. Conclusions

The automation of underground mining operations has advanced significantly in recent years, with Unmanned Ground Vehicles (UGVs) playing a crucial role in improving efficiency, safety, and productivity. Unlike outdoor and structured indoor environments, underground mines present unique challenges, including complex tunnel networks, low visibility, and unstable terrain. To navigate these environments, autonomous mining vehicles rely on core navigation components, such as mapping, Simultaneous Localization and Mapping (SLAM), and path planning, all of which must be tailored to the constraints of underground operations. UGVs are deployed in exploration, monitoring structural changes, transportation, Search and Rescue Operations (SARs) tasks, and inspection, requiring robust navigation systems to ensure operational reliability.
Path planning in underground mines presents distinct challenges due to GPS-denied, unpredictable environmental changes, and the need for efficient real-time decision-making. This review comprehensively analyzed global and local path planning algorithms used in underground mining applications, covering graph-based, sampling-based, nature-inspired, and reinforcement learning (RL)-based approaches. The analysis conducted in this study addressed the research questions and produced the following key findings:
  • Sensors, such as LiDAR, cameras, and radar, are critical for perceiving underground mining environments, and Robot Operating System (ROS) has emerged as the primary framework for integrating and managing sensor-based data in mining robots;
  • Graph-based algorithms, including A* and Dijkstra’s, work well in structured environments due to their deterministic nature, while sampling-based approaches, like Rapidly-exploring Random Tree (RRT*), offer better scalability in high-dimensional spaces. Nature-Inspired algorithms, such as Ant Colony Optimization (ACO), are useful for solving complex optimization problems. In contrast, RL-based techniques provide adaptability in dynamic and unknown environments;
  • Among global path planning algorithms, A*, Dijkstra’s, RRT*, and ACO are the most frequently used in underground UGV applications. For local path planning, the Dynamic Window Approach (DWA) remains the dominant method in real mining scenarios;
  • Optimization strategies such as spline curves, node optimization, and potential field are commonly applied to improve path smoothness, efficiency, and safety;
  • The majority of research is conducted in simulation environments, such as MATLAB, which do not fully capture real-world sensor integration challenges and environmental complexities. Only a relatively small number of studies have been validated in real underground mining environments;
  • Complex and computationally intensive algorithms, especially RL-based and hybrid methods, present practical implementation challenges in real-world deployments.
These findings underline a significant research gap between theoretical development and practical deployment. Addressing this gap requires future studies to emphasize real-environment testing and the interpretability of complex algorithms in underground conditions.
This review serves as a timely and valuable resource for researchers and practitioners aiming to advance autonomous navigation systems for UGVs in underground mining environments.

Author Contributions

Conceptualization, A.A. and J.B.; methodology, A.A.; formal analysis, A.A.; investigation, A.A.; resources, J.B; data curation, A.A.; writing—original draft preparation, AA.; writing—review and editing, J.B.; visualization, A.A.; supervision, J.B.; project administration, J.B.; funding Acquisition, J.B. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the German Academic Scholarship Foundation, the Deutsche Forschungsgemeinschaft (DFG, German Research Foundation)—Project number 422117092 using the research infrastructure INST 267/165-1 FUGG and by “El-yurt umidi” Foundation for training specialists abroad and the dialogue with compatriots—Certificate number DR-2022-0115.

Data Availability Statement

No new data were created or analyzed in this study. Data sharing is not applicable to this article due to internal policy.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kokkinis, A.; Frantzis, T.; Skordis, K.; Nikolakopoulos, G.; Koustoumpardis, P. Review of Automated Operations in Drilling and Mining. Machines 2024, 12, 845. [Google Scholar] [CrossRef]
  2. Saleh, J.H.; Cummings, A.M. Safety in the Mining Industry and the Unfinished Legacy of Mining Accidents: Safety Levers and Defense-in-Depth for Addressing Mining Hazards. Saf. Sci. 2011, 49, 764–777. [Google Scholar] [CrossRef]
  3. Li, J.; Zhan, K. Intelligent Mining Technology for an Underground Metal Mine Based on Unmanned Equipment. Engineering 2018, 4, 381–391. [Google Scholar] [CrossRef]
  4. Hofmann-Wellenhof, B.; Legat, K.; Wieser, M. Navigation: Principles of Positioning and Guidance; Springer: Vienna, Austria, 2003; Available online: https://books.google.de/books?id=dMXcBQAAQBAJ (accessed on 26 February 2025).
  5. Roberts, J.M.; Duff, E.S.; Corke, P. Reactive Navigation and Opportunistic Localization for Autonomous Underground Mining Vehicles. Inf. Sci. 2002, 145, 127–146. Available online: https://api.semanticscholar.org/CorpusID:1925516 (accessed on 8 May 2025). [CrossRef]
  6. Ebadi, K.; Bernreiter, L.; Biggie, H.; Catt, G.; Chang, Y.; Chatterjee, A.; Denniston, C.E.; Deschênes, S.-P.; Harlow, K.; Khattak, S.; et al. Present and Future of SLAM in Extreme Underground Environments. arXiv 2022, arXiv:2208.01787. Available online: https://api.semanticscholar.org/CorpusID:251280074 (accessed on 8 May 2025).
  7. Ojeda, L.; Borenstein, J. Personal Dead-Reckoning System for GPS-Denied Environments. In Proceedings of the 2007 IEEE International Workshop on Safety, Security and Rescue Robotics, Rome, Italy, 25–27 September 2007; pp. 1–6. [Google Scholar] [CrossRef]
  8. Tatsch, C.; Bredu, J.A.; Covell, D.; Tulu, I.B.; Gu, Y. Rhino: An Autonomous Robot for Mapping Underground Mine Environments. In Proceedings of the 2023 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Seattle, WA, USA, 27–30 June 2023; pp. 1166–1173. [Google Scholar] [CrossRef]
  9. Mäkelä, H. Overview of LHD Navigation without Artificial Beacons. Rob. Auton. Syst. 2001, 36, 21–35. [Google Scholar] [CrossRef]
  10. Li, Y.; Peng, P.; Li, H.; Xie, J.; Liu, L.; Xiao, J. Drilling Path Planning of Rock-Drilling Jumbo Using a Vehicle-Mounted 3D Scanner. Sustainability 2023, 15, 9737. [Google Scholar] [CrossRef]
  11. Kim, H.; Choi, Y. Development of Autonomous Driving Patrol Robot for Improving Underground Mine Safety. Appl. Sci. 2023, 13, 3717. [Google Scholar] [CrossRef]
  12. Wang, W.; Dong, W.; Su, Y.; Wu, D.; Du, Z. Development of Search-and-Rescue Robots for Underground Coal Mine Applications. J. Field Robot. 2014, 31, 386–407. [Google Scholar] [CrossRef]
  13. Karimi, H. Indoor Wayfinding and Navigation; CRC Press: Boca Raton, FL, USA, 2015; Available online: https://books.google.de/books?id=I3oZBwAAQBAJ (accessed on 28 February 2025).
  14. Galar, D.; Kumar, U.; Seneviratne, D. Robots, Drones, UAVs and UGVs for Operation and Maintenance; CRC Press: Boca Raton, FL, USA, 2020. [Google Scholar] [CrossRef]
  15. Inostroza, F.; Parra-Tsunekawa, I.; Ruiz-del-Solar, J. Robust Localization for Underground Mining Vehicles: An Application in a Room and Pillar Mine. Sensors 2023, 23, 8059. [Google Scholar] [CrossRef]
  16. Liu, L.; Wang, X.; Yang, X.; Liu, H.; Li, J.; Wang, P. Path Planning Techniques for Mobile Robots: Review and Prospect. Expert Syst. Appl. 2023, 227, 120254. [Google Scholar] [CrossRef]
  17. Biggie, H.; Rush, E.R.; Riley, D.G.; Ahmad, S.; Ohradzansky, M.T.; Harlow, K.; Miles, M.J.; Torres, D.; McGuire, S.; Frew, E.W.; et al. Flexible Supervised Autonomy for Exploration in Subterranean Environments. Field Robot. 2023, 3, 125–189. [Google Scholar] [CrossRef]
  18. Egerstedt, M.; Martin, C. Control Theoretic Splines: Optimal Control, Statistics, and Path Planning; Princeton University Press: Princeton, NJ, USA, 2009; Available online: https://books.google.de/books?id=crNiMAsPex8C (accessed on 6 March 2025).
  19. Trybała, P.; Szrek, J.; Remondino, F.; Kujawa, P.; Wodecki, J.; Blachowski, J.; Zimroz, R. MIN3D Dataset: MultI-seNsor 3D Mapping with an Unmanned Ground Vehicle. PFG–J. Photogramm. Remote Sens. Geoinf. Sci. 2023, 91, 425–442. [Google Scholar] [CrossRef]
  20. Peng, P.; Pan, J.; Zhao, Z.; Xi, M.; Chen, L. A Novel Obstacle Detection Method in Underground Mines Based on 3D LiDAR. IEEE Access 2024, 12, 106685–106694. [Google Scholar] [CrossRef]
  21. Nielsen, K. Robust LIDAR-Based Localization in Underground Mines; Linköping University Electronic Press: Linköping, Sweden, 2021; Volume 1906. [Google Scholar] [CrossRef]
  22. Jing, N.-B.; Ma, X.; Guo, W.; Wang, M. 3D Reconstruction of Underground Tunnel Using Depth-Camera-Based Inspection Robot. Sensors Mater. 2019, 31, 2719–2734. Available online: https://api.semanticscholar.org/CorpusID:203068830 (accessed on 8 May 2025). [CrossRef]
  23. Cunha, F.; Youcef-Toumi, K. Ultra-Wideband Radar for Robust Inspection Drone in Underground Coal Mines. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, Australia, 21–25 May 2018; pp. 86–92. [Google Scholar] [CrossRef]
  24. Ahmad, N.; Ghazilla, A.R.; Khairi, N.M.; Kasi, V. Reviews on Various Inertial Measurement Unit (IMU) Sensor Applications. Int. J. Signal Process. Syst. 2013, 1, 256–262. [Google Scholar] [CrossRef]
  25. Rodrigues, C.M. Ground Mobile Vehicle Velocity Control Using Encoders and Optical Flow Sensor Fusion. 2016. Available online: https://api.semanticscholar.org/CorpusID:202662013 (accessed on 8 May 2025).
  26. Liu, K.-Q.; Zhong, S.-S.; Zhao, K.; Song, Y. Motion Control and Positioning System of Multi-Sensor Tunnel Defect Inspection Robot: From Methodology to Application. Sci. Rep. 2023, 13, 13125. [Google Scholar] [CrossRef]
  27. Quigley, M. ROS: An Open-Source Robot Operating System. In Proceedings of the IEEE International Conference on Robotics and Automation, Kobe, Japan, 12–17 May 2009; Available online: https://api.semanticscholar.org/CorpusID:6324125 (accessed on 8 May 2025).
  28. Aljamal, M.; Patel, S.; Mahmood, A. Comprehensive Review of Robotics Operating System-Based Reinforcement Learning in Robotics. Appl. Sci. 2025, 15, 1840. [Google Scholar] [CrossRef]
  29. Al-Batati, A.S.; Koubaa, A.; Abdelkader, M. ROS 2 in a Nutshell: A Survey. Preprints 2024. [CrossRef]
  30. Joseph, L.; Cacace, J. Mastering ROS for Robotics Programming; Packt Publishing: Birmingham, UK, 2018; Available online: https://books.google.de/books?id=MulODwAAQBAJ (accessed on 9 March 2025).
  31. Agha, A.; Otsu, K.; Morrell, B.; Fan, D.D.; Thakker, R.; Santamaria-Navarro, A.; Kim, S.-K.; Bouman, A.; Lei, X.; Edlund, J.; et al. NeBula: Quest for Robotic Autonomy in Challenging Environments; TEAM CoSTAR at the DARPA Subterranean Challenge. arXiv 2021, arXiv:2103.11470. [Google Scholar]
  32. Losch, R.; Grehl, S.; Donner, M.; Buhl, C.; Jung, B. Design of an Autonomous Robot for Mapping, Navigation, and Manipulation in Underground Mines. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018; pp. 1407–1412. [Google Scholar] [CrossRef]
  33. Thrun, S. Learning Metric-Topological Maps for Indoor Mobile Robot Navigation. Artif. Intell. 1998, 99, 21–71. [Google Scholar] [CrossRef]
  34. Gil, A.; Reinoso, Ó.; Vicente, A.; Fernández, C.; Payá, L. Monte Carlo Localization Using SIFT Features. In Computer Aided Systems Theory—EUROCAST 2005; Springer: Berlin/Heidelberg, Germany, 2005; pp. 623–630. [Google Scholar] [CrossRef]
  35. Yang, L.; Li, P.; Qian, S.; Quan, H.; Miao, J.; Liu, M.; Hu, Y.; Memetimin, E. Path Planning Technique for Mobile Robots: A Review. Machines 2023, 11, 980. [Google Scholar] [CrossRef]
  36. Javaid, M.A. Understanding Dijkstra Algorithm. SSRN Electron. J. 2013. [CrossRef]
  37. Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  38. Koenig, S.; Likhachev, M. D*Lite. In Proceedings of the AAAI Conference on Artificial Intelligence (AAAI/IAAI), Edmonton, AB, Canada, 28 July–1 August 2002. [Google Scholar]
  39. LaValle, S.M. Rapidly-Exploring Random Trees: A New Tool for Path Planning. Annu. Res. Rep. 1998. Available online: https://api.semanticscholar.org/CorpusID:14744621 (accessed on 8 May 2025).
  40. Karaman, S.; Frazzoli, E. Optimal Kinodynamic Motion Planning Using Incremental Sampling-Based Methods. In Proceedings of the 49th IEEE Conference on Decision and Control (CDC), Atlanta, GA, USA, 15–17 December 2010; pp. 7681–7687. [Google Scholar] [CrossRef]
  41. Kavraki, L.E.; Švestka, P.; Latombe, J.C.; Overmars, M.H. Probabilistic Roadmaps for Path Planning in High-Dimensional Configuration Spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef]
  42. Goldberg, D.E. Genetic Algorithms in Search, Optimization, and Machine Learning; Addison-Wesley: Boston, MA, USA, 1989; Available online: https://archive.org/details/geneticalgorithm0000gold (accessed on 2 February 2025).
  43. Kennedy, J.; Eberhart, R. Particle Swarm Optimization. In Proceedings of the IEEE International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; pp. 1942–1948. [Google Scholar]
  44. Dorigo, M.; Gambardella, L.M. Ant Colony System: A Cooperative Learning Approach to the Traveling Salesman Problem. IEEE Trans. Evol. Comput. 1997, 1, 53–66. [Google Scholar] [CrossRef]
  45. Sutton, R.S.; Barto, A.G. Reinforcement Learning: An Introduction, 2nd ed.; MIT Press: Cambridge, MA, USA, 2018. [Google Scholar]
  46. Watkins, C.J.C.H.; Dayan, P. Q-Learning. Mach. Learn. 1992, 8, 279–292. [Google Scholar] [CrossRef]
  47. Mnih, V.; Kavukcuoglu, K.; Silver, D.; Rusu, A.A.; Veness, J.; Bellemare, M.G.; Graves, A.; Riedmiller, M.; Fidjeland, A.K.; Ostrovski, G.; et al. Human-Level Control through Deep Reinforcement Learning. Nature 2015, 518, 529–533. [Google Scholar] [CrossRef]
  48. Al-Ansarry, S.; Al-Darraji, S. Hybrid RRT-A*: An Improved Path Planning Method for an Autonomous Mobile Robots. J. Electr. Electron. Eng. 2021, 17, 1–9. Available online: https://api.semanticscholar.org/CorpusID:236371326 (accessed on 8 May 2025). [CrossRef]
  49. Lu, D.V.; Hershberger, D.; Smart, W.D. Layered Costmaps for Context-Sensitive Navigation. In Proceedings of the IEEE International Conference on Intelligent Robots and Systems (IROS), Chicago, IL, USA, 14–18 September 2014; pp. 709–715. [Google Scholar] [CrossRef]
  50. Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef]
  51. Khatib, O. Real-Time Obstacle Avoidance for Manipulators and Mobile Robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
  52. Borenstein, J.; Koren, Y. The Vector Field Histogram—Fast Obstacle Avoidance for Mobile Robots. IEEE J. Robot. Autom. 1991, 7, 278–288. [Google Scholar] [CrossRef]
  53. Li, J.; Sun, J.; Liu, L.; Xu, J. Model Predictive Control for the Tracking of Autonomous Mobile Robot Combined with a Local Path Planning. Meas. Control 2021, 54, 1319–1325. [Google Scholar] [CrossRef]
  54. Yongzhe, Z.; Ma, B.; Wai, C.K. A Practical Study of Time-Elastic-Band Planning Method for Driverless Vehicle for Auto-Parking. In Proceedings of the 2018 International Conference on Intelligent Autonomous Systems (ICoIAS), Singapore, 1–3 March 2018; pp. 196–200. [Google Scholar] [CrossRef]
  55. Chang, Z.; Wang, Y.; Cai, Y.; Li, S.; Gao, F. Fusion of Improved RRT and Ant Colony Optimization for Robot Path Planning. Eng. Res. Express 2024, 6, 045247. [Google Scholar] [CrossRef]
  56. Sharma, V.D.; Lee, J.; Andrews, M.; Hadžić, I.H. Hybrid Classical/RL Local Planner for Ground Robot Navigation. arXiv 2024, arXiv:2410.03066. Available online: http://arxiv.org/abs/2410.03066 (accessed on 2 February 2025).
  57. Ravankar, A.; Ravankar, A.A.; Kobayashi, Y.; Hoshino, Y.; Peng, C.-C. Path Smoothing Techniques in Robot Navigation: State-of-the-Art, Current and Future Challenges. Sensors 2018, 18, 3170. [Google Scholar] [CrossRef]
  58. Thrun, S.; Burgard, W.; Fox, D. Probabilistic Robotics; MIT Press: Cambridge, MA, USA, 2005. [Google Scholar]
  59. Wang, L.; Yang, X.; Chen, Z.; Wang, B. Application of the Improved Rapidly Exploring Random Tree Algorithm to an Insect-like Mobile Robot in a Narrow Environment. Biomimetics 2023, 8, 374. [Google Scholar] [CrossRef]
  60. Dorigo, M.; Maniezzo, V.; Colorni, A. The Ant System: Optimization by a colony of cooperating agents. IEEE Trans. Syst. Man Cybern. B Cybern. 1996, 26, 29–41. [Google Scholar] [CrossRef]
  61. Liu, T.; Huang, Z.; Wang, C.; An, Z.; Meng, X.; Zheng, J. Path Planning of Underground Mining Area Transportation Scene Based on Improved A* Algorithm. In Proceedings of the 2023 7th International Conference on Transportation Information and Safety (ICTIS), Nanjing, China, 3–6 August 2023; pp. 2265–2270. [Google Scholar] [CrossRef]
  62. Yulong, Q.; Qingyong, M.; Xu, T. Research on Navigation Path Planning for an Underground Load Haul Dump. J. Eng. Sci. Technol. Rev. 2015, 8, 102–109. Available online: https://api.semanticscholar.org/CorpusID:116378442 (accessed on 8 May 2025). [CrossRef]
  63. Bao, J.-s.; Zhang, M.-y.; Ge, S.-r.; Liu, Q.; Yuan, X.-m.; Wang, M.-s.; Yin, Y.; Zhao, L. Underground Driverless Path Planning of Trackless Rubber Tyred Vehicle Based on Improved A* and Artificial Potential Field Algorithm. J. China Coal Soc. 2022, 47, 1347–1360. Available online: https://www.mtxb.com.cn/en/article/id/d7bec14d-e1ed-4d3d-9990-eb127b3e130c (accessed on 8 May 2025).
  64. Zhang, C.; Yang, X.; Zhou, R.; Guo, Z. A Path Planning Method Based on Improved A* and Fuzzy Control DWA of Underground Mine Vehicles. Appl. Sci. 2024, 14, 3103. [Google Scholar] [CrossRef]
  65. Zhu, D.; Zhang, Y.; Wang, J.; Ren, K.; Yang, K. Evaluation of Motion Planning Algorithms for Underground Mobile Robots. In Proceedings of the International Conference on Robotics and Applications (ICRA), Philadelphia, PA, USA, 23–27 May 2022; Springer: Singapore, 2022; pp. 368–379. [Google Scholar] [CrossRef]
  66. Gu, C.; Liu, S.; Li, H.; Yuan, K.; Bao, W. Research on Hybrid Path Planning of Underground Degraded Environment Inspection Robot Based on Improved A* Algorithm and DWA Algorithm. Robotica 2025, 43, 1–22. [Google Scholar] [CrossRef]
  67. Zhang, B.; Zhang, Y.; Zhang, C.; Cheng, J.; Shen, G.; Wang, X. Path Planning for Unmanned Load–Haul–Dump Machines Based on a VHF_A* Algorithm. Proc. Inst. Mech. Eng. C J. Mech. Eng. Sci. 2024, 238, 6584–6597. [Google Scholar] [CrossRef]
  68. Ma, X.; Mao, R. Path Planning for Coal Mine Robot to Avoid Obstacle in Gas Distribution Area. Int. J. Adv. Robot. Syst. 2018, 15, 1–10. [Google Scholar] [CrossRef]
  69. Xu, R.; Yao, S. Research on UGV Path Planning in Tunnel Based on the Dijkstra*-PSO* Algorithm. In Proceedings of the 2022 6th Asian Conference on Artificial Intelligence Technology (ACAIT), Chengdu, China, 9–11 December 2022; pp. 1–9. [Google Scholar] [CrossRef]
  70. Chen, Z. Path Planning Method for Underground Survey Robot in Dangerous Scenarios. Highl. Sci. Eng. Technol. 2023, 43, 207–214. [Google Scholar] [CrossRef]
  71. Ma, T.; Lv, J.; Guo, M. Downhole Robot Path Planning Based on Improved D* Algorithm. In Proceedings of the 2020 IEEE International Conference on Signal Processing, Communications and Computing (ICSPCC), Macau, China, 26–28 August 2020; pp. 1–5. [Google Scholar] [CrossRef]
  72. Wang, H.; Li, G.; Hou, J.; Chen, L.; Hu, N. A Path Planning Method for Underground Intelligent Vehicles Based on an Improved RRT* Algorithm. Electronics 2022, 11, 294. [Google Scholar] [CrossRef]
  73. Hopfenblatt, B.; Axel, N. A Combined RRT*-Optimal Control Approach for Kinodynamic Motion Planning for Mobile Robots. 2016. Available online: https://api.semanticscholar.org/CorpusID:203702248 (accessed on 8 May 2025).
  74. Wu, J.; Zhao, L.; Liu, R. Research on Path Planning of a Mining Inspection Robot in an Unstructured Environment Based on an Improved Rapidly Exploring Random Tree Algorithm. Appl. Sci. 2024, 14, 6389. [Google Scholar] [CrossRef]
  75. Steinbrink, M.; Koch, P.; Jung, B.; May, S. Rapidly-Exploring Random Graph Next-Best View Exploration for Ground Vehicles. arxiv 2021, arXiv:2108.01012. Available online: http://arxiv.org/abs/2108.01012 (accessed on 28 January 2025).
  76. Song, B.; Miao, H.; Xu, L. Path Planning for Coal Mine Robot via Improved Ant Colony Optimization Algorithm. Syst. Sci. Control Eng. 2021, 9, 283–289. [Google Scholar] [CrossRef]
  77. Xu, J.C.; Huang, Y.R.; Xu, G.Y. A Path Optimization Algorithm for the Mobile Robot of Coal Mine Based on Ant Colony Membrane Algorithm. In Proceedings of the 2018 ACM International Conference on Computing and Sustainable Societies (COMPASS), Menlo Park and San Jose, CA, USA, 12–15 December 2018. [Google Scholar] [CrossRef]
  78. Shao, X.; Wang, G.; Zheng, R.; Wang, B.; Yang, T.; Liu, S. Path Planning for Mine Rescue Robots Based on Improved Ant Colony Algorithm. In Proceedings of the 2022 8th International Conference on Control, Automation and Robotics (ICCAR), Xiamen, China, 8–10 April 2022; pp. 161–166. [Google Scholar] [CrossRef]
  79. Liu, K.; Zhang, M. Path Planning Based on Simulated Annealing Ant Colony Algorithm. In Proceedings of the 2016 9th International Symposium on Computational Intelligence and Design (ISCID), Hangzhou, China, 10–11 December 2016; Volume 2, pp. 461–466. [Google Scholar] [CrossRef]
  80. Fang, C.; Liu, X.; Hua, D.; Wang, H.; Li, Z.; Chauhan, S.; Vashishtha, G. Real-Time Path Planning of Drilling Robot Using Global and Local Sensor Information Fusion: Mining-Oriented Validation. Int. J. Adv. Manuf. Technol. 2024, 135, 5875–5891. [Google Scholar] [CrossRef]
  81. Li, P.; Zhu, H. Immune Optimization of Path Planning for Coal Mine Rescue Robot. 2016. Available online: https://api.semanticscholar.org/CorpusID:13507361 (accessed on 8 May 2025).
  82. Gao, Y.; Dai, Z.; Yuan, J. A Multiobjective Hybrid Optimization Algorithm for Path Planning of Coal Mine Patrol Robot. Comput. Intell. Neurosci. 2022, 2022, 9094572. [Google Scholar] [CrossRef]
  83. Zhang, S.; Zeng, Q. Online Unmanned Ground Vehicle Path Planning Based on Multi-Attribute Intelligent Reinforcement Learning for Mine Search and Rescue. Appl. Sci. 2024, 14, 9127. [Google Scholar] [CrossRef]
  84. Jiang, Y.; Peng, P.; Wang, L.; Wang, J.; Wu, J.; Liu, Y. LiDAR-Based Local Path Planning Method for Reactive Navigation in Underground Mines. Remote Sens. 2023, 15, 309. [Google Scholar] [CrossRef]
  85. Tian, Z.-J.; Gao, X.-H.; Zhang, M.-X. Path Planning Based on the Improved Artificial Potential Field of Coal Mine Dynamic Target Navigation. J. China Coal Soc. 2016, 41, 589–597. [Google Scholar] [CrossRef]
Figure 2. Workflow and types of path planning.
Figure 2. Workflow and types of path planning.
Mining 05 00033 g002
Figure 3. Percentage and number of existing path planning algorithms that are being investigated by researchers for the underground mining environment (a) Global path planning; (b) Local path planning.
Figure 3. Percentage and number of existing path planning algorithms that are being investigated by researchers for the underground mining environment (a) Global path planning; (b) Local path planning.
Mining 05 00033 g003
Table 1. Unique factors of each environment and their impact on navigation.
Table 1. Unique factors of each environment and their impact on navigation.
FactorsMineIndoorOutdoor
Surface ConditionsIrregular surfaces, narrow passages, and mudSmooth and structured
surfaces
Varied surfaces
ObscurantsDust, smoke, and gasNearly clearRain, fog, and snow
GPS AvailabilityGPS deniedAvailable with extended setupsWidely available and effective
Obstacle DensityRelatively highLowModerate
Table 2. Requirements and evaluation criteria for planned paths in underground mining environments.
Table 2. Requirements and evaluation criteria for planned paths in underground mining environments.
RequirementsEvaluation Criteria
Optimal pathMinimal travel time and path length
SmoothnessSpatial and temporal smoothness coefficients [18]
High accuracy and safetyAvoids obstacles and ensures collision-free path
Success ratePercentage of successful path completions
Computational costProcessing time and resource consumption
RobustnessAbility to handle uncertainties
Handling narrow tunnelsMinimum passable width
Table 3. Sensors’ features.
Table 3. Sensors’ features.
SensorsStrengthsWeaknessesRange and Frequency
LiDAR 3D [20]Works well in
low-light environments;
Performance can degrade in dust, smoke or reflective surfaces;10–300 m;
10–100 Hz
High accuracy in 3D mapping and obstacle detection.High power consumption.
Laser scanner 2D [21]Works in low-light environments;Performance may degrade in heavy particulate environments;0,5–25 m;
10–100 Hz
Provides precise distance
measurements.
Computationally intensive.
Depth Camera [22]Provides both color (RGB) and depth (D) information;Sensitive to reflective and
transparent surfaces;
0.2–10 m;
30–90 Hz
Compact and lightweightCan be disrupted by dust or fog.
Radar [23]Works in harsh environments (dust, smoke);Difficult to interpret data
without additional processing;
0.1–250 m;
10–200 Hz
Reliable for detecting dynamic objects.Lower resolution.
IMU [24]Small, lightweight, and power-efficient;Susceptible to external
vibrations and sensor noise;
100–1000 Hz
Provides high-frequency motion data.Accumulates drift over time.
Motor Encoder [25]Simple integration with UGV control systems;Accumulates drift over long
distances (wheel slippage);
10–1000 Hz
High frequency data.Not reliable for rough terrain or slippery surfaces.
Table 4. Strengths and weaknesses of path-planning algorithms.
Table 4. Strengths and weaknesses of path-planning algorithms.
AlgorithmsStrengthWeakness
DijkstraGuarantees the shortest path;Computationally intensive;
Works well in static environments.Inefficiency in dynamic environment.
A*Fast and Efficient;Depends on map quality and resolution;
Deterministic and reliable on structured maps.Slow in high-dimensional spaces.
D*Efficient replanning;Higher memory usage;
Handles dynamic obstacles well.Slower with frequent changes.
RRT*Efficient in high-dimensional spaces;Paths are not always smooth;
Incremental path improvement.Slower in narrow passages.
PRMReusable path for repeated queries;Paths are not always smooth;
Works well in large, open spaces.Struggles with dynamic obstacles.
GAEfficient in high-dimensional spaces;Slow convergence;
Works well with noisy data.Sensitive to parameter selection.
PSOSimple to implement;Prone to local minima;
Adaptive to dynamic environments.Sensitive to parameter selection.
ACOGood for multi-agent path planning;Computationally intensive;
Works in dynamic environments.Slower convergence.
Q-LearningWorks with Partial Information;Higher memory usage;
Can Handle Complex Environments.Slow convergence in large spaces.
DQNSuitable for high-dimensional spaces;Requires high computational power;
Works with Partial Observability.Sensitive to parameter selection.
DWASmooth and feasible paths;Prone to local minima;
Computationally lightweight.Struggles with complex environment.
APFLightweight, fast obstacle avoidance;Prone to local minima;
Simple, best for reactive navigation.Struggles with dynamic obstacles.
VFHEfficient real-time obstacle avoidance;Prone to local minima;
Handles noisy sensor data well.Oscillations in Narrow Spaces.
MPCOptimizes performance;Computationally intensive;
Generates smooth and efficient paths.Limited real-time application.
TEBGenerates smooth, time-optimal path;Computationally intensive;
Dynamic Obstacle Avoidance.Sensitive to parameter selection.
Table 5. Analysis of various path planning techniques for UGVs in underground mine.
Table 5. Analysis of various path planning techniques for UGVs in underground mine.
AuthorPath TypeBasic
Algorithms
Optimization StrategyTest FieldAdvantagesApplication
[61]GlobalA*Gaussian filtering method;MATLABSafety;LHD in mining transportation
Quadratic programming method.Smoother path.
[62]GlobalA*Expanding nodes by articulation angle;Indoor; C++.Enhanced search
efficiency;
LHD in mining transportation
Collision threat cost.Collision free.
[63]Global
Local
A* + APFExponential function weighting;MATLAB; Indoor.Smoother path;Transportation in coal mine
Cubic spline interpolation;More robust;
Repulsion potential field correction factor.Guaranteed safety.
[64]Global
Local
A* + DWAKey node selection strategy;MATLAB; Indoor.Safety;Vehicle in mine
transportation
Clamped-B spline;Smoother path;
Fuzzy control.Optimal path.
[65]Global LocalA* + DWA-IndoorShortest path;Mobile robot in
inspection
Smoothest path.
[66]Global LocalA* + DWAFloyd Algorithm;MATLAB; Indoor.Smoother path;Inspection robot in coal mine
B-Spline curves.Safer.
[67]GlobalVFH-A*Bezier interpolation;MATLAB;
Mine.
More efficient search;LHD in mining operation
Smooth path;
Fast calculation speed.
[68]Global
Local
Dijkstra-ACOMAKLINK lines.MineSmooth pathRobot in SAR
Shifting locally;
Symmetric polynomial curve.
[69]GlobalDijkstra-PSOPSO-based optimizationMATLABShorter path;Mine mapping and inspection
Safety.
[70]GlobalDijkstra3D Environment-based adaptationMATLABFeasible pathSurvey robot in mine exploration
[71]GlobalD*Danger-aware cost functionMATLABSafer path;Downhole robot in mine detection
Reduced planning time and cost.
[72]GlobalRRT*Vectorized map;Python Shorter path;LHD in mining operations
Optimal tree reconnection.Smoother path.
[73]GlobalRRT*Line cornerMATLAB;
Outdoor.
Smooth path;Robotic excavator loader
Better in narrow passages with tight turn;
[74]GlobalRRT-PRMFan-shaped goal orientation;MATLAB;
Indoor.
Higher success rate;Inspection robot in Mining
Adaptive step size expansion;Smoother path;
Third-order Bessel curve.Shorter path length.
[75]GlobalRRG 1Ray tracing method; GazeboShorter path;Mobile Robot in Mine rescue
Next-Best View.Fast calculation.
[76]GlobalACORetreat-punishment strategy;MATLABConsumes less
resources
Coal mine robot
Serial number and Cartesian
coordinate methods.
[77]LocalACOMembrane computingSimulationFaster convergence;Mobile robot
Better robustness.
[78]GlobalACO16-directional 24-neighbourhood ant search approach;MATLABImproved search efficiency;Rescue robot in Mine
Ant retreat strategy.U-shaped trap solution;
Shorter path.
[79]GlobalACOAnnealing algorithm;MATLABStrong in robustness;Mining robot in SAR
Entropy increase strategy.High convergence speed.
[80]Global
Local
ACO + TEBPheromone updating model;MATLAB;
Indoor.
Enhanced search capabilities;Drilling robot in mining rockburst
Faster convergence.
[81]GlobalBFA 2-PSA 3Metaheuristic optimizationMATLABFast convergence speed;Rescue robot in coal mine
Better Robustness
[82]Global
Local
AFSA 4 + DWAImproved genetic algorithmMATLAB;
Gazebo;
Indoor.
Shorter path;Patrol robot in mine safety inspection
Adaptive trajectory evaluation functionSmoother path.
[83]GlobalQLearning Even gray model;
Multi-attribute intelligent.
MATLABSmoother convergence;UGV in SAR
Shorter path;
[84]LocalSkeleton-BasedThinning algorithmMineHigh robustness;LHD in mining operation
Stable;
[85]LocalAPFVelocity and acceleration fields;MATLAB;
Indoor
Dynamic collision avoidance;Mobile robot in coal mine rescue
Global potential field line;
Genetic Trust Region AlgorithmEscape local minima.
1 Rapidly Random Graph; 2 Bacterial Foraging algorithm; 3 Polyclonal selection algorithm; 4 Artificial fish swam algorithm.
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

Abdukodirov, A.; Benndorf, J. Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment. Mining 2025, 5, 33. https://doi.org/10.3390/mining5020033

AMA Style

Abdukodirov A, Benndorf J. Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment. Mining. 2025; 5(2):33. https://doi.org/10.3390/mining5020033

Chicago/Turabian Style

Abdukodirov, Abdurauf, and Jörg Benndorf. 2025. "Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment" Mining 5, no. 2: 33. https://doi.org/10.3390/mining5020033

APA Style

Abdukodirov, A., & Benndorf, J. (2025). Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment. Mining, 5(2), 33. https://doi.org/10.3390/mining5020033

Article Metrics

Back to TopTop