Recent Developments in Path Planning for Unmanned Ground Vehicles in Underground Mining Environment
Abstract
1. Introduction
- 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].
- 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.
- 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.
2. Requirement Analysis and Methodological Basis for Path Planning in Underground Mining Environments
- 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].
- 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?
3. Materials
3.1. Sensors to Perceive the Environment
- LiDAR (Light Detection and Ranging);
- Depth Camera;
- Radar;
- IMUs (Inertial Measurement Units);
- Motor encoders.
3.2. ROS as Main Operating System
- 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].
- 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.
- 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.
- 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.
4. Path Planning Framework
4.1. Global Path Planning Algorithms
- 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
- 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].
4.3. Optimization Strategies in Underground Path Planning
- 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 is computed as shown in Equation (1):
- 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):
- 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.
- is the pheromone value on edge (i, j);
- is the evaporation rate (0 < < 1);
- is the amount of pheromone deposited, often defined by Equation (4):
5. Related Works on Underground Mining Path Planning with UGVs
6. Discussion
- 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.
- 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
- 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.
Author Contributions
Funding
Data Availability Statement
Conflicts of Interest
References
- 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]
- 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]
- Li, J.; Zhan, K. Intelligent Mining Technology for an Underground Metal Mine Based on Unmanned Equipment. Engineering 2018, 4, 381–391. [Google Scholar] [CrossRef]
- 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).
- 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]
- 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).
- 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]
- 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]
- Mäkelä, H. Overview of LHD Navigation without Artificial Beacons. Rob. Auton. Syst. 2001, 36, 21–35. [Google Scholar] [CrossRef]
- 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]
- Kim, H.; Choi, Y. Development of Autonomous Driving Patrol Robot for Improving Underground Mine Safety. Appl. Sci. 2023, 13, 3717. [Google Scholar] [CrossRef]
- 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]
- 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).
- 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]
- 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]
- 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]
- 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]
- 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).
- 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]
- 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]
- Nielsen, K. Robust LIDAR-Based Localization in Underground Mines; Linköping University Electronic Press: Linköping, Sweden, 2021; Volume 1906. [Google Scholar] [CrossRef]
- 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]
- 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]
- 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]
- 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).
- 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]
- 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).
- 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]
- Al-Batati, A.S.; Koubaa, A.; Abdelkader, M. ROS 2 in a Nutshell: A Survey. Preprints 2024. [CrossRef]
- 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).
- 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]
- 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]
- Thrun, S. Learning Metric-Topological Maps for Indoor Mobile Robot Navigation. Artif. Intell. 1998, 99, 21–71. [Google Scholar] [CrossRef]
- 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]
- 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]
- Javaid, M.A. Understanding Dijkstra Algorithm. SSRN Electron. J. 2013. [CrossRef]
- 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]
- 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]
- 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).
- 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]
- 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]
- 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).
- 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]
- 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]
- Sutton, R.S.; Barto, A.G. Reinforcement Learning: An Introduction, 2nd ed.; MIT Press: Cambridge, MA, USA, 2018. [Google Scholar]
- Watkins, C.J.C.H.; Dayan, P. Q-Learning. Mach. Learn. 1992, 8, 279–292. [Google Scholar] [CrossRef]
- 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]
- 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]
- 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]
- Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef]
- Khatib, O. Real-Time Obstacle Avoidance for Manipulators and Mobile Robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
- 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]
- 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]
- 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]
- 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]
- 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).
- 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]
- Thrun, S.; Burgard, W.; Fox, D. Probabilistic Robotics; MIT Press: Cambridge, MA, USA, 2005. [Google Scholar]
- 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]
- 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]
- 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]
- 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]
- 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).
- 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]
- 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]
- 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]
- 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]
- 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]
- 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]
- Chen, Z. Path Planning Method for Underground Survey Robot in Dangerous Scenarios. Highl. Sci. Eng. Technol. 2023, 43, 207–214. [Google Scholar] [CrossRef]
- 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]
- 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]
- 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).
- 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]
- 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).
- 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]
- 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]
- 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]
- 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]
- 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]
- 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).
- 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]
- 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]
- 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]
- 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]
Factors | Mine | Indoor | Outdoor |
---|---|---|---|
Surface Conditions | Irregular surfaces, narrow passages, and mud | Smooth and structured surfaces | Varied surfaces |
Obscurants | Dust, smoke, and gas | Nearly clear | Rain, fog, and snow |
GPS Availability | GPS denied | Available with extended setups | Widely available and effective |
Obstacle Density | Relatively high | Low | Moderate |
Requirements | Evaluation Criteria |
---|---|
Optimal path | Minimal travel time and path length |
Smoothness | Spatial and temporal smoothness coefficients [18] |
High accuracy and safety | Avoids obstacles and ensures collision-free path |
Success rate | Percentage of successful path completions |
Computational cost | Processing time and resource consumption |
Robustness | Ability to handle uncertainties |
Handling narrow tunnels | Minimum passable width |
Sensors | Strengths | Weaknesses | Range 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 lightweight | Can 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. |
Algorithms | Strength | Weakness |
---|---|---|
Dijkstra | Guarantees 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. | |
PRM | Reusable path for repeated queries; | Paths are not always smooth; |
Works well in large, open spaces. | Struggles with dynamic obstacles. | |
GA | Efficient in high-dimensional spaces; | Slow convergence; |
Works well with noisy data. | Sensitive to parameter selection. | |
PSO | Simple to implement; | Prone to local minima; |
Adaptive to dynamic environments. | Sensitive to parameter selection. | |
ACO | Good for multi-agent path planning; | Computationally intensive; |
Works in dynamic environments. | Slower convergence. | |
Q-Learning | Works with Partial Information; | Higher memory usage; |
Can Handle Complex Environments. | Slow convergence in large spaces. | |
DQN | Suitable for high-dimensional spaces; | Requires high computational power; |
Works with Partial Observability. | Sensitive to parameter selection. | |
DWA | Smooth and feasible paths; | Prone to local minima; |
Computationally lightweight. | Struggles with complex environment. | |
APF | Lightweight, fast obstacle avoidance; | Prone to local minima; |
Simple, best for reactive navigation. | Struggles with dynamic obstacles. | |
VFH | Efficient real-time obstacle avoidance; | Prone to local minima; |
Handles noisy sensor data well. | Oscillations in Narrow Spaces. | |
MPC | Optimizes performance; | Computationally intensive; |
Generates smooth and efficient paths. | Limited real-time application. | |
TEB | Generates smooth, time-optimal path; | Computationally intensive; |
Dynamic Obstacle Avoidance. | Sensitive to parameter selection. |
Author | Path Type | Basic Algorithms | Optimization Strategy | Test Field | Advantages | Application |
---|---|---|---|---|---|---|
[61] | Global | A* | Gaussian filtering method; | MATLAB | Safety; | LHD in mining transportation |
Quadratic programming method. | Smoother path. | |||||
[62] | Global | A* | Expanding nodes by articulation angle; | Indoor; C++. | Enhanced search efficiency; | LHD in mining transportation |
Collision threat cost. | Collision free. | |||||
[63] | Global Local | A* + APF | Exponential 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* + DWA | Key node selection strategy; | MATLAB; Indoor. | Safety; | Vehicle in mine transportation |
Clamped-B spline; | Smoother path; | |||||
Fuzzy control. | Optimal path. | |||||
[65] | Global Local | A* + DWA | - | Indoor | Shortest path; | Mobile robot in inspection |
Smoothest path. | ||||||
[66] | Global Local | A* + DWA | Floyd Algorithm; | MATLAB; Indoor. | Smoother path; | Inspection robot in coal mine |
B-Spline curves. | Safer. | |||||
[67] | Global | VFH-A* | Bezier interpolation; | MATLAB; Mine. | More efficient search; | LHD in mining operation |
Smooth path; | ||||||
Fast calculation speed. | ||||||
[68] | Global Local | Dijkstra-ACO | MAKLINK lines. | Mine | Smooth path | Robot in SAR |
Shifting locally; | ||||||
Symmetric polynomial curve. | ||||||
[69] | Global | Dijkstra-PSO | PSO-based optimization | MATLAB | Shorter path; | Mine mapping and inspection |
Safety. | ||||||
[70] | Global | Dijkstra | 3D Environment-based adaptation | MATLAB | Feasible path | Survey robot in mine exploration |
[71] | Global | D* | Danger-aware cost function | MATLAB | Safer path; | Downhole robot in mine detection |
Reduced planning time and cost. | ||||||
[72] | Global | RRT* | Vectorized map; | Python | Shorter path; | LHD in mining operations |
Optimal tree reconnection. | Smoother path. | |||||
[73] | Global | RRT* | Line corner | MATLAB; Outdoor. | Smooth path; | Robotic excavator loader |
Better in narrow passages with tight turn; | ||||||
[74] | Global | RRT-PRM | Fan-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] | Global | RRG 1 | Ray tracing method; | Gazebo | Shorter path; | Mobile Robot in Mine rescue |
Next-Best View. | Fast calculation. | |||||
[76] | Global | ACO | Retreat-punishment strategy; | MATLAB | Consumes less resources | Coal mine robot |
Serial number and Cartesian coordinate methods. | ||||||
[77] | Local | ACO | Membrane computing | Simulation | Faster convergence; | Mobile robot |
Better robustness. | ||||||
[78] | Global | ACO | 16-directional 24-neighbourhood ant search approach; | MATLAB | Improved search efficiency; | Rescue robot in Mine |
Ant retreat strategy. | U-shaped trap solution; | |||||
Shorter path. | ||||||
[79] | Global | ACO | Annealing algorithm; | MATLAB | Strong in robustness; | Mining robot in SAR |
Entropy increase strategy. | High convergence speed. | |||||
[80] | Global Local | ACO + TEB | Pheromone updating model; | MATLAB; Indoor. | Enhanced search capabilities; | Drilling robot in mining rockburst |
Faster convergence. | ||||||
[81] | Global | BFA 2-PSA 3 | Metaheuristic optimization | MATLAB | Fast convergence speed; | Rescue robot in coal mine |
Better Robustness | ||||||
[82] | Global Local | AFSA 4 + DWA | Improved genetic algorithm | MATLAB; Gazebo; Indoor. | Shorter path; | Patrol robot in mine safety inspection |
Adaptive trajectory evaluation function | Smoother path. | |||||
[83] | Global | QLearning | Even gray model; Multi-attribute intelligent. | MATLAB | Smoother convergence; | UGV in SAR |
Shorter path; | ||||||
[84] | Local | Skeleton-Based | Thinning algorithm | Mine | High robustness; | LHD in mining operation |
Stable; | ||||||
[85] | Local | APF | Velocity and acceleration fields; | MATLAB; Indoor | Dynamic collision avoidance; | Mobile robot in coal mine rescue |
Global potential field line; | ||||||
Genetic Trust Region Algorithm | Escape local minima. |
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).
Share and Cite
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
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 StyleAbdukodirov, 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 StyleAbdukodirov, 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