Hybrid Path Planning Algorithm for Autonomous Mobile Robots: A Comprehensive Review
Abstract
1. Introduction
2. Methodology
- ➢
- Graph-based algorithms: This section provides mathematical techniques for determining the shortest path from a start node to a goal node, suitable for a static environment with known obstacles. Algorithms include A*, Dijkstra, Breadth-First Search (BFS), Depth First Search (DFS), Floyd-Warshall, and Bellman-Ford algorithms. The pseudocode for graph-based algorithms is presented in Appendix A.
- ➢
- Sampling-based algorithms: This covers techniques that explore the configuration space by random sampling points and constructing a graph or tree structure to identify feasible paths. Algorithms such as Rapidly Exploring Random Tree (RRT), Probabilistic Road Map (PRM), Batch Informed Tree (BIT), and Single-Query Biased algorithms are analyzed. The pseudocode for PRM, RRT, and BIT algorithms is presented in Appendix A.
- ➢
- Reaction-based algorithms: This part focuses on strategies where robot motion is determined in response to real-time sensors or environmental changes. This includes Artificial Potential Fields (APF), Dynamic Window Approach (DWA), and Vector Field Approach (VFA).
- ➢
- Optimization-based algorithms: These approaches treat path planning as an optimization problem, computing trajectories that minimize a specific cost function while adhering to operational constraints. Algorithms like the Gradient Descent Algorithm (GDA), Ant Colony Optimization (ACO), Particle Swarm Optimization (PSO), and Genetic Algorithm (GA) are discussed.
3. Graph-Based Path Planning Algorithms
3.1. A* Algorithm
3.2. Dijkstra Algorithm
3.3. Breadth-First Search
3.4. Depth-First Search
3.5. Floyd-Warshall Algorithm
3.6. Bellman-Ford Algorithm
4. Sampling-Based Path Planning Algorithms
4.1. Rapidly Exploring Random Tree Algorithm
4.2. Probabilistic Roadmap Algorithm
4.3. Batch Informed Tree
4.4. Single-Query Biased
5. Reaction-Based Path Planning Algorithms
5.1. Artificial Potential Fields Algorithm
5.2. Dynamic Window Approach
5.3. Vector Field Approach
- ➢
- Attractive field: Directs the robot toward the designated goal.
- ➢
- Repulsive field: Emanates from obstacles, exerting a force that diverts the robot to avoid collisions.
6. Optimization-Based Algorithm
6.1. Gradient Descent Algorithm
6.2. Ant Colony Optimization Algorithm
6.3. Particle Swarm Optimization Algorithm
6.4. Genetic Algorithm
7. Hybrid Path Planning Algorithms
7.1. Hybrid Algorithms
7.1.1. Challenges in Path Planning
7.1.2. Search Acceleration
7.1.3. Dynamic Adaptation
7.1.4. Probabilistic Approach
7.1.5. Trajectory Smoothness
7.1.6. Real-Time Adaptability and Energy Optimization
- AI-Driven Hybrid Algorithms:
- Transformer-Based Hybrid Algorithms:
- Cooperative Multi-Agent Hybrid Algorithm:
7.2. Applications of Hybrid Path Planning Algorithms
- ➢
- ➢
- Autonomous driving system: Meta-heuristic optimization methods are widely adopted for their effectiveness in addressing complex and high-dimensional PP problems. ML and DL methods are increasingly favored due to their adaptive learning capabilities and rapid decision-making in dynamic environments [26].
- ➢
- ➢
- Multi-Robot path planning: The hybridisation of the Sine-Cosine algorithm, which was inspired by the Kidney, was employed for Multi-Robot PP [140]. For multi-robot PP in a cluttered environment, a hybrid improved PSO-DV (Dynamic Vortex) algorithm was employed [141]. A novel hybrid optimization approach based on the Cuckoo Search –Adaptive Neuro-Fuzzy Inference System (CS-ANFIS) methodology was used for multiple mobile robot navigation [142].
- ➢
- Warehouse Automation: Combining PSO with simulated annealing (SA) (PSO-SA) improves navigation in warehouses and traffic flow management in AGV systems [143].
- ➢
- ➢
- Agriculture and Industrial Automation: Improves automated harvesting and robotic pollination in farming [144]. Utilized by warehouse robots to enhance the efficiency of storage and retrieval paths.
7.3. Advantages of Hybrid Path Planning Algorithms
- ➢
- Improved Efficiency and Speed: Integrates global planning for optimal route selection with local planning for real-time obstacle avoidance, thereby minimizing the overall computational burden.
- ➢
- Optimized Resource Utilization: Reduces energy usage and travel expenses, making it perfect for drones, self-driving cars, and industrial uses.
- ➢
- Enhanced Safety and Reliability: Minimizes collision risks and facilitates smooth trajectory planning in high-risk environments.
8. Discussion
9. Limitations and Future Directions in Hybrid Path Planning
- Environmental challenges:
- ➢
- Dynamic and Uncertain Environments: AMRs frequently operate in settings characterized by unpredictable obstacles, varying terrains, and moving entities. Ensuring safe and efficient navigation requires PP algorithms capable of rapidly adapting to these dynamic conditions, including sudden changes in obstacle positions and unexpected terrain variations.
- ➢
- Limited sensor range and accuracy: Although advanced sensors such as LiDAR, RGB-D cameras, and GPS provide continuous environmental feedback, their inherent noise, resolution limits, and susceptibility to environmental interference can lead to localization errors. These inaccuracies can propagate through the planning process, compromising the reliability and safety of navigation.
- Computational Challenges
- ➢
- High computational cost: Real-time PP requires identifying optimal routes while simultaneously minimizing costs such as path distance, number of nodes visited, energy usage, and computational cost. In densely populated environments, particularly in multi-robot systems, the computational cost escalates, demanding high processing power and efficient algorithmic solutions.
- ➢
- Local minima issues in heuristic algorithms: Many traditional and heuristic-based approaches, especially in environments with narrow or cluttered configurations, are prone to becoming trapped in local minima. This can result in suboptimal or even infeasible paths, reducing operational efficiency.
- ➢
- Energy efficiency and Resource constraints: For battery-powered AMRs, energy-efficient PP is critical. Algorithms must balance navigation efficiency with the conservation of onboard energy resources to maximize operational endurance without compromising safety or task competition.
- Future Work
- ➢
- Developing adaptive hybrid algorithms that integrate learning absed and optimization-driven methods to enhance real-time responsiveness.
- ➢
- Leveraging sensor fusion and advanced filtering techniques to mitigate localization errors.
- ➢
- Incorporating predictive modeling for dynamic obstacle trajectories to enhance safety in uncertain environments.
- ➢
- Designing energy-aware planning frameworks that consider battery state and mission-critical constraints in real time.
- ➢
- Future research is expected to focus on several critical directions, including the integration of AI-driven adaptive systems, collaborative multi-robot coordination, and cloud robotics for scalable data sharing and decision-making. Moreover, establishing standardized frameworks for interoperability and benchmarking will be essential for broader deployment.
- ➢
- Such advancements will significantly improve the robustness, adaptability, and operational efficiency of AMRs, enabling their deployment in increasingly complex and dynamic environments.
10. Conclusions
Author Contributions
Funding
Data Availability Statement
Conflicts of Interest
Appendix A
- Graph-based algorithms:
- A* Search [145]
- Mathematical model
- f(n) = g(n) + h(n)
- g(n): The actual cost from the start node to the current node.
- h(n): The estimated cost from the current node to the goal.
- For example, if it needs to be modified to weighted A*. This formula will be converted into
- f(n) = g(n) + w * h(n)
- w: weight to the heuristic function
- Pseudocode
- A_STAR(G, w, s, t, h):
- for v in V: g[v] ← +∞; parent[v] ← NIL
- g[s] ← 0
- OPEN ← priority-queue by f[v] = g[v] + h(v)
- PUSH (OPEN, s)
- CLOSED ← ∅
- while OPEN not empty:
- u ← EXTRACT-MIN(OPEN) // by f
- if u = t: return RECONSTRUCT (parent, t)
- add u to CLOSED
- for each (u, v) in E:
- tentative ← g[u] + w(u, v)
- if v ∈ CLOSED and tentative ≥ g[v]: continue
- if tentative < g[v]:
- parent[v] ← u
- g[v] ← tentative
- if v not in OPEN: PUSH(OPEN, v) else DECREASE-KEY(OPEN, v, g[v] + h(v))
- return “no path”
- Dijkstra’s Algorithm [146]
- Mathematical model
- Greedy relaxation under invariant:
- When a vertex u is extracted, d(u) = δ(s,u) (true shortest distance).
- Relaxation step for edge (u,v):
- d(v)←min
- Pseudocode
- DIJKSTRA(G, w, s):
- for v in V: d[v] ← +∞; parent[v] ← NIL
- d[s] ← 0
- Q ← priority-queue keyed by d[·] with all vertices
- while Q not empty:
- u ← EXTRACT-MIN(Q)
- for each (u, v) in E:
- if d[v] > d[u] + w(u, v):
- d[v] ← d[u] + w(u, v)
- parent[v] ← u
- DECREASE-KEY(Q, v, d[v])
- return d, parent
- Breadth-First Search (BFS) [147]
- Pseudocode
- BFS(G, s):
- for v in V: d[v] ← +∞; parent[v] ← NIL
- d[s] ← 0
- Q ← queue; ENQUEUE(Q, s)
- while Q not empty:
- u ← DEQUEUE(Q)
- for each (u, v) in E:
- if d[v] = +∞:
- d[v] ← d[u] + 1
- parent[v] ← u
- ENQUEUE(Q, v)
- return d, parent
- Floyd-Warshall [148]
- Mathematical model
- D(0)[i,j] = w(i,j) (or +∞, 0 on diagonal)
- D(k)[i,j] = min(D(k−1)[i,j], D(k−1)[i,k] + D(k−1)[k,j]).
- Pseudocode
- FLOYD_WARSHALL(W): // W is n×n, W[i][i] = 0; +∞ if no edge
- D ← W
- for k in 1..n:
- for i in 1..n:
- for j in 1..n:
- if D[i][j] > D[i][k] + D[k][j]:
- D[i][j] ← D[i][k] + D[k][j]
- return D
- Depth-First Search (DFS) [149]
- Pseudocode
- DFS(G):
- for v in V: color[v] ← WHITE; parent[v] ← NIL
- time ← 0
- for v in V:
- if color[v] = WHITE: DFS_VISIT(v)
- DFS_VISIT(u):
- color[u] ← GRAY; time ← time + 1; d[u] ← time
- for each (u, v) in E:
- if color[v] = WHITE:
- parent[v] ← u
- DFS_VISIT(v)
- color[u] ← BLACK; time ← time + 1; f[u] ← time
- Bellman–Ford [150]
- Pseudocode
- BELLMAN_FORD(G, w, s):
- for v in V: d[v] ← +∞; parent[v] ← NIL
- d[s] ← 0
- for i in 1..(n − 1):
- updated ← false
- for each (u, v) in E:
- if d[u] + w(u,v) < d[v]:
- d[v] ← d[u] + w(u,v)
- parent[v] ← u
- updated ← true
- if not updated: break
- // detect negative cycle
- for each (u, v) in E:
- if d[u] + w(u,v) < d[v]: return “negative cycle”
- return d, parent
- Sampling-based algorithms:
- Probabilistic Roadmap (PRM) [151]
- Pseudocode
- PRM (G, N_samples, k or r):
- V ← ∅; E ← ∅
- for i = 1 to N_samples:
- q ← SAMPLE_C_FREE()
- V ← V ∪ [151]
- for each q in V:
- neighbors ← NEAR (V, q, k or radius r)
- for each q’ in neighbors:
- if LocalPlan (q, q’):
- E ← E ∪ [152]
- add start, goal to V; connect to neighbors similarly
- return graph (V, E)
- PRM_QUERY (graph, start, goal):
- return SHORTEST_PATH (graph, start, goal)
- Rapidly Exploring Random Tree (RRT) [153]
- Pseudocode
- RRT(q_init, K, Δq):
- V ← (q_init)c; E ← ∅
- for k = 1 to K:
- q_rand ← SAMPLE_C_FREE()
- q_near ← NEAREST(V, q_rand)
- q_new ← STEER(q_near, q_rand, Δq)
- if LocalPlan(q_near, q_new):
- V ← V ∪ (q_new)
- E ← E ∪ [(q_near, q_new)]
- return (V, E)
- Batch Informed Trees (BIT) [56]
- Pseudocode
- BIT*(start, goal, batch_size, heuristic h):
- initialize tree T with start
- best_cost ← ∞
- while time remains:
- S_batch ← SAMPLE_BATCH(batch_size)
- build implicit RGG over existing vertices + S_batch
- E_queue ← PRIORITIZE_EDGES_BY_ESTIMATED_COST()
- while E_queue not empty and first estimate < best_cost:
- extract edge (u, v), evaluate true cost via LocalPlan
- if cost + g(u) + h(v) < best_cost:
- add/update edge in T, update costs and best_cost
- prune nodes with cost + h ≥ best_cost
- return best path in T
References
- Zhang, S.; Tang, W.; Li, P.; Zha, F. Mapless Path Planning for Mobile Robot Based on Improved Deep Deterministic Policy Gradient Algorithm. Sensors 2024, 24, 5667. [Google Scholar] [CrossRef]
- Sreerag, S.; Lekshmi, R.R. Allocation of Medicine Dispensing Mobile Robot Considering Path Plan and Battery SoC. In Proceedings of the 2024 IEEE International Conference on Interdisciplinary Approaches in Technology and Management for Social Innovation (IATMSI), Gwalior, India, 14–16 March 2024; pp. 1–6. [Google Scholar]
- Ajeil, F.H.; Ibraheem, I.K.; Sahib, M.A.; Humaidi, A.J. Multi-objective path planning of an autonomous mobile robot using hybrid PSO-MFB optimization algorithm. Appl. Soft Comput. J. 2020, 89, 106076. [Google Scholar] [CrossRef]
- Mohanraj, T.; Dinesh, T.; Guruchandhramavli, B.; Sanjai, S.; Sheshadhri, B. Mobile robot path planning and obstacle avoidance using hybrid algorithm. Int. J. Inf. Technol. 2023, 15, 4481–4490. [Google Scholar] [CrossRef]
- Pudugosula, H.; Kochuvila, S. Path Planning of Robots Using Classical Reinforcement Learning Approach. In Proceedings of the 2024 First International Conference on Innovations in Communications, Electrical and Computer Engineering (ICICEC), Davangere, India, 24–25 October 2024; pp. 1–6. [Google Scholar]
- Yan, Y. Research on the A Star Algorithm for Finding Shortest Path. Highlights Sci. Eng. Technol. 2023, 46, 154–161. [Google Scholar] [CrossRef]
- Duchoň, F.; Babinec, A.; Kajan, M.; Beňo, P.; Florek, M.; Fico, T.; Jurišica, L. Path Planning with Modified a Star Algorithm for a Mobile Robot. Procedia Eng. 2014, 96, 59–69. [Google Scholar] [CrossRef]
- Wang, C.; Wang, L.; Qin, J.; Wu, Z.; Duan, L.; Li, Z.; Cao, M.; Ou, X.; Su, X.; Li, W.; et al. Path planning of automated guided vehicles based on improved A-Star algorithm. In Proceedings of the 2015 IEEE International Conference on Information and Automation, Lijiang, China, 8–10 August 2015; pp. 2071–2076. [Google Scholar]
- Wang, D.; Liu, Q.; Yang, J.; Huang, D. Research on path planning for intelligent mobile robots based on improved A* algorithm. Symmetry 2024, 16, 1311. [Google Scholar] [CrossRef]
- Xu, X.; Zeng, J.; Zhao, Y.; Lü, X. Research on global path planning algorithm for mobile robots based on improved A. Expert Syst. Appl. 2024, 243, 122922. [Google Scholar] [CrossRef]
- Liu, Y.; Wang, C.; Wu, H.; Wei, Y. Mobile robot path planning based on kinematically constrained A-star algorithm and DWA fusion algorithm. Mathematics 2023, 11, 4552. [Google Scholar] [CrossRef]
- Li, Y.; Jin, R.; Xu, X.; Qian, Y.; Wang, H.; Xu, S.; Wang, Z. A mobile robot path planning algorithm based on improved A* algorithm and dynamic window approach. IEEE Access 2022, 10, 57736–57747. [Google Scholar] [CrossRef]
- Shu-Xi, W. The improved dijkstra’s shortest path algorithm and its application. Procedia Engineering 2012, 29, 1186–1190. [Google Scholar] [CrossRef]
- Verma, D.; Messon, D.; Rastogi, M.; Singh, A. Comparative Study of Various Approaches of Dijkstra Algorithm. In Proceedings of the 2021 International Conference on Computing, Communication, and Intelligent Systems (ICCCIS), Greater Noida, India, 19–20 February 2021; pp. 328–336. [Google Scholar]
- Ubaidillah, A.; Sukri, H. Application of Odometry and Dijkstra algorithm as navigation and shortest path determination system of warehouse mobile robot. J. Robot. Control (JRC) 2023, 4, 413–423. [Google Scholar] [CrossRef]
- Li, F.-F.; Du, Y.; Jia, K.-J. Path planning and smoothing of mobile robot based on improved artificial fish swarm algorithm. Sci. Rep. 2022, 12, 659. [Google Scholar] [CrossRef] [PubMed]
- Shaposhnikova, S.; Omelian, D. Towards effective strategies for mobile robot using reinforcement learning and graph algorithms. Autom. Technol. Bus. Process. 2023, 15, 24–34. [Google Scholar] [CrossRef]
- Beamer, S.; Asanovic, K.; Patterson, D. Direction-optimizing Breadth-First Search. In Proceedings of the SC ‘12: Proceedings of the International Conference on High Performance Computing, Networking, Storage and Analysis, Salt Lake City, UT, USA, 10–16 November 2012; pp. 137–148. [Google Scholar]
- Liu, W.; Hu, J.; Zhang, H.; Wang, M.Y.; Xiong, Z. A novel graph-based motion planner of multi-mobile robot systems with formation and obstacle constraints. IEEE Trans. Robot. 2023, 40, 714–728. [Google Scholar] [CrossRef]
- Biju, A.; Gayathri, M.P.; Jayapandian, N.; Chris, A.; Thaleeparambil, N.R. Efficient Pathfinding in a Maze to overcome Challenges in Robotics and AI Using Breadth-First Search. In Proceedings of the 2025 IEEE 14th International Conference on Communication Systems and Network Technologies (CSNT), Bhopal, India, 7–9 March 2025; pp. 727–732. [Google Scholar]
- Li, Q.; Xie, F.; Zhao, J.; Xu, B.; Yang, J.; Liu, X.; Suo, H. FPS: Fast path planner algorithm based on sparse visibility graph and bidirectional breadth-first search. Remote Sens. 2022, 14, 3720. [Google Scholar] [CrossRef]
- Abd Rahman, N.A.; Sahari, K.S.M.; Hamid, N.A.; Hou, Y.C. A coverage path planning approach for autonomous radiation mapping with a mobile robot. Int. J. Adv. Robot. Syst. 2022, 19, 17298806221116483. [Google Scholar] [CrossRef]
- Deng, X.; Jiao, T.; Qin, X.; Wang, Y.; Zheng, Q.; Hou, Z.; Zhen, Y.; Li, W. Radiation Mapping based on DFS and Gaussian Process Regression. In Proceedings of the 2024 4th URSI Atlantic Radio Science Meeting (AT-RASC), Meloneras, Spain, 19–24 May 2024; pp. 1–3. [Google Scholar]
- Han, Z.; Sun, H.; Huang, J.; Xu, J.; Tang, Y.; Liu, X. Path planning algorithms for smart parking: Review and prospects. World Electr. Veh. J. 2024, 15, 322. [Google Scholar] [CrossRef]
- Zhou, X.; Zheng, W.; Li, Z.; Wu, P.; Sun, Y. Improving path planning efficiency for underwater gravity-aided navigation based on a new depth sorting fast search algorithm. Def. Technol. 2024, 32, 285–296. [Google Scholar] [CrossRef]
- Reda, M.; Onsy, A.; Haikal, A.Y.; Ghanbari, A. Path planning algorithms in the autonomous driving system: A comprehensive review. Robot. Auton. Syst. 2024, 174, 104630. [Google Scholar] [CrossRef]
- Champagne Gareau, J.; Beaudry, É.; Makarenkov, V. Fast and optimal branch-and-bound planner for the grid-based coverage path planning problem based on an admissible heuristic function. Front. Robot. AI 2023, 9, 1076897. [Google Scholar] [CrossRef]
- Nordin, N.A.; Shariff, S.S.; Supadi, S.S.; Masudin, I. Modelling the Shortest Path for Inner Warehouse Travelling Using the Floyd–Warshall Algorithm. Mathematics 2024, 12, 2698. [Google Scholar] [CrossRef]
- Habib, S.; Majeed, A.; Akram, M.; Al-shamiri, M. Floyd-Warshall Algorithm Based on Picture Fuzzy Information. Comput. Model. Eng. Sci. 2023, 136, 2873–2894. [Google Scholar] [CrossRef]
- NageswaraGuptha, M.N. Autonomous UAV object Avoidance with Floyd-warshall differential evolution approach. Intel. Artif. 2022, 25, 77–94. [Google Scholar] [CrossRef]
- Zhang, X.; Ji, Y.; Wang, C.; Lin, H.; Wang, Y. Path planning of inspection robot based on improved intelligent water drop algorithm. IEEE Access 2023, 11, 119993–120000. [Google Scholar] [CrossRef]
- Wang, L.; Wang, H.; Yang, X.; Gao, Y.; Cui, X.; Wang, B. Research on smooth path planning method based on improved ant colony algorithm optimized by Floyd algorithm. Front. Neurorobotics 2022, 16, 955179. [Google Scholar] [CrossRef]
- Katona, K.; Neamah, H.A.; Korondi, P. Obstacle Avoidance and Path Planning Methods for Autonomous Navigation of Mobile Robot. Sensors 2024, 24, 3573. [Google Scholar] [CrossRef]
- Pak, J.; Kim, J.; Park, Y.; Son, H.I. Field Evaluation of Path-Planning Algorithms for Autonomous Mobile Robot in Smart Farms. IEEE Access 2022, 10, 60253–60266. [Google Scholar] [CrossRef]
- Bhat, R.; Rao, P.K.; Kamath, C.R.; Tandon, V.; Vizzapu, P. Comparative analysis of Bellman-Ford and Dijkstra’s algorithms for optimal evacuation route planning in multi-floor buildings. Cogent Eng. 2024, 11, 2319394. [Google Scholar] [CrossRef]
- Alamoudi, O.; Al-Hashimi, M. On the Energy Behaviors of the Bellman–Ford and Dijkstra Algorithms: A Detailed Empirical Study. J. Sens. Actuator Netw. 2024, 13, 67. [Google Scholar] [CrossRef]
- Li, X.; Tong, Y. Path planning of a mobile robot based on the improved RRT algorithm. Appl. Sci. 2023, 14, 25. [Google Scholar] [CrossRef]
- Hao, K.; Yang, Y.; Li, Z.; Liu, Y.; Zhao, X. CERRT: A mobile robot path planning algorithm based on RRT in complex environments. Appl. Sci. 2023, 13, 9666. [Google Scholar] [CrossRef]
- Varricchio, V.; Chaudhari, P.; Frazzoli, E. Sampling-based algorithms for optimal motion planning using process algebra specifications. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; pp. 5326–5332. [Google Scholar]
- Wang, J.; Zheng, E. Path planning of a mobile robot based on the improved rapidly exploring random trees star algorithm. Electronics 2024, 13, 2340. [Google Scholar] [CrossRef]
- Ayalew, W.; Menebo, M.; Merga, C.; Negash, L. Optimal path planning using bidirectional rapidly-exploring random tree star-dynamic window approach (BRRT*-DWA) with adaptive Monte Carlo localization (AMCL) for mobile robot. Eng. Res. Express 2024, 6, 035212. [Google Scholar] [CrossRef]
- Muhsen, D.K.; Sadiq, A.T.; Raheem, F.A. Memorized rapidly exploring random tree optimization (mrrto): An enhanced algorithm for robot path planning. Cybern. Inf. Technol. 2024, 24, 190–204. [Google Scholar] [CrossRef]
- Zhu, L.; Duan, P.; Meng, L.; Yang, X. GAO-RRT*: A path planning algorithm for mobile robot with low path cost and fast convergence. AIMS Math. 2024, 9, 12011–12042. [Google Scholar] [CrossRef]
- Qiao, L.; Luo, X.; Luo, Q. An Optimized Probabilistic Roadmap Algorithm for Path Planning of Mobile Robots in Complex Environments with Narrow Channels. Sensors 2022, 22, 8983. [Google Scholar] [CrossRef]
- Alarabi, S.; Luo, C.; Santora, M. A PRM Approach to Path Planning with Obstacle Avoidance of an Autonomous Robot. In Proceedings of the 2022 8th International Conference on Automation, Robotics and Applications (ICARA), Prague, Czech Republic, 18–20 February 2022; pp. 76–80. [Google Scholar]
- Sabeeh, S.; Sabri, I. Efficient Path Planning in Medical Environments: Integrating Genetic Algorithm and Probabilistic Roadmap (GA-PRM) for Autonomous Robotics. Iraqi J. Electr. Electron. Eng. 2024, 20, 243–258. [Google Scholar] [CrossRef]
- Stone, R.F.; Wang, J.; Sha, Z. Risk-Bounded and Probabilistic Roadmap-Based Motion Planner for Arbitrarily Shaped Robots With Uncertainty. J. Comput. Inf. Sci. Eng. 2025, 25, 081002. [Google Scholar] [CrossRef]
- Al-Kamil, S.J.; Szabolcsi, R. Optimizing path planning in mobile robot systems using motion capture technology. Results Eng. 2024, 22, 102043. [Google Scholar] [CrossRef]
- Deshpande, S.V.; Harikrishnan, R.; Walambe, R. POMDP-based probabilistic decision making for path planning in wheeled mobile robot. Cogn. Robot. 2024, 4, 104–115. [Google Scholar] [CrossRef]
- Ayawli, B.B.K.; Dawson, J.K.; Badu, E.; Ayawli, I.E.B.; Lamusah, D. Comparative analysis of popular mobile robot roadmap path-planning methods. Robotica 2025, 43, 1548–1571. [Google Scholar] [CrossRef]
- Swedeen, J.; Droge, G. Batch Informed Trees (BIT*). arXiv 2023, arXiv:2302.11670. [Google Scholar] [CrossRef]
- Kobilarov, M. Cross-entropy motion planning. Int. J. Robot. Res. 2012, 31, 855–871. [Google Scholar] [CrossRef]
- Wang, H.; Wang, W.; Shen, Y.; Li, K.; Zhang, Q.; Zheng, T. A Kinematic Constrained Batch Informed Trees algorithm with varied density sampling for mobile robot path planning. IEEE Robot. Autom. Lett. 2025, 10, 6912–6919. [Google Scholar] [CrossRef]
- Gammell, J.D.; Barfoot, T.D.; Srinivasa, S.S. Batch informed trees (bit*): Informed asymptotically optimal anytime search. Int. J. Robot. Res. 2020, 39, 543–567. [Google Scholar] [CrossRef]
- Zhang, L.; Bing, Z.; Chen, K.; Chen, L.; Cai, K.; Zhang, Y.; Wu, F.; Krumbholz, P.; Yuan, Z.; Haddadin, S. Flexible informed trees (FIT*): Adaptive batch-size approach in informed sampling-based path planning. In Proceedings of the 2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Abu Dhabi, United Arab Emirates, 14–18 October 2024; pp. 3146–3152. [Google Scholar]
- Gammell, J.D.; Srinivasa, S.S.; Barfoot, T.D. BIT*: Sampling-based optimal planning via batch informed trees. In Proceedings of the The Information-Based Grasp and Manipulation Planning Workshop, Robotics: Science and Systems (RSS), Berkeley, CA, USA, 12–13 July 2014. [Google Scholar]
- Hsu, D.; Latombe, J.-C.; Kurniawati, H. On the Probabilistic Foundations of Probabilistic Roadmap Planning. Int. J. Robot. Res. 2006, 25, 627–643. [Google Scholar] [CrossRef]
- Bruce, J.; Veloso, M. Real-time randomized path planning for robot navigation. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Lausanne, Switzerland, 30 September–4 October 2002; Volume 2383, pp. 2383–2388. [Google Scholar]
- Wu, D.; Wei, L.; Wang, G.; Tian, L.; Dai, G. APF-IRRT*: An Improved Informed Rapidly-Exploring Random Trees-Star Algorithm by Introducing Artificial Potential Field Method for Mobile Robot Path Planning. Appl. Sci. 2022, 12, 10905. [Google Scholar] [CrossRef]
- Sivaranjani, A.; Vinod, B. Artificial Potential Field Incorporated Deep-Q-Network Algorithm for Mobile Robot Path Prediction. Intell. Autom. Soft Comput. 2023, 35, 1135–1150. [Google Scholar] [CrossRef]
- Siming, W.; Tiantian, Z.; Weijie, L. Mobile Robot Path Planning Based on Improved Artificial Potential Field Method. In Proceedings of the 2018 IEEE International Conference of Intelligent Robotic and Control Engineering (IRCE), Lanzhou, China, 24–27 August 2018; pp. 29–33. [Google Scholar]
- Wu, Z.; Dai, J.; Jiang, B.; Karimi, H.R. Robot path planning based on artificial potential field with deterministic annealing. ISA Trans. 2023, 138, 74–87. [Google Scholar] [CrossRef]
- Szczepanski, R. Safe artificial potential field-novel local path planning algorithm maintaining safe distance from obstacles. IEEE Robot. Autom. Lett. 2023, 8, 4823–4830. [Google Scholar] [CrossRef]
- Yang, C.; Pan, J.; Wei, K.; Lu, M.; Jia, S. A novel unmanned surface vehicle path-planning algorithm based on A* and artificial potential field in ocean currents. J. Mar. Sci. Eng. 2024, 12, 285. [Google Scholar] [CrossRef]
- Shan, S.; Shao, J.; Zhang, H.; Xie, S.; Sun, F. Research and validation of self-driving path planning algorithm based on optimized A*-artificial potential field method. IEEE Sens. J. 2024, 24, 24708–24722. [Google Scholar] [CrossRef]
- Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. Robot. Autom. Mag. IEEE 1997, 4, 23–33. [Google Scholar] [CrossRef]
- Kuderer, M.; Gulati, S.; Burgard, W. Learning driving styles for autonomous vehicles from demonstration. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, DC, USA, 26–30 May 2015; pp. 2641–2646. [Google Scholar]
- Khatib, O. Real-time obstacle avoidance for manipulators and mobile robots. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation, St. Louis, MO, USA, 25–28 March 1985; pp. 500–505. [Google Scholar]
- Lin, Z.; Taguchi, R. Faster implementation of the dynamic window approach based on non-discrete path representation. Mathematics 2023, 11, 4424. [Google Scholar] [CrossRef]
- Yasuda, S.; Kumagai, T.; Yoshida, H. Safe and efficient dynamic window approach for differential mobile robots with stochastic dynamics using deterministic sampling. IEEE Robot. Autom. Lett. 2023, 8, 2614–2621. [Google Scholar] [CrossRef]
- Dobrevski, M.; Skočaj, D. Dynamic adaptive dynamic window approach. IEEE Trans. Robot. 2024, 40, 3068–3081. [Google Scholar] [CrossRef]
- Borroni, C.G.; Cazzaro, M.; Chiodini, P.M. The Dynamic Window Approach as a Tool to Improve Performance of Nonparametric Self-Starting Control Charts. Mathematics 2025, 13, 938. [Google Scholar] [CrossRef]
- Kapitanyuk, Y.A.; Proskurnikov, A.V.; Cao, M. A Guiding Vector-Field Algorithm for Path-Following Control of Nonholonomic Mobile Robots. IEEE Trans. Control Syst. Technol. 2018, 26, 1372–1385. [Google Scholar] [CrossRef]
- Boroujeni, Z.; Mohammadi, M.; Neumann, D.; Goehring, D.; Rojas, R. Autonomous Car Navigation Using Vector Fields. In Proceedings of the 2018 IEEE Intelligent Vehicles Symposium (IV), Suzhou, China, 26–30 June 2018; pp. 794–799. [Google Scholar]
- Jogeshwar, B.K.; Lochan, K. Algorithms for Path Planning on Mobile Robots. IFAC-PapersOnLine 2022, 55, 94–100. [Google Scholar] [CrossRef]
- Chen, X.; Gan, Y.; Xiong, S. Optimization of Mobile Robot Delivery System Based on Deep Learning. J. Comput. Sci. Res. 2024, 6, 51–65. [Google Scholar] [CrossRef]
- Dorigo, M.; Gambardella, L.M. Ant colonies for the travelling salesman problem. Biosystems 1997, 43, 73–81. [Google Scholar] [CrossRef]
- Li, D.; Wang, L.; Cai, J.; Ma, K.; Tan, T. Research on Terminal Distance Index-Based Multi-Step Ant Colony Optimization for Mobile Robot Path Planning. IEEE Trans. Autom. Sci. Eng. 2023, 20, 2321–2337. [Google Scholar] [CrossRef]
- Pu, X.; Song, X.; Tan, L.; Zhang, Y. Improved ant colony algorithm in path planning of a single robot and multi-robots with multi-objective. Evol. Intell. 2024, 17, 1313–1326. [Google Scholar] [CrossRef]
- Li, P.; Wei, L.; Wu, D. An Intelligently Enhanced Ant Colony Optimization Algorithm for Global Path Planning of Mobile Robots in Engineering Applications. Sensors 2025, 25, 1326. [Google Scholar] [CrossRef] [PubMed]
- Tao, B.; Kim, J.-H. Mobile robot path planning based on bi-population particle swarm optimization with random perturbation strategy. J. King Saud. Univ.-Comput. Inf. Sci. 2024, 36, 101974. [Google Scholar] [CrossRef]
- Xu, L.; Cao, M.; Song, B. A new approach to smooth path planning of mobile robot based on quartic Bezier transition curve and improved PSO algorithm. Neurocomputing 2022, 473, 98–106. [Google Scholar] [CrossRef]
- Pandey, K.K.; Kumbhar, C.; Parhi, D.R.; Mathivanan, S.K.; Jayagopal, P.; Haque, A. Trajectory Planning and Collision Control of a Mobile Robot: A Penalty-Based PSO Approach. Math. Probl. Eng. 2023, 2023, 1040461. [Google Scholar] [CrossRef]
- Lamini, C.; Benhlima, S.; Elbekri, A. Genetic Algorithm Based Approach for Autonomous Mobile Robot Path Planning. Procedia Comput. Sci. 2018, 127, 180–189. [Google Scholar] [CrossRef]
- Yang, C.; Zhang, T.; Pan, X.; Hu, M. Multi-objective mobile robot path planning algorithm based on adaptive genetic algorithm. In Proceedings of the 2019 Chinese Control Conference (CCC), Guangzhou, China, 27–30 July 2019; pp. 4460–4466. [Google Scholar]
- Yang, J.; Kang, M.; Lee, S.; Kim, S. Hybrid A*-Guided Model Predictive Path Integral Control for Robust Navigation in Rough Terrains. Mathematics 2025, 13, 810. [Google Scholar] [CrossRef]
- Wang, D.; Zhao, Z.; Yu, L.; Zhang, J.; Lian, J.; Wu, F. A Hybrid Multi-objective Heuristic Algorithm for Automated Guided Vehicle Path Planning. In Proceedings of the 2024 43rd Chinese Control Conference (CCC), Kunming, China, 28–31 July 2024; pp. 4778–4783. [Google Scholar]
- Dai, X.; Liu, C.; Lai, Q.; Huang, X.; Zeng, Q.; Liu, M. The Local Path Planning Algorithm for Amphibious Robots Based on an Improved Dynamic Window Approach. J. Mar. Sci. Eng. 2025, 13, 399. [Google Scholar] [CrossRef]
- Baek, Y.; Park, J.K. Fast Path Generation Algorithm for Mobile Robot Navigation Using Hybrid Map. Appl. Sci. 2025, 15, 2414. [Google Scholar] [CrossRef]
- Ren, L.; Kang, Y.; Yang, L.; Jia, H.; Wang, S. Optimization Algorithm for 3D Smooth Path of Robotic Arm in Dynamic Obstacle Environments. Appl. Sci. 2025, 15, 2116. [Google Scholar] [CrossRef]
- Sánchez-Ibáñez, J.R.; Pérez-del-Pulgar, C.J.; García-Cerezo, A. Path Planning for Autonomous Mobile Robots: A Review. Sensors 2021, 21, 7898. [Google Scholar] [CrossRef] [PubMed]
- Lin, P.; Yang, J.H.; Quan, Y.S.; Chung, C.C. Potential field-based path planning for emergency collision avoidance with a clothoid curve in waypoint tracking. Asian J. Control 2022, 24, 1074–1087. [Google Scholar] [CrossRef]
- Li, H.; Lu, Y.; Li, Y.; Zheng, S.; Sun, C.; Zhang, J.; Liu, L. Optimization of Model Predictive Control for Autonomous Vehicles Through Learning-Based Weight Adjustment. IEEE Trans. Intell. Transp. Syst. 2024, 1–12. [Google Scholar] [CrossRef]
- Bai, Y.; Kotpalliwar, S.; Kanellakis, C.; Nikolakopoulos, G. Multi-agent Path Planning Based on Conflict-Based Search (CBS) Variations for Heterogeneous Robots. J. Intell. Robot. Syst. 2025, 111, 26. [Google Scholar] [CrossRef]
- LaValle, S.M.; Kuffner, J.J. Randomized Kinodynamic Planning. Int. J. Robot. Res. 2001, 20, 378–400. [Google Scholar] [CrossRef]
- Chen, H.; Zang, X.; Zhu, Y.; Zhao, J. Hybrid Sampling-Based Path Planning for Mobile Manipulators Performing Pick and Place Tasks in Narrow Spaces. Appl. Sci. 2024, 14, 10313. [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]
- Ganesan, S.; Ramalingam, B.; Mohan, R.E. A hybrid sampling-based RRT* path planning algorithm for autonomous mobile robot navigation. Expert Syst. Appl. 2024, 258, 125206. [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]
- Qin, H.; Shao, S.; Wang, T.; Yu, X.; Jiang, Y.; Cao, Z. Review of Autonomous Path Planning Algorithms for Mobile Robots. Drones 2023, 7, 211. [Google Scholar] [CrossRef]
- Elbanhawi, M.; Simic, M. Sampling-Based Robot Motion Planning: A Review. IEEE Access 2014, 2, 56–77. [Google Scholar] [CrossRef]
- Herlambang, T.; Rahmalia, D.; Yulianto, T. Particle Swarm Optimization (PSO) and Ant Colony Optimization (ACO) for optimizing PID parameters on Autonomous Underwater Vehicle (AUV) control system. J. Phys. Conf. Ser. 2019, 1211, 012039. [Google Scholar] [CrossRef]
- Gul, F.; Mir, I.; Abualigah, L.; Sumari, P.; Forestiero, A. A Consolidated Review of Path Planning and Optimization Techniques: Technical Perspectives and Future Directions. Electronics 2021, 10, 2250. [Google Scholar] [CrossRef]
- Hassan, I.A.; Abed, I.A.; Al-Hussaibi, W.A. Path planning and trajectory tracking control for two-wheel mobile robot. J. Robot. Control (JRC) 2024, 5, 1–15. [Google Scholar] [CrossRef]
- Wang, W.; Wen, T.; He, X.; Xu, G. Robust trajectory tracking and control allocation of X-rudder AUV with actuator uncertainty. Control Eng. Pract. 2023, 136, 105535. [Google Scholar] [CrossRef]
- Reyhanoglu, M.; Jafari, M. A simple learning approach for robust tracking control of a class of dynamical systems. Electronics 2023, 12, 2026. [Google Scholar] [CrossRef]
- Hu, Y.; Zhou, W.; Liu, Y.; Zeng, M.; Ding, W.; Li, S.; Li, G.; Li, Z.; Knoll, A. Efficient online planning and robust optimal control for nonholonomic mobile robot in unstructured environments. IEEE Trans. Emerg. Top. Comput. Intell. 2024, 8, 3559–3575. [Google Scholar] [CrossRef]
- Lee, T.; Jeong, Y. A tube-based model predictive control for path tracking of autonomous articulated vehicle. Actuators 2024, 13, 164. [Google Scholar] [CrossRef]
- Khan, S.; Guivant, J.; Li, Y.; Liu, W.; Li, X. Hybrid model predictive control for unmanned ground vehicles. IEEE Trans. Intell. Veh. 2023, 9, 1537–1546. [Google Scholar] [CrossRef]
- Qie, T.; Wang, W.; Yang, C.; Li, Y.; Zhang, Y.; Liu, W.; Xiang, C. An improved model predictive control-based trajectory planning method for automated driving vehicles under uncertainty environments. IEEE Trans. Intell. Transp. Syst. 2022, 24, 3999–4015. [Google Scholar] [CrossRef]
- Hao, L.-Y.; Wang, R.-Z.; Shen, C.; Shi, Y. Trajectory tracking control of autonomous underwater vehicles using improved tube-based model predictive control approach. IEEE Trans. Ind. Inform. 2023, 20, 5647–5657. [Google Scholar] [CrossRef]
- Heshmati-alamdari, S.; Nikou, A.; Dimarogonas, D.V. Robust Trajectory Tracking Control for Underactuated Autonomous Underwater Vehicles. In Proceedings of the 2019 IEEE 58th Conference on Decision and Control (CDC), Nice, France, 11–13 December 2019; pp. 8311–8316. [Google Scholar]
- Ou, Y.; Cai, Y.; Sun, Y.; Qin, T. Autonomous navigation by mobile robot with sensor fusion based on deep reinforcement learning. Sensors 2024, 24, 3895. [Google Scholar] [CrossRef] [PubMed]
- Ušinskis, V.; Nowicki, M.; Dzedzickis, A.; Bučinskas, V. Sensor-Fusion Based Navigation for Autonomous Mobile Robot. Sensors 2025, 25, 1248. [Google Scholar] [CrossRef] [PubMed]
- Vásconez, J.P.; Calderón-Díaz, M.; Briceño, I.C.; Pantoja, J.M.; Cruz, P.J. A Behavior-Based Fuzzy Control System for Mobile Robot Navigation: Design and Assessment. In International Conference on Advanced Research in Technologies, Information, Innovation and Sustainability; Springer Nature Switzerland: Cham, Switzerland, 2024; pp. 412–426. [Google Scholar]
- Hachani, S.; Nechadi, E. Type-2 Fuzzy Logic-Based Robot Navigation in Uncertain Environments: Simulation and Real-World Implementation. J. Robot. Control (JRC) 2025, 6, 437–445. [Google Scholar] [CrossRef]
- Tao, B.; Kim, J.-H. Deep reinforcement learning-based local path planning in dynamic environments for mobile robot. J. King Saud Univ.-Comput. Inf. Sci. 2024, 36, 102254. [Google Scholar] [CrossRef]
- Bi, Y.; Fang, X. A Hybrid Path Planning Framework Integrating Deep Reinforcement Learning and Variable-Direction Potential Fields. Mathematics 2025, 13, 2312. [Google Scholar] [CrossRef]
- Zhang, J.; Xian, Y.; Zhu, X.; Deng, H. A hybrid deep learning model for UAV path planning in dynamic environments. IEEE Access 2025, 13, 67459–67475. [Google Scholar] [CrossRef]
- Zhu, W.; Chen, Z. Research on Path Planning for Mobile Charging Robots Based on Improved A* and DWA Algorithms. Electronics 2025, 14, 2318. [Google Scholar] [CrossRef]
- Li, X.; Zhang, R.; Wang, J.; He, B. Path Planning for Transoceanic Underwater Glider Based on Hybrid Reinforcement Learning Algorithm. IEEE Internet Things J. 2025, 12, 32271–32282. [Google Scholar] [CrossRef]
- Ugwoke, K.C.; Nnanna, N.A.; Abdullahi, S.E.-Y. Simulation-based review of classical, heuristic, and metaheuristic path planning algorithms. Sci. Rep. 2025, 15, 12643. [Google Scholar] [CrossRef] [PubMed]
- Zhang, T.; Fan, J.; Zhou, N.; Gao, Z. Highly Self-Adaptive Path-Planning Method for Unmanned Ground Vehicle Based on Transformer Encoder Feature Extraction and Incremental Reinforcement Learning. Machines 2024, 12, 289. [Google Scholar] [CrossRef]
- Lee, K.; Im, E.; Cho, K. Mission-Conditioned Path Planning with Transformer Variational Autoencoder. Electronics 2024, 13, 2437. [Google Scholar] [CrossRef]
- Chen, L.; Wang, Y.; Miao, Z.; Mo, Y.; Feng, M.; Zhou, Z.; Wang, H. Transformer-based imitative reinforcement learning for multirobot path planning. IEEE Trans. Ind. Inform. 2023, 19, 10233–10243. [Google Scholar] [CrossRef]
- Zhuang, L.; Zhao, J.; Li, Y.; Xu, Z.; Zhao, L.; Liu, H. Transformer-Enhanced Motion Planner: Attention-Guided Sampling for State-Specific Decision Making. IEEE Robot. Autom. Lett. 2024, 9, 8794–8801. [Google Scholar] [CrossRef]
- Nan, J.; Zhang, R.; Yin, G.; Zhuang, W.; Zhang, Y.; Deng, W. Safe and Interpretable Human-Like Planning With Transformer-Based Deep Inverse Reinforcement Learning for Autonomous Driving. IEEE Trans. Autom. Sci. Eng. 2025, 22, 12134–12146. [Google Scholar] [CrossRef]
- Briden, J.; Gurga, T.; Johnson, B.; Cauligi, A.; Linares, R. Transformer-based tight constraint prediction for efficient powered descent guidance. J. Guid. Control Dyn. 2025, 48, 1054–1070. [Google Scholar] [CrossRef]
- Dong, L.; Jiang, F.; Peng, Y. Attention-based UAV trajectory optimization for wireless power transfer-assisted IoT systems. IEEE Trans. Ind. Electron. 2025, 72, 8463–8471. [Google Scholar] [CrossRef]
- Liu, S.; Lin, Z.; Huang, W.; Yan, B. Technical development and future prospects of cooperative terminal guidance based on knowledge graph analysis: A review. J. Zhejiang Univ.-Sci. A 2025, 26, 605–634. [Google Scholar] [CrossRef]
- Cai, Z.; Liu, J.; Xu, L.; Wang, J. Cooperative path planning study of distributed multi-mobile robots based on optimised ACO algorithm. Robot. Auton. Syst. 2024, 179, 104748. [Google Scholar] [CrossRef]
- Huang, C.; Ma, H.; Zhou, X.; Deng, W. Cooperative Path Planning of Multiple Unmanned Aerial Vehicles Using Cylinder Vector Particle Swarm Optimization With Gene Targeting. IEEE Sens. J. 2025, 25, 8470–8480. [Google Scholar] [CrossRef]
- Nasti, S.; Chishti, M.; Najar, Z. A Comprehensive Review of Path Planning Techniques for Mobile Robot Navigation in Known and Unknown Environments. Int. J. Comput. Exp. Sci. Eng. 2025, 11, 10–39. [Google Scholar] [CrossRef]
- Qiu, H.; Yu, W.; Zhang, G.; Xia, X.; Yao, K. Multi-robot Collaborative 3D Path Planning Based On Game Theory and Particle Swarm Optimization Hybrid Method. J. Supercomput. 2025, 81, 487. [Google Scholar] [CrossRef]
- Loganathan, A.; Ahmad, N.S. A systematic review on recent advances in autonomous mobile robot navigation. Eng. Sci. Technol. Int. J. 2023, 40, 101343. [Google Scholar] [CrossRef]
- Minh, D.T.; Dung, N.B. Hybrid algorithms in path planning for autonomous navigation of unmanned aerial vehicle: A comprehensive review. Meas. Sci. Technol. 2024, 35, 112002. [Google Scholar] [CrossRef]
- Abdulsaheb, J.A.; Kadhim, D.J. Classical and heuristic approaches for mobile robot path planning: A survey. Robotics 2023, 12, 93. [Google Scholar] [CrossRef]
- Zhang, C.; Wu, Z.; Li, Z.; Xu, H.; Xue, Z.; Qian, R. Multi-agent Reinforcement Learning-Based UAV Swarm Confrontation: Integrating QMIX Algorithm with Artificial Potential Field Method. In Proceedings of the 2024 IEEE International Conference on Systems, Man, and Cybernetics (SMC), Kuching, Malaysia, 6–10 October 2024; pp. 161–166. [Google Scholar]
- Kong, G.; Cai, J.; Gong, J.; Tian, Z.; Huang, L.; Yang, Y. Cooperative following of multiple autonomous robots based on consensus estimation. Electronics 2022, 11, 3319. [Google Scholar] [CrossRef]
- Das, P.K. Hybridization of Kidney-Inspired and sine–cosine algorithm for multi-robot path planning. Arab. J. Sci. Eng. 2020, 45, 2883–2900. [Google Scholar] [CrossRef]
- Das, P.K.; Behera, H.S.; Das, S.; Tripathy, H.K.; Panigrahi, B.K.; Pradhan, S. A hybrid improved PSO-DV algorithm for multi-robot path planning in a clutter environment. Neurocomputing 2016, 207, 735–753. [Google Scholar] [CrossRef]
- Mohanty, P.K.; Parhi, D.R. A new hybrid optimization algorithm for multiple mobile robots navigation based on the CS-ANFIS approach. Memetic Comput. 2015, 7, 255–273. [Google Scholar] [CrossRef]
- Lin, S.; Liu, A.; Wang, J.; Kong, X. An intelligence-based hybrid PSO-SA for mobile robot path planning in warehouse. J. Comput. Sci. 2023, 67, 101938. [Google Scholar] [CrossRef]
- Ni, Z.; Li, Q.; Zhang, M. Efficient motion planning for chili flower pollination mechanism based on BI-RRT. Comput. Electron. Agric. 2025, 232, 110063. [Google Scholar] [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]
- Dijkstra, E.W. A note on two problems in connexion with graphs. Numer. Math. 1959, 1, 269–271. [Google Scholar] [CrossRef]
- Subramanian, M.B.; Sudhagar, K.; RajaRajeswari, G. Optimal path forecasting of an autonomous mobile robot agent using breadth first search algorithm. Int. J. Mech. Mechatron. Eng. 2014, 14, 85–89. [Google Scholar]
- Floyd, R.W. Algorithm 97: Shortest path. Commun. ACM 1962, 5, 345. [Google Scholar] [CrossRef]
- Tarjan, R.E. Depth-First Search and Linear Graph Algorithms. SIAM J. Comput. 1972, 1, 146–160. [Google Scholar] [CrossRef]
- Bellman, R. ON A ROUTING PROBLEM. Q. Appl. Math. 1958, 16, 87–90. [Google Scholar] [CrossRef]
- Kavraki, L.E.; Svestka, 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]
- Gammell, J.D.; Srinivasa, S.S.; Barfoot, T.D. Batch Informed Trees (BIT*): Sampling-based optimal planning via the heuristically guided search of implicit random geometric graphs. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, DC, USA, 26–30 May 2015; pp. 3067–3074. [Google Scholar]
- Karaman, S.; Walter, M.R.; Perez, A.; Frazzoli, E.; Teller, S. Anytime motion planning using the RRT. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 1478–1483. [Google Scholar]
Algorithm | Time Complexity | Space Complexity | Real-Time Feasibility | Memory Usage | Suitable Application Domains |
---|---|---|---|---|---|
A* | O(E) with heuristic, typically O(V log V) using priority queue | O(V) | High for small-to-medium search spaces; depends on heuristic quality | Moderate | Mobile robot navigation, game AI, autonomous vehicles (static and dynamic environments) |
Dijkstra | O(V2) without heap, O((V+E) log V) with min-heap | O(V) | Moderate for sparse graphs; less suitable for very large graphs | Moderate | Network routing, static obstacle environments, warehouse navigation |
BFS | O(V+E) | O(V) | High for small graphs; less efficient in large spaces | High (stores entire frontier) | Multi-robot formation planning, shortest path in unweighted graphs |
DFS | O(V+E) | O(V) | Low for optimality; fast for exploration, but not the shortest path | Low | Maze exploration, connectivity checking, and backtracking-based navigation |
Floyd-Warshall | O(V3) | O(V2) | Low for real-time; better for offline precomputation | High | All-pairs shortest paths, traffic network analysis, dense graph applications |
Bellman–Ford | O(V·E) | O(V) | Low for real-time in large graphs | Moderate | Single-source shortest path with negative weights, evacuation planning, and power-efficient small-scale tasks |
Algorithm | Time Complexity | Space Complexity | Real-Time Feasibility | Memory Usage | Suitable Application Domains |
---|---|---|---|---|---|
RRT | O(n log n) | O(n) | High (in moderately complex static environments) | Low–Medium | Exploration, robot navigation in unknown or partially known static environments |
RRT* | O(n log n) | O(n) | Moderate (higher computation due to path optimization) | Medium | Optimal motion planning in robotics, Unmanned Aerial Vehicles (UAV) navigation, where smooth paths are critical |
Informed RRT* | O(n log n) | O(n) | Moderate–High (faster convergence than RRT*) | Medium | High-dimensional motion planning with known start-goal states |
PRM | O(n2) | O(n) | Low (offline phase is heavy) | High | Multi-query static environments, such as factory floor navigation |
BIT* | O(n log n) | O(n) | Moderate | Medium | Anytime optimal planning in static/dynamic settings |
Single-Query Biased | O(n)—O(n log n) depending on biasing strategy | O(n) | High (due to focused search) | Low–Medium | Single-instance motion planning in cluttered or goal-directed environments, UAV navigation, robotic arm path generation |
Algorithm | Time Complexity | Space Complexity | Real-Time Feasibility | Memory Usage | Suitable Application Domains |
---|---|---|---|---|---|
APF | O(n) | O(n) | High (suitable for on-the-fly obstacle avoidance) | Very Low | Mobile robots in structured indoor environments, UAV collision avoidance, and robotic arm obstacle evasion |
DWA | O(k⋅n), where k is the number of velocity samples | O(n) | High (widely used in real-time navigation) | Low | Autonomous ground vehicles, service robots in dynamic environments, and planetary rovers |
VFH | O(n) | O(n) | High | Medium | Outdoor mobile robots, agricultural robots, and autonomous wheelchairs |
Algorithm | Time Complexity | Space Complexity | Real-Time Feasibility | Memory Usage | Suitable Application Domains |
---|---|---|---|---|---|
GDA | O(k⋅n), where k = iterations, n = number of variables | O(n) | Medium–High (fast convergence for smooth cost functions) | Low | Local trajectory optimization, fine-tuning of precomputed paths, UAV landing path refinement, and autonomous vehicle lane-change optimization |
GA | O(g⋅p⋅n) where g = generations, p = population size, n = chromosome length | O(p⋅n) | Medium (feasible with smaller populations) | Medium–High | Global route optimization in large-scale maps, UAV mission planning, and multi-objective optimization in robotics |
PSO | O(i⋅p) where i = iterations, p = number of particles | O(p) | Medium–High | Medium | Mobile robot navigation in dynamic environments, swarm robotics coordination, AGV path optimization |
ACO | O(m⋅n2) where m = number of ants, n = number of nodes | O(n2) | Medium | High | Warehouse robot routing, UAV coverage path planning, and network routing in robotics |
Hybrid Algorithm | Operating Principle | Performance Characteristics | Computational Requirements | Adaptability to Dynamic Environments | Typical Application Domains | Relative Ranking # | References |
---|---|---|---|---|---|---|---|
A* + GA | Heuristic search with genetic optimization refinement | Shorter paths, smoother motion | Moderate–High | Moderate | Warehouse robots, static indoor navigation | Perf.: High; Comp.: Medium; Adapt.: Med | [133] |
Dijkstra + ACO | Initial shortest path + pheromone-based refinement | High accuracy, balanced exploration/exploitation | High | Good | Multi-robot coordination, terrain navigation | Perf.: High; Comp.: High; Adapt.: High | [87,133] |
Floyd-Warshall + PSO | All-pairs shortest paths + PSO | Multi-node connectivity, smooth transitions | High | Limited | Inspection robots, network routing | Perf.: Medium; Comp.: High; Adapt.: Low | [86,133] |
Bellman–Ford + DL | Shortest path with DL prediction | Predictive adaptation, stable paths | High | High | Autonomous driving, smart parking | Perf.: High; Comp.: High; Adapt.: High | [97] |
RRT* + A | RRT feasible path + A* refinement | Smooth, collision-free paths | Moderate | High | UAV navigation, exploration | Perf.: High; Comp.: Medium; Adapt.: High | [90] |
PRM + RL | Roadmap connectivity + RL policy navigation | Learns optimal transitions | High | High | AGVs, cluttered environments | Perf.: High; Comp.: High; Adapt.: High | [89] |
PF + MPC | Potential field + predictive control | Safe, anticipates obstacle motion | High | Very High | Multi-agent coordination, autonomous vehicles | Perf.: High; Comp.: High; Adapt.: Very High | [92] |
GDA + A* | Gradient descent cost minimization + A* | Quick convergence | Low–Moderate | Moderate | Embedded robotics | Perf.: Medium; Comp.: Low; Adapt.: Med | [91] |
RRT + RL | Sampling exploration + learning refinement | Adapts to unknown environments | High | High | Swarm robotics, search-and-rescue | Perf.: High; Comp.: High; Adapt.: High | [100] |
PRM + DL | PRM with DL obstacle prediction | Accurate long-term navigation | High | Very High | Roadmap optimization, urban navigation | Perf.: High; Comp.: High; Adapt.: Very High | [97] |
RRT* + DRL | Optimal sampling trees + deep RL refinement | Obstacle-aware optimality | Very High | Very High | Autonomous driving in dynamic traffic | Perf.: Very High; Comp.: Very High; Adapt.: Very High | [100] |
RRT* + Predictive Control | RRT* + MPC for coordination | Collision-free multi-agent trajectories | High | High | Multi-robot fleets, drones | Perf.: High; Comp.: High; Adapt.: High | [98] |
Sampling + FL | Probabilistic sampling + fuzzy logic | Human-like smoothness | Low–Moderate | High | Assistive robotics, uneven terrain | Perf.: Medium; Comp.: Low; Adapt.: High | [95,101] |
RRT* + GA | RRT* + GA convergence boost | Faster convergence | Moderate–High | Moderate | UAV coverage missions | Perf.: Medium –High; Comp.: Medium; Adapt.: Medium | [101] |
PF + A* | Local PF + global A* | Balanced local/global planning | Low–Moderate | Moderate | Mobile ground robots | Perf.: Medium; Comp.: Low; Adapt.: Medium | [91] |
GDA + LQR | Gradient descent + optimal control | High precision, energy efficiency | Low | Low–Moderate | Industrial manipulators | Perf.: Medium; Comp.: Low; Adapt.: Low | [93] |
GDA + MPC | GDA optimization + predictive control | Smooth motion in dynamic obstacles | Moderate–High | High | Human–robot interaction | Perf.: High; Comp.: Medium –High; Adapt.: High | [92] |
PSO + Modified FA | Swarm + firefly attraction | High exploration capability | High | Moderate–High | Maritime robotics | Perf.: High; Comp.: High; Adapt.: High | [102] |
ACO + DE | Pheromone exploration + evolutionary optimization | Strong in complex maps | High | Moderate–High | Search missions | Perf.: High; Comp.: High; Adapt.: High | [30,77] |
ACO + FL | ACO + fuzzy adaptation | Flexible decision-making | Moderate | High | Semi-autonomous systems | Perf.: Medium –High; Comp.: Medium; Adapt.: High | [80] |
PSO + ANN | Swarm + ANN prediction | Obstacle anticipation | High | Very High | Real-time autonomous driving | Perf.: High; Comp.: High; Adapt.: Very High | [81] |
PSO + GWO | Swarm + social hierarchy search | Faster convergence | Moderate–High | High | Exploration under uncertainty | Perf.: High; Comp.: Medium –High; Adapt.: High | [134] |
Hybrid RRT + PSO* | RRT* + PSO | Globally optimal feasible paths | High | High | Underwater robotics | Perf.: High; Comp.: High; Adapt.: High | [98] |
GA + Hybrid A* | Classical + improved heuristic A* | Higher smoothness, fewer turns | Moderate | Moderate | Self-driving vehicles | Perf.: Medium –High; Comp.: Medium; Adapt.: Medium | [86] |
Algorithm | Path Distance (Relative) | # Nodes Visited (Relative) | Path Smoothness | Convergence Rate | Success Rate |
---|---|---|---|---|---|
A* + GA/RL* | High | Medium | High | High | High |
Dijkstra + ACO | Medium–High | Medium | Medium–High | Medium–High | High |
Floyd-Warshall + PSO | Medium | High | Medium | Medium | Medium–High |
Bellman–Ford + DL | Medium | Medium–High | Medium–High | High | High |
RRT + A* | High | Medium | High | High | High |
RRT + DRL | High | Low–Medium | High | Very High | Very High |
PRM + DL | Medium–High | Medium | High | High | High |
PFA + MPC | High | Low | Very High | High | High |
Hybrid A* + RRT/APF* | High | Medium | High | High | High |
GDA + MPC/LQR | Medium–High | Low | Very High | High | High |
PSO + ACO | High | Medium | Medium–High | High | High |
PSO + ANN/GWO | High | Low–Medium | High | Very High | High |
Transformer + RL/DL | Very High | Low | Very High | Very High | Very High |
Cooperative Multi-Agent Hybrids (ACO/PSO/MPC) | High | Medium | High | High | Very High |
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
Shanmugaraja, M.; Thangamuthu, M.; Ganesan, S. Hybrid Path Planning Algorithm for Autonomous Mobile Robots: A Comprehensive Review. J. Sens. Actuator Netw. 2025, 14, 87. https://doi.org/10.3390/jsan14050087
Shanmugaraja M, Thangamuthu M, Ganesan S. Hybrid Path Planning Algorithm for Autonomous Mobile Robots: A Comprehensive Review. Journal of Sensor and Actuator Networks. 2025; 14(5):87. https://doi.org/10.3390/jsan14050087
Chicago/Turabian StyleShanmugaraja, Mithun, Mohanraj Thangamuthu, and Sivasankar Ganesan. 2025. "Hybrid Path Planning Algorithm for Autonomous Mobile Robots: A Comprehensive Review" Journal of Sensor and Actuator Networks 14, no. 5: 87. https://doi.org/10.3390/jsan14050087
APA StyleShanmugaraja, M., Thangamuthu, M., & Ganesan, S. (2025). Hybrid Path Planning Algorithm for Autonomous Mobile Robots: A Comprehensive Review. Journal of Sensor and Actuator Networks, 14(5), 87. https://doi.org/10.3390/jsan14050087