Next Article in Journal
An RGB-D Vision-Guided Robotic Depalletizing System for Irregular Camshafts with Transformer-Based Instance Segmentation and Flexible Magnetic Gripper
Previous Article in Journal
Modeling of a C-Frame Reluctance-Enhanced Shaded-Pole Induction Motor—Study of Shaded-Coil Design
Previous Article in Special Issue
Model Predictive Control for Pneumatic Manipulator via Receding-Horizon-Based Extended State Observers
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Weight-Incorporating A* Algorithm with Multi-Factor Cost Function for Enhanced Mobile Robot Path Planning

Department of Human Intelligence Robot Engineering, Sangmyung University, Cheonan 31066, Republic of Korea
*
Authors to whom correspondence should be addressed.
Actuators 2025, 14(8), 369; https://doi.org/10.3390/act14080369
Submission received: 1 June 2025 / Revised: 10 July 2025 / Accepted: 22 July 2025 / Published: 24 July 2025
(This article belongs to the Special Issue Actuators in Robotic Control—3rd Edition)

Abstract

This study proposes the Weight-Incorporating A* (WIA*) algorithm for mobile robot path planning. The WIA* algorithm integrates three weight factors into the Conventional A* cost function: an Obstacle Collision (OC) weight factor for collision avoidance, a Path Distance (PD) weight factor for path length optimization, and a Driving Suitability (DS) weight factor for environmental considerations. Experimental validation was conducted using nine 2D grid maps and a 3D virtual environment. The results show that WIA* achieved zero obstacle collisions compared to an average of 9.11 collisions with Conventional A*. Although WIA* increased path length by 12.69%, it reduced driving suitability cost by 93.88%, achieving zero cost in six out of nine test environments. The algorithm demonstrates effective collision-free path generation while incorporating environmental factors for practical mobile robot navigation.

1. Introduction

Efficient path planning algorithms are essential for autonomous navigation of mobile robots [1]. Path planning can be classified into global path planning and local path planning [2,3]. Global path planning algorithms have been studied to generate optimal paths from the starting point to the target point for mobile robots in environments with static obstacles [4,5,6]. Performance metrics such as path length, path curvature, accuracy, and collision frequency are considered in this process [7]. Local path planning is performed in dynamic environments that are not known in advance. Local path planning algorithms generate paths that avoid dynamic obstacles and return to the global path.
Global path planning methods can be broadly categorized into graph-based and sampling-based approaches. Graph-based path planning algorithms include Dijkstra [8], A*, D*, and D* Lite. Sampling-based path planning methods encompass Probabilistic Roadmap (PRM), Rapidly Exploring Random Tree (RRT) [9], and RRT*. Among these algorithms, A* demonstrates a fast search speed and high efficiency by incorporating heuristic functions into the Dijkstra algorithm. The A* algorithm exhibits optimal performance in static environments where complete environmental information is available. Due to these advantages, the A* algorithm is widely utilized not only for mobile robots but also for unmanned aerial vehicles (UAVs) and unmanned surface vehicles (USVs) [10,11,12]. For static global path planning, the A* algorithm is widely used in robotics research owing to its inherent advantages of simplicity, computational efficiency, and adaptability.
Recent research has focused on extending A* algorithms to address specific application requirements. Graph-based algorithms such as Dijkstra and A* typically exhibit good completeness, meaning that if a feasible path exists, the algorithm will eventually find it [13,14]. However, these algorithms can become computationally intensive when dealing with large maps and may face challenges in dynamic environments [15]. Various A*-based variants have been developed to overcome specific limitations. For instance, D* algorithms handle dynamic environments by replanning paths when obstacles change, while other approaches focus on computational efficiency or path quality improvements [16,17]. Wang et al. proposed improvements to the traditional A* algorithm by introducing bidirectional search strategies and optimizing heuristic functions to reduce computational load [18]. Li et al. developed adaptive step-size algorithms that dynamically adjust based on obstacle distribution, reducing node expansions and integrating a dynamic window approach for real-time obstacle avoidance [19]. Most A*-based algorithms primarily focus on finding the shortest geometric path, with opportunities remaining for incorporating practical constraints for mobile robot navigation, such as collision margins and environmental suitability for robot operation [20].
Sampling-based planning algorithms, such as PRM and RRT, are more computationally efficient and can adapt to dynamic changes, though they may not guarantee finding the optimal path [21,22]. The initial paths generated by both graph-based and sampling-based algorithms typically require subsequent processing for smoothness [23]. Optimization-based planning methods, such as Model Predictive Control (MPC) and Artificial Potential Field (APF), can effectively handle various complex environments and dynamic changes, while requiring higher computational complexity and model dependency [24,25]. Recent studies have shown that MPC approaches can effectively handle multi-constraint optimization with increased computational requirements, while APF methods may encounter local minima challenges [26,27].
Intelligent algorithms have gained considerable attention in path planning research, including Genetic Algorithm (GA), Particle Swarm Optimization (PSO) [28], Ant Colony Optimization (ACO) [29], and Deep Reinforcement Learning (DRL) approaches [30,31,32,33]. GAs provide strong global search capabilities while addressing convergence challenges [34,35]. PSO algorithms demonstrate fast convergence characteristics with considerations for local optimization issues [36,37]. Recent hybrid approaches have successfully combined multiple algorithms to leverage their respective advantages [38,39,40]. Despite significant advances in path planning algorithms, opportunities remain for further development [41]. Many existing algorithms focus on geometric optimality, with potential for incorporating real-world robot constraints such as physical size, turning radius, and operational safety margins [42]. There is scope for enhanced consideration of environmental factors that affect robot navigation, such as surface conditions, terrain difficulty, and operational safety [43]. Research opportunities exist for simultaneous optimization of path length, collision avoidance, and environmental suitability in a unified framework [44].
Several considerations arise when applying the traditional A* algorithm to mobile robots. The algorithm may create paths that pass through the boundaries of obstacles such as walls, making actual movement challenging due to the physical size of the robot [15]. To address this, hybrid A* algorithms incorporating repulsive forces for collision avoidance have been studied [45]. However, these approaches may be less suitable for paths that require straight-line trajectories. Additionally, the A* algorithm may include unnecessary movement paths, presenting opportunities for generating more direct routes [45]. The A* algorithm explores paths by selecting neighboring nodes with low costs, with potential for considering broader cost function aspects [46]. Furthermore, since the A* algorithm focuses on avoiding static obstacles based on known map information, there is potential for incorporating environmental factors that may affect mobile robot navigation, such as congested areas or areas with steps [47]. Several studies have applied new cost functions to enhance the traditional A* algorithm [48].
Building upon these research foundations, this study proposes the Weight-Incorporating A* (WIA*) algorithm, which aims to address multiple path planning considerations through an integrated approach. The WIA* algorithm enhances the traditional A* algorithm by integrating three weight factors into the cost function. This approach seeks to address multiple limitations while preserving the inherent advantages of the Conventional A* algorithm. The WIA* algorithm incorporates three key aspects: obstacle collision avoidance, path distance optimization, and driving suitability consideration. The Obstacle Collision (OC) weight factor is designed to generate practical paths that prevent mobile robots from passing through the boundaries of static obstacles, addressing real-world physical constraints. The Path Distance (PD) weight factor is applied to eliminate unnecessary paths and promote efficient route generation. The Driving Suitability (DS) weight factor enables adaptive path generation that considers environmental factors that may affect mobile robot navigation. WIA* provides a unified framework within the A* paradigm, maintaining computational efficiency while addressing multiple practical considerations. The WIA* algorithm is designed for environments that require straight-line paths. This approach incorporates weights proportional to path characteristics to find optimal paths while maintaining path integrity. The proposed approach aims to provide a balanced solution that maintains the computational efficiency of A* while addressing practical navigation requirements through a multi-objective optimization framework.

2. Conventional A* Algorithm

The Conventional A* algorithm is a graph-based path planning algorithm that uses heuristic functions to search for optimal paths from the starting point to the target point. The A* algorithm discretizes static obstacle environments using the grid method technique to generate two-dimensional grid maps. Each grid cell is represented as a node, where nodes with obstacles are set as impassable areas and empty spaces are set as passable areas.
The fundamental principle of the A* algorithm is to find the optimal path by calculating the cost function for each node. The cost function for the current node is defined as shown in Equation (1).
f n = g n + h ( n )
where g(n) is the actual movement cost from the start node to the current node, n, and h(n) is the estimated movement cost from the current node, n, to the target node. For g(n), a value of 1 is used for straight movements and a value of 1.4 is used for diagonal movements. h(n) is calculated using the Manhattan distance method [49].
The cost functions of the eight neighboring nodes from the current node are calculated and added to the Open list. The Open list is a priority queue that stores nodes to be explored. The node with the lowest cost function value is selected from the Open list and moved to the Closed list. The Closed list stores nodes that have already been explored [50,51]. This process is repeated until the target node is reached.
In the Conventional A* algorithm, the total cost of the entire path is calculated as shown in Equation (2).
F = w 1 k = 1 n f k ( n )
where fk(n) is the cost function value of the k-th node stored in the Closed list and w1 is the weight coefficient. In this study, w1 was used as 10 for the A* algorithm implementation. The final path is generated by backtracking through the nodes stored in the Closed list.

3. Weight-Incorporating A* Algorithm

The Weight-Incorporating A* (WIA*) algorithm proposed in this study performs optimized path planning by adding three weight factors to the cost function of the Conventional A* algorithm. The added weight factors generate practical paths for the mobile robot by reflecting obstacle collision avoidance, path length optimization, and driving environment suitability, respectively.

3.1. Obstacle Collision Weight Factor

The Obstacle Collision (OC) weight factor was introduced to ensure the generation of only practical navigation paths by excluding infeasible routes that pass through obstacle boundaries, where mobile robots cannot actually travel due to physical size constraints. The OC weight factor prevents potential collisions by imposing a large penalty when the path passes through obstacle boundaries. The OC weight factor is defined as in Equation (3).
F 1 = w p 1
where w is the penalty weight for passing through obstacle boundaries and p1 is the number of times the path crosses obstacle boundaries. The penalty weight is set by multiplying the sum of the horizontal and vertical grid numbers by the weight coefficient, w1, in Equation (2) to represent the maximum possible distance in the given map. The extended cost function applying the OC weight factor to the Conventional A* algorithm is shown in Equation (4).
F = w 1 k = 1 n f k n + F 1
Figure 1 compares the path generation results before and after applying the OC weight factor in a 6 × 5 grid map. As shown in Figure 1a, the Conventional A* algorithm generates a path that penetrates obstacles, while the OC weighted A* algorithm generates a practical path that bypasses obstacle boundaries as in Figure 1b. In this experiment, the penalty weight denoted by w in Equation (3) was set as 110. When the path passed through obstacles, F1 was calculated as being much larger than the conventional cost function value.

3.2. Path Distance Weight Factor

The Path Distance (PD) weight factor was introduced to minimize unnecessary detour paths and promote the generation of shortest distance paths. The PD weight factor is calculated proportionally to the total path length, as shown in Equation (5).
F 2 = w 1 ( 1.4 p 2 + p 3 )
where p2 is the number of diagonal movements and p3 is the number of straight movements. The length of one grid side was normalized to 1. The diagonal movement distance was set as 1.4, and the straight movement distance was one. The cost function applying both OC and PC weight factors is shown in Equation (6).
F = w 1 k = 1 n f k n + F 1 + F 2
Figure 2 shows the effect of the PD weight factor in a 10 × 10 grid map. Figure 2a shows the case where the OC weighted A* algorithm was applied, containing unnecessary detour paths, while Figure 2b shows that the OC-PD weighted A* algorithm generates a more efficient path.

3.3. Driving Suitability Weight Factor

In the case of actual mobile robot operation, factors such as terrain conditions, slopes, congestion levels, and road surface conditions affect driving performance. The Driving Suitability (DS) weight factor reflects these environmental factors to select favorable paths for mobile robot navigation. The DS weight factor is defined as shown in Equation (7).
F 3 = w 1 i = 1 n W i Z
where Wi represents the discrete level of driving environment suitability for each grid node and Z is the step size between each level. In this study, Wi was set as an integer between 0 and 100 to use 101 discrete levels. The multiplication result of Wi and Z becomes the value of driving environment suitability for the corresponding node. The final cost function of the WIA* algorithm integrates all three weights and is defined as shown in Equation (8).
F = w 1 k = 1 n f k n + F 1 + F 2 + F 3
Figure 3 demonstrates the effect of the DS weight factor. The color assigned to each node reflects the value of driving environment suitability. White nodes represent areas highly favorable for driving, such as flat terrain. Blue nodes indicate moderately favorable areas, such as minor slopes. Red nodes correspond to areas highly unfavorable for driving, such as stairs and steep slopes. The value of driving environment suitability was defined as 0, 15, and 95 for the white, blue, and red nodes, respectively. As shown in Figure 3a, the OC-PD weighted A* algorithm generates a physically shortest path without considering the driving stability, while the WIA* in Figure 3b generates a path that bypasses areas highly unfavorable for driving and passes through areas favorable for driving.
The proposed WIA* algorithm can generate optimal paths that simultaneously consider obstacle boundary avoidance, travel distance, and driving environment suitability through three additional weight factors.

4. Performance Evaluation of Weight-Incorporating A* Algorithm

Systematic experiments were conducted to validate the performance of the proposed WIA* algorithm using two types of simulation: one was a simple 2D environment, and the other was a 3D virtual environment that mimicked a real-world room. Through the experiments, the individual effects of each weight factor and the overall performance of the integrated WIA* algorithm were estimated.

4.1. Performance Evaluation Methods

4.1.1. Experiments Using Simple 2D Environment

Nine virtual 2D maps with different characteristics were designed to comprehensively analyze the impact of each weight factor of the WIA* algorithm on path generation. As shown in Figure 4, all the maps consisted of 26 × 26 grids, with differentiated driving suitability settings for each grid node. The value of driving environment suitability was defined as 0, 15, and 95 for the white, blue, and red nodes, respectively. The white nodes represent areas highly favorable for driving, such as flat terrain. The blue nodes indicate moderately favorable areas with minor obstacles or slight slopes. The red nodes correspond to areas highly unfavorable for driving, such as stairs, steep slopes, or hazardous terrain, that should be avoided whenever possible.
Four algorithms were systematically compared across all nine maps to evaluate their performance under various environmental conditions. The tested algorithms included Conventional A*, representing the original A* algorithm; OC weighted A*, representing the algorithm with only the Obstacle Collision weight factor applied; OC-PD weighted A*, representing the algorithm with both the OC and Path Distance weight factors applied; and WIA*, representing the proposed algorithm with all three weight factors applied.
Three evaluation metrics were employed to assess algorithm performance: the number of obstacle collisions, path distance, and driving suitability cost. The number of obstacle collisions represents the number of collisions that would occur if a robot followed the generated path, considering the robot’s physical dimensions. Path distance measures the total travel distance of the generated route. Driving suitability cost represents the sum of driving environment suitability values along the traveled path, where a value of 0 indicates that the robot never traversed unfavorable driving areas.

4.1.2. Experiments Using 3D Virtual Environment

A 3D virtual environment was constructed using the Gazebo simulator to simulate actual mobile robot operating environments. The 3D virtual environment is shown in Figure 5. The experimental environment modeled Room 501 of Hanuri Hall at Sangmyung University. In Figure 5a, the experimental environment has a size of 40 m × 40 m and has six static obstacles of 12 m × 6 m each. The grid resolution was set to 800 × 800 to implement a 5 cm resolution, and Turtlebot3, with a width of 30 cm and a length of 22 cm, was used as the mobile robot. The virtual sensors used in the experiment consisted of 2D LiDAR, IMU, and wheel encoders.
SLAM was performed using the SLAM Toolbox framework. Robot localization was achieved by recording robot trajectories through virtual LiDAR scan data and velocity control. Pose estimation was conducted by searching within x, y, and θ parameter spaces using the robot’s estimated pose and scan data. Correlation coefficients were computed by evaluating the correspondence between existing map data and current scan measurements. The map was generated by aligning current scan data with the optimal pose that yielded the highest correlation coefficient.
A real-time 2D occupancy grid map was generated through SLAM (Simultaneous Localization and Mapping) algorithms, as shown in Figure 5b. The performance of the WIA* algorithm was evaluated on the generated 2D map. The environmental adaptability of the algorithm was verified by analyzing path generation results according to various DS value settings.

4.2. Performance Evaluation Results

4.2.1. Experimental Results Using Simple 2D Environment

The paths generated by each algorithm in the first three representative 2D maps are shown in Figure 6. In each map, all paths generated by each algorithm were consistent across multiple trials, as all four algorithms are deterministic and based on the A* algorithm, consistently producing the same results under identical conditions. In Figure 6, the blue, green, mint, and red paths represent the routes generated by the Conventional A*, OC weighted A*, OC-PD weighted A*, and WIA* algorithms, respectively.
Figure 6a demonstrates the effectiveness of the Obstacle Collision weight factor. The Conventional A* algorithm generated a path that passes through obstacle boundaries, making actual robot movement impossible. The OC weighted A* algorithm successfully modified the path to avoid crossing obstacle boundaries. The OC-PD weighted A* algorithm generated the shortest collision-free path, while the WIA* algorithm prioritized safe navigation by exclusively traveling through white areas with optimal driving suitability, albeit with a slightly longer path.
In Figure 6b, the Conventional A* algorithm again exhibited obstacle boundary crossing issues. The OC weighted A* algorithm created a collision-free but suboptimal path with unnecessary detours. The OC-PD weighted A* algorithm achieved the shortest collision-free path. The WIA* algorithm generated a longer path to completely avoid blue regions, demonstrating its ability to prioritize environmental suitability over path length.
Figure 6c illustrates the algorithm’s behavior in environments with highly unfavorable areas. The Conventional A* algorithm generated an impractical path through obstacles. Both the OC weighted A* and OC-PD weighted A* algorithms avoided obstacles but traversed red regions. The WIA* algorithm successfully bypassed the red regions and navigated through blue regions with more favorable driving suitability values, demonstrating its environmental adaptability.
To comprehensively evaluate the algorithm performance beyond the three representative examples, quantitative analysis was conducted across all nine test environments. Regarding obstacle collision performance, the Conventional A* algorithm experienced collisions in every map, with collision counts ranging from 6 to 14 per map and averaging 9.11 collisions across all environments. Specifically, the Conventional A* algorithm recorded six collisions in Maps 1 and 7, eight collisions in Maps 4 and 6, nine collisions in Maps 3 and 9, eleven collisions in Maps 5 and 8, and fourteen collisions in Map 2. In contrast, the WIA* algorithm, along with both the OC weighted A* and OC-PD weighted A* algorithms, achieved zero obstacle collisions across all environments.
In terms of path efficiency, the Conventional A* algorithm generated the shortest geometric paths with distances ranging from 354 to 724 units and averaging 413.33 units across all maps. The OC weighted A* algorithm showed longer paths ranging from 408 to 762 units with an average of 464.44 units, representing a 12.36% increase due to obstacle avoidance considerations. The OC-PD weighted A* algorithm achieved better optimization with paths ranging from 394 to 730 units and averaging 432.11 units, only 4.54% longer than those of Conventional A*. The WIA* algorithm produced paths ranging from 400 to 836 units with an average length of 465.78 units, representing a 12.69% increase compared to Conventional A*, representing a trade-off in path length.
The most significant advantage of the WIA* algorithm was demonstrated in driving suitability cost optimization. The Conventional A* algorithm accumulated driving suitability costs ranging from 0 to 330, with an average of 245.00 across all maps. The OC weighted A* and OC-PD weighted A* algorithms showed similar performance with average costs of 281.67 and 286.67, respectively, performing worse than Conventional A* in this metric as they focused solely on collision avoidance and path length optimization without considering environmental factors. The WIA* algorithm achieved low driving suitability costs, with values ranging from 0 to 90 and averaging 15.00, representing a 93.88% reduction compared to Conventional A*. The WIA* algorithm achieved zero driving suitability cost in six maps (Maps 1, 2, 3, 4, 5, and 6), indicating completely optimal environmental navigation where the robot never traversed unfavorable areas. In the remaining three maps, where complete avoidance was impossible due to environmental constraints, the WIA* algorithm still achieved substantial cost reductions compared to Conventional A*: from 330 to 90 units in Map 7, representing a 72.73% reduction; from 190 to 30 units in Map 8, representing an 84.21% reduction; and from 285 to 15 units in Map 9, representing a 94.74% reduction.

4.2.2. Experimental Results Using 3D Virtual Environment

Four types of grid maps were created by modifying the driving environment suitability values for each node in the grid map shown in Figure 5b. The four types of grid maps and the paths generated by the WIA* algorithm are presented in Figure 7. In the experiments shown in Figure 7, the penalty weight, w, in Equation (3) was set to 1280. According to Equation (5), weights of 1.4 for diagonal movements and 1 for straight movements were applied. The experiments involved adding DS values to the paths traversed on the map and subsequently regenerating the optimal paths.
Figure 7a represents the case where the grid map has high driving suitability in all regions, with all nodes set to a driving environment suitability value of 0. In Figure 7a, the WIA* algorithm generated a path that avoids contact with obstacle boundaries.
Figure 7b shows a grid map where two regions have medium driving suitability. The regions with medium driving suitability are indicated in gray, and the nodes belonging to these gray regions were set to a driving environment suitability value of 95. The WIA* algorithm generated a path that bypasses nodes with medium driving suitability and passes only through nodes with high driving suitability.
Figure 7c adds one additional region with medium driving suitability to Figure 7b. It was confirmed that the WIA* algorithm generates a path that bypasses the additional medium-driving suitability nodes added in Figure 7c.
Figure 7d contains four regions of medium driving suitability and one region of low driving suitability. The low-driving suitability region is indicated in black on the map, and the nodes in this region were set to a driving environment suitability value of 200. Since it is impossible to reach the destination by passing only through high-driving suitability regions, the WIA* algorithm generated a path that minimizes the sum of driving environment suitability values of the traversed nodes.
The WIA* algorithm generates the shortest path in regions with high driving suitability by considering driving environment factors. When nodes with low driving environment suitability are applied to the region where the shortest path is generated, the algorithm creates a path through regions with high driving environment suitability. Therefore, it prioritizes generating paths through regions with high driving suitability rather than the shortest path. When nodes with low driving environment suitability are applied to all accessible regions, the algorithm generates a path that bypasses the nodes with the lowest suitability values. The results demonstrate that the algorithm generates paths considering both the regions with the highest driving environment suitability and the spatial extent of these regions within the accessible area.

5. Conclusions

This study proposes the Weight-Incorporating A* (WIA*) algorithm to address multiple limitations of the Conventional A* algorithm in mobile robot navigation. Building upon analysis of existing path planning approaches, including graph-based, sampling-based, optimization-based, and intelligent algorithms, the WIA* algorithm integrates three weight factors into the cost function while maintaining the computational efficiency of the original A* framework. The Obstacle Collision (OC) weight factor addresses obstacle boundary crossing issues, the Path Distance (PD) weight factor optimizes path length, and the Driving Suitability (DS) weight factor incorporates environmental factors affecting mobile robot navigation.
Path generation experiments were conducted using nine virtual 2D grid maps with varying obstacle configurations and driving suitability regions, as well as a 3D virtual environment based on a real-world space to evaluate the proposed algorithm. The experimental evaluation employed three metrics: obstacle collision count, path distance, and driving suitability cost. The results show that while the Conventional A* algorithm experienced an average of 9.11 obstacle collisions per map, the WIA* algorithm achieved zero collisions across all test environments. The WIA* algorithm showed a 12.69% increase in average path length compared to Conventional A* but achieved a 93.88% reduction in driving suitability cost, with zero cost achieved in six out of nine test environments.
In experiments using a 3D virtual environment, a 2D grid map was acquired through SLAM. The WIA* algorithm adaptively generated paths according to various driving suitability configurations and generated detour paths that considered environmental factors for mobile robot navigation. When complete avoidance of unfavorable areas was not possible due to environmental constraints, the WIA* algorithm achieved cost reductions ranging from 72.73% to 94.74% compared to Conventional A*.
The WIA* algorithm selects safer navigation routes over shorter geometric paths, enabling robots to bypass unsuitable areas when feasible. The proposed algorithm has potential applications in human–robot collaborative environments, such as smart warehouses and manufacturing systems, where environmental considerations are important for safe and efficient operation.
However, this study has several limitations. The experiments were conducted in simulation environments without validation on actual robot hardware under real-world conditions. The driving suitability values were manually configured, which may limit adaptability to dynamic environmental changes. Additionally, the WIA* algorithm focused on static obstacle environments without incorporating mechanisms for dynamic obstacles.
Future research directions include implementing the WIA* algorithm on actual mobile robots equipped with real-time sensor systems for dynamic map generation. Further development could focus on incorporating machine learning techniques to enable automatic determination and dynamic adjustment of environment suitability values based on real-time conditions. Extending the algorithm to handle dynamic obstacles and varying environmental conditions would enhance its applicability to real-world robotic systems.

Author Contributions

Conceptualization, J.H.B. and S.J.; methodology, S.B., J.H.B. and S.J.; software, S.B.; validation, S.B.; data curation, S.B.; writing—original draft preparation, S.B.; writing—review and editing, J.H.B.; visualization, S.B.; supervision, J.H.B. and S.J. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by a 2025 research grant from Sangmyung University.

Data Availability Statement

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

Acknowledgments

During the preparation of this manuscript, the authors used Claude Sonnet 4.0 for the purposes of grammatical review of the manuscript. The authors have reviewed and edited the output and take full responsibility for the content of this publication.

Conflicts of Interest

The authors declare no conflicts of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript; or in the decision to publish the results.

Abbreviations

The following abbreviations are used in this manuscript:
OCObstacle Collision
PDPath Distance
DSDriving Stability
WIA*Weight-Incorporating A*

References

  1. Yan, X.; Zhou, X.; Luo, Q. A Safe Heuristic Path-Planning Method Based on a Search Strategy. Sensors 2024, 24, 101. [Google Scholar] [CrossRef]
  2. 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]
  3. Azizi, M.R.; Rastegarpanah, A.; Stolkin, R. Motion Planning and Control of an Omnidirectional Mobile Robot in Dynamic Environments. Robotics 2021, 10, 48. [Google Scholar] [CrossRef]
  4. Liao, T.; Chen, F.; Wu, Y.; Zeng, H.; Ouyang, S.; Guan, J. Research on Path Planning with the Integration of Adaptive A-Star Algorithm and Improved Dynamic Window Approach. Electronics 2024, 13, 455. [Google Scholar] [CrossRef]
  5. Braun, J.; Brito, T.; Lima, J.; Costa, P.; Costa, P.; Nakano, A. A Comparison of A* and RRT* Algorithms with Dynamic and Real Time Constraint Scenarios for Mobile Robots. In SIMULTECH 2019; Scitepress: Setúbal, Portugal, 2019; pp. 398–405. [Google Scholar]
  6. Yun, S.-W.; Kim, D.-H.; Kim, S.-W.; Kim, D.-J.; Kim, H.-J. Global Path Planning for Autonomous Ship Navigation Considering the Practical Characteristics of the Port of Ulsan. J. Mar. Sci. Eng. 2024, 12, 160. [Google Scholar] [CrossRef]
  7. 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]
  8. Sun, Y.; Fang, M.; Su, Y. AGV Path Planning Based on Improved Dijkstra Algorithm. J. Phys. Conf. Ser. 2021, 1746, 12052. [Google Scholar] [CrossRef]
  9. Li, X.; Tong, Y. Path Planning of a Mobile Robot Based on the Improved RRT Algorithm. Appl. Sci. 2024, 14, 25. [Google Scholar] [CrossRef]
  10. Wang, X.; Ma, X.; Li, Z. Research on SLAM and Path Planning Method of Inspection Robot in Complex Scenarios. Electronics 2023, 12, 2178. [Google Scholar] [CrossRef]
  11. Ha, I.-k. Improved A-Star Search Algorithm for Probabilistic Air Pollution Detection Using UAVs. Sensors 2024, 24, 1141. [Google Scholar] [CrossRef]
  12. Zhang, H.; Tao, Y.; Zhu, W. Global Path Planning of Unmanned Surface Vehicle Based on Improved A-Star Algorithm. Sensors 2023, 23, 6647. [Google Scholar] [CrossRef]
  13. Javaid, A. Understanding Dijkstra’s Algorithm. Telecommun. Netw. Models Ejournal 2013. [Google Scholar] [CrossRef]
  14. Singal, P.; Dijkstra, R.C. Shortest Path Algorithm Using Global Position System. Int. J. Comput. Appl. 2014, 101, 12–18. [Google Scholar] [CrossRef]
  15. Bing, H.; Lai, L. Improvement and Application of Dijkstra Algorithms. Acad. J. Comput. Inf. Sci. 2022, 5, 97–102. [Google Scholar] [CrossRef]
  16. Wang, H.; Qi, X.; Lou, S.; Jing, J.; He, H.; Liu, W. An Efficient and Robust Improved A* Algorithm for Path Planning. Symmetry 2021, 13, 2213. [Google Scholar] [CrossRef]
  17. Liu, S.; Ma, Y. Research for Bidirectional Path Planning Based on An Improved A* Algorithm. In Proceedings of the 2020 IEEE International Conference on Advances in Electrical Engineering and Computer Applications (AEECA), Dalian, China, 25–27 August 2020; pp. 1036–1039. [Google Scholar]
  18. Wang, X.; Liu, Z.; Liu, J. Mobile Robot Path Planning Based on an Improved A* Algorithm. In Proceedings of the Conference on Computer Graphics, Artificial Intelligence, and Data Processing, Guangzhou, China, 23 May 2023. [Google Scholar]
  19. Li, Y.; Jin, R.; Xu, X.; Qian, Y.; Wang, H.; Xu, S.-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]
  20. Li, Z.; Shi, R.; Zhao, Z. A New Path Planning Method Based on Sparse A* Algorithm with Map Segmentation. Trans. Inst. Meas. Control 2021, 44, 916–925. [Google Scholar]
  21. Sun, Z.; Hsu, D.; Jiang, T.; Kurniawati, H.; Reif, J.H. Reif Narrow Passage Sampling for Probabilistic Roadmap Planning. IEEE Trans. Robot. 2005, 21, 1105–1115. [Google Scholar]
  22. LaValle, S. Rapidly-Exploring Random Trees: A New Tool for Path Planning. Annu. Res. Rep. 1998, 18, 1001–1024. [Google Scholar]
  23. Zhang, H.; Wang, Y.; Zheng, J.; Yu, J. Path Planning of Industrial Robot Based on Improved RRT Algorithm in Complex Environments. IEEE Access 2018, 6, 53296–53306. [Google Scholar] [CrossRef]
  24. Schwenzer, M.; Ay, M.; Bergs, T.; Abel, D. Review on Model Predictive Control: An Engineering Perspective. Int. J. Adv. Manuf. Technol. 2021, 117, 1327–1349. [Google Scholar] [CrossRef]
  25. Li, Y.; Tian, B.; Yang, Y.; Li, C. Path Planning of Robot Based on Artificial Potential Field Method. In Proceedings of the 2022 IEEE 6th Information Technology and Mechatronics Engineering Conference (ITOEC), Chongqing, China, 4–6 March 2022; Volume 6, pp. 91–94. [Google Scholar]
  26. Batkovic, I.; Gupta, A.; Zanon, M.; Falcone, P. Experimental Validation of Safe MPC for Autonomous Driving in Uncertain Environments. IEEE Trans. Control Syst. Technol. 2023, 31, 2027–2042. [Google Scholar] [CrossRef]
  27. Xia, X.; Li, T.; Sang, S.; Cheng, Y.; Ma, H.; Zhang, Q.; Yang, K. Path Planning for Obstacle Avoidance of Robot Arm Based on Improved Potential Field Method. Sensors 2023, 23, 3754. [Google Scholar] [CrossRef]
  28. Jain, M.; Saihjpal, V.; Singh, N.; Singh, S.B. An Overview of Variants and Advancements of PSO Algorithm. Appl. Sci. 2022, 12, 8392. [Google Scholar] [CrossRef]
  29. Wu, L.; Huang, X.; Cui, J.; Liu, C.; Xiao, W. Modified adaptive ant colony optimization algorithm and its application for solving path planning of mobile robot. Expert Syst. Appl. 2023, 215, 119410. [Google Scholar] [CrossRef]
  30. Varma, A.P.T. Self-Driving Car Simulation Using Genetic Algorithm. Int. J. Res. Appl. Sci. Eng. Technol. 2020, 8, 514–519. [Google Scholar] [CrossRef]
  31. Freitas, D.; Lopes, L.G.; Dias, F.M. Particle Swarm Optimisation: A Historical Review Up to the Current Developments. Entropy 2020, 22, 362. [Google Scholar] [CrossRef]
  32. Doerner, K.F.; Merkle, D.; Stützle, T. Special Issue on Ant Colony Optimization. Swarm Intell. 2009, 3, 1–2. [Google Scholar] [CrossRef]
  33. Yang, Y.; Li, J.; Peng, L. Multi-Robot Path Planning Based on a Deep Reinforcement Learning DQN Algorithm. CAAI Trans. Intell. Technol. 2020, 5, 177–183. [Google Scholar] [CrossRef]
  34. Li, K.; Hu, Q.; Liu, J. Path Planning of Mobile Robot Based on Improved Multiobjective Genetic Algorithm. Wirel. Commun. Mob. Comput. 2021, 2021, 8836615:1–8836615:12. [Google Scholar] [CrossRef]
  35. Hao, K.; Zhao, J.; Yu, K.; Li, C.; Wang, C. Path Planning of Mobile Robots Based on a Multi-Population Migration Genetic Algorithm. Sensors 2020, 20, 5873. [Google Scholar] [CrossRef] [PubMed]
  36. van Zyl, J.-P.; Engelbrecht, A.P. Set-Based Particle Swarm Optimisation: A Review. Mathematics 2023, 11, 2980. [Google Scholar] [CrossRef]
  37. Chu, H.-S.; Yi, J.; Yang, F. Chaos Particle Swarm Optimization Enhancement Algorithm for UAV Safe Path Planning. Appl. Sci. 2022, 12, 8977. [Google Scholar] [CrossRef]
  38. Nazarahari, M.; Khanmirza, E.; Doostie, S. Multi-Objective Multi-Robot Path Planning in Continuous Environment Using an Enhanced Genetic Algorithm. Expert Syst. Appl. 2019, 115, 106–120. [Google Scholar] [CrossRef]
  39. Abhishek, B.; Ranjit, S.; Shankar, T.; Eappen, G.; Sivasankar, P.; Rajesh, A. Hybrid PSO-HSA and PSO-GA Algorithm for 3D Path Planning in Autonomous UAVs. SN Appl. Sci. 2020, 2, 1–16. [Google Scholar] [CrossRef]
  40. Li, M.; Li, B.; Qi, Z.; Li, J.; Wu, J. Optimized APF-ACO Algorithm for Ship Collision Avoidance and Path Planning. J. Mar. Sci. Eng. 2023, 11, 1177. [Google Scholar] [CrossRef]
  41. Zhang, H.Y.; Lin, W.M.; Chen, A.X. Path Planning for the Mobile Robot: A Review. Symmetry 2018, 10, 450. [Google Scholar] [CrossRef]
  42. Xu, B. Precise path planning and trajectory tracking based on improved A-star algorithm. Meas. Control 2024, 57, 1025–1037. [Google Scholar] [CrossRef]
  43. Wang, M.; Zhu, C.; Wang, F.; Li, T.; Zhang, X. Multi-Factor of Path Planning Based on an Ant Colony Optimization Algorithm. Ann. GIS 2020, 26, 101–112. [Google Scholar] [CrossRef]
  44. Thammachantuek, I.; Ketcham, M. Path Planning for Autonomous Mobile Robots Using Multi-Objective Evolutionary Particle Swarm Optimization. PLoS ONE 2022, 17, e0271924. [Google Scholar] [CrossRef] [PubMed]
  45. Guo, Z. Efficient path planning method based on A-STAR. J. Phys. Conf. Ser. 2023, 2649, 012026. [Google Scholar] [CrossRef]
  46. XiangRong, T.; Yukun, Z.; XinXin, J. Improved A* algorithm for robot path planning in static environment. J. Phys. Conf. Ser. 2021, 1792, 012067. [Google Scholar] [CrossRef]
  47. Karur, K.; Sharma, N.; Dharmatti, C.; Siegel, J.E. A Survey of Path Planning Algorithms for Mobile Robots. Vehicles 2021, 3, 448–468. [Google Scholar] [CrossRef]
  48. Li, J.; Zhang, W.; Hu, Y.; Fu, S.; Liao, C.; Yu, W. RJA-Star Algorithm for UAV Path Planning Based on Improved R5DOS Model. Appl. Sci. 2023, 13, 1105. [Google Scholar] [CrossRef]
  49. Liu, L.; Liang, J.; Guo, K.; Ke, C.; He, D.; Chen, J. Dynamic Path Planning of Mobile Robot Based on Improved Sparrow Search Algorithm. Biomimetics 2023, 8, 182. [Google Scholar] [CrossRef] [PubMed]
  50. Auh, E.; Kim, J.; Joo, Y.; Park, J.; Lee, G.; Oh, I.; Pico, N.; Moon, H. Unloading sequence planning for autonomous robotic container-unloading system using A-star search algorithm. Eng. Sci. Technol. Int. J. 2024, 50, 101610. [Google Scholar] [CrossRef]
  51. Abdel-Rahman, A.S.; Zahran, S.; Elnaghi, B.E.; Nafea, S. Enhanced Hybrid Path Planning Algorithm Based on Apf and A-Star. Int. Arch. Photogramm. Remote Sens. Spat. Inf. Sci. 2023, 48, 867–873. [Google Scholar] [CrossRef]
Figure 1. Path generation results on a grid map: (a) Conventional A* algorithm; (b) OC weighted A* algorithm.
Figure 1. Path generation results on a grid map: (a) Conventional A* algorithm; (b) OC weighted A* algorithm.
Actuators 14 00369 g001
Figure 2. Path generation results on a grid map: (a) OC weighted A* algorithm; (b) OC-PD weighted A* algorithm.
Figure 2. Path generation results on a grid map: (a) OC weighted A* algorithm; (b) OC-PD weighted A* algorithm.
Actuators 14 00369 g002
Figure 3. Path generation results on a grid map with nodes of varying driving environment suitability: (a) OC-PD weighted A*; (b) WIA* algorithm.
Figure 3. Path generation results on a grid map with nodes of varying driving environment suitability: (a) OC-PD weighted A*; (b) WIA* algorithm.
Actuators 14 00369 g003
Figure 4. Nine virtual 2D test environments with varying obstacle configurations and driving suitability regions.
Figure 4. Nine virtual 2D test environments with varying obstacle configurations and driving suitability regions.
Actuators 14 00369 g004aActuators 14 00369 g004b
Figure 5. Three-dimensional virtual environment based on a real-world space: (a) top view of the 3D model; (b) 2D SLAM-generated map.
Figure 5. Three-dimensional virtual environment based on a real-world space: (a) top view of the 3D model; (b) 2D SLAM-generated map.
Actuators 14 00369 g005
Figure 6. Path generation results for Conventional A*, OC weighted A*, OC-PD weighted A*, and WIA* algorithms in three representative 2D test environments. (a) first test environment, (b) second test environment, (c) third test environment.
Figure 6. Path generation results for Conventional A*, OC weighted A*, OC-PD weighted A*, and WIA* algorithms in three representative 2D test environments. (a) first test environment, (b) second test environment, (c) third test environment.
Actuators 14 00369 g006
Figure 7. Paths generated by WIA* algorithm on four grid maps with driving environment suitability variations: (a) grid map with high driving suitability in all regions; (b) grid map with medium driving suitability in two regions; (c) grid map with medium driving suitability in three regions; (d) grid map with medium suitability in four regions and low suitability in one region.
Figure 7. Paths generated by WIA* algorithm on four grid maps with driving environment suitability variations: (a) grid map with high driving suitability in all regions; (b) grid map with medium driving suitability in two regions; (c) grid map with medium driving suitability in three regions; (d) grid map with medium suitability in four regions and low suitability in one region.
Actuators 14 00369 g007
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Baik, S.; Bong, J.H.; Jeong, S. Weight-Incorporating A* Algorithm with Multi-Factor Cost Function for Enhanced Mobile Robot Path Planning. Actuators 2025, 14, 369. https://doi.org/10.3390/act14080369

AMA Style

Baik S, Bong JH, Jeong S. Weight-Incorporating A* Algorithm with Multi-Factor Cost Function for Enhanced Mobile Robot Path Planning. Actuators. 2025; 14(8):369. https://doi.org/10.3390/act14080369

Chicago/Turabian Style

Baik, Seungwoo, Jae Hwan Bong, and Seongkyun Jeong. 2025. "Weight-Incorporating A* Algorithm with Multi-Factor Cost Function for Enhanced Mobile Robot Path Planning" Actuators 14, no. 8: 369. https://doi.org/10.3390/act14080369

APA Style

Baik, S., Bong, J. H., & Jeong, S. (2025). Weight-Incorporating A* Algorithm with Multi-Factor Cost Function for Enhanced Mobile Robot Path Planning. Actuators, 14(8), 369. https://doi.org/10.3390/act14080369

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop