Next Article in Journal
A Preliminary Study of Model-Generated Speech
Previous Article in Journal
Temperature Distribution Characteristics and Action Pattern of Concrete Box Girder under Low-Temperature and Cold Wave Conditions
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Path Planning Method Based on Improved A* and Fuzzy Control DWA of Underground Mine Vehicles

School of Mechanical Engineering, Xi’an University of Science and Technology, Xi’an 710054, China
*
Author to whom correspondence should be addressed.
Appl. Sci. 2024, 14(7), 3103; https://doi.org/10.3390/app14073103
Submission received: 9 March 2024 / Revised: 28 March 2024 / Accepted: 5 April 2024 / Published: 7 April 2024

Abstract

:
In order to solve the problem of low safety and efficiency of underground mine vehicles, a path planning method for underground mine vehicles based on an improved A star (A*) and fuzzy control Dynamic Window Approach (DWA) is proposed. Firstly, the environmental information is analyzed, and the proportion of obstacles is introduced into the A* algorithm to optimize the heuristic function to improve its search efficiency in different environments. Secondly, for the global path, the key node selection strategy is proposed, the node selection method is optimized, and the redundant nodes are deleted. The path is optimized by using a 3 times Clamped-B spline to improve the smoothness of the path. Then, based on the principle of fuzzy control, fuzzy rules are established, and a DWA fuzzy controller is designed to improve the environmental adaptability of the DWA algorithm. Finally, on the basis of the global path, the key node is used as the local target point of the DWA, and the fusion of the improved A* and DWA algorithm is realized. Finally, experiments are conducted to verify the effectiveness and feasibility of the proposed path-planning method. The average deviation of the path is controlled at ±0.109 m, which basically meets the path planning needs of underground mine vehicles.

1. Introduction

With the development of unmanned technology, it has been widely applied in the fields of unmanned vehicles and drones. The working environment underground is harsh, with frequent safety accidents, and mine areas usually operate 24 h a day. Drivers need to overcome their own fatigue, making driving work boring and posing certain safety hazards [1]. Underground scenes have advantages such as relatively simple, closed roads, low traffic volume, fewer people, and low-speed environments compared to urban road scenes. Therefore, the most urgent need for developing autonomous driving technology is in the underground scene.
At present, some scholars have conducted theoretical research on unmanned driving technology for underground mine vehicles. In [2], the modeling and validation of the operation process control of underground unmanned locomotives are researched. In [3], a feasibility study on the unmanned driving of underground explosion-proof vehicles in coal mines based on 4G communication technology has been carried out. In [4], the perception, decision-making, and control of unmanned vehicles in tunnel environments are researched, and the safe and reliable control of underground unmanned trackless rubber-wheeled vehicles is achieved.
Autonomous driving technology provides an important means to achieve the safe, efficient, and intelligent transportation of mine vehicles. It can replace manual labor, improve transportation efficiency, reduce costs, and minimize safety risks. However, the development bottleneck of underground unmanned driving technology is mainly manifested in the following: (1) There is no global positioning system (GPS) signal on the underground roadway, and vehicles cannot realize positioning. (2) The length of underground tunnels is usually more than ten kilometers, and there are multiple corners and forks, so it is difficult to construct large-scale high-precision maps. (3) There are other vehicles in the tunnels, which necessitates a highly accurate vehicle path planning and obstacle avoidance ability. These issues have led to the slow development of underground unmanned vehicles. Therefore, this paper focuses on the path planning problem of underground unmanned mine vehicles to achieve unmanned vehicle navigation, which has significant application prospects and practical significance for liberating workers, reducing costs, and improving the efficiency of the entire transportation system [5].
At present, most scholars have conducted research on urban road vehicles, and there is relatively little research on path-planning methods for underground mine vehicles. In order to improve the transportation efficiency of underground unmanned mine vehicles, this paper proposes a path-planning method suitable for the structure of mine tunnels. The easily implementable A* algorithm is used as the global planning method and the efficient DWA algorithm is used as the local planning method. The reliability and adaptability of the algorithm are improved through optimization and improvement to achieve path planning for underground unmanned mine vehicles. The main contributions are as follows:
(1)
The logarithmic function is introduced to improve the heuristic function coefficient. The adaptive adjustment of the A* algorithm is realized, and the key node selection strategy and 3 times Clamped-B spline are used to optimize and smooth the global path.
(2)
A DWA fuzzy controller based on the fuzzy control principle is proposed and designed, which adjusts the coefficient weight of the DWA evaluation function in real-time by judging the distance between the vehicle, obstacles, and target points.
(3)
A hybrid path planning method based on the improved A* algorithm and the fuzzy control DWA algorithm is proposed, and the global path key points are used as the local target points of the DWA to guide the vehicle and perform dynamic obstacle avoidance.
The remaining sections of this paper are organized as follows. In the second section, the related works on the path-planning methods are briefly reviewed. In the third section, the details of the proposed hybrid method are introduced. In the fourth section, the experimental devices and experimental results are introduced. In the fifth section, the full text is summarized.

2. Related Work

The path planning of underground unmanned mine vehicles refers to the fact that, in the underground tunnel environment, the vehicle finds a collision-free path from the start point to the target point according to certain criteria [6]. Path planning methods are generally divided into global path planning and local path planning [7,8]. Global path planning is a process of quickly and accurately planning the optimal path on a known environmental map, taking into account the principles of shortest path length, lowest vehicle energy consumption, and highest vehicle driving safety based on traffic tasks, using appropriate global path planning algorithms [9]. Local path planning is based on the global path, utilizing sensors to dynamically collect environmental information and generate real-time vehicle paths. [10,11]. At present, global path planning algorithms mainly include A* [12], Dijkstra [13], and rapidly-exploring random trees (RRTs) [14]. Local path planning algorithms include the artificial potential field algorithm (APF) [15], DWA [16], and deep learning method (DL) [17]. Dijkstra [18] uses a breadth-first search, which has the advantages of simple principles and a small amount of computation, but the computational efficiency is low. RRT [19] is a sampling-based algorithm with probabilistic integrity, but the algorithm search is blind, and the convergence speed is slow. The A* algorithm, as a heuristic search algorithm, has the characteristics of simple and easy implementation, a small amount of required computation, and high efficiency. However, when the complexity of the environment increases, the amount of computation required increases sharply, so it is difficult to find the optimal path. At the same time, the path planned by the A* algorithm has many inflection points, which is not conducive to vehicle tracking [20]. APF is an error control strategy with real-time obstacle avoidance, but, when multiple obstacles appear, zero potential energy points are prone to occur, resulting in vehicles being unable to reach the target point [21]. Path planning methods based on DL generally have feedback mechanisms, strong robustness, and good adaptability, but they have a slow convergence speed, high temporal and spatial complexity, and are prone to local convergence [22]. The DWA algorithm transforms the obstacle avoidance problem of the vehicle into the optimal speed execution problem by simulating the path of the vehicle at different speeds and scoring them [23]. The DWA algorithm has significant advantages in dynamic obstacle avoidance, but it is prone to local minima in complex environments, thereby reducing algorithm performance. In [24], an improved A* algorithm that uses different coefficient ratios to find the optimal path by changing the weight of the heuristic function in real-time and improving the smoothness of the path is proposed, and the path length is significantly reduced. In [25], a bidirectional A* algorithm is proposed by considering the factors affecting road escape. The experiment shows that fewer nodes are generated, and the planned path is shorter. In [26], a joint algorithm based on improved A* and APF is proposed. A* is improved by using exponential function weighting and spline interpolation methods. APF is improved by adding correction and escape factors, respectively, making the generated path smoother. In [27], the concepts of the relative velocity potential field and acceleration potential field are proposed in the artificial potential field method to achieve optimal path selection. In [28], A* and DWA are used based on a grid diagram to achieve autonomous path planning for underground vehicles in coal mines. The above examples are all explorations and studies of autonomous path planning in underground mines, but most of the algorithms are still in the simulation and testing stage, and their adaptability to the auxiliary tunnel environment of coal mines needs to be verified.

3. Methods

3.1. Improved A* Algorithm

3.1.1. Optimization Heuristic Function

The A* algorithm obtains the child node with the smallest generation value around the parent node by calculating the cost function and continuously promotes the search as a new node until the target point is searched and the global path search is completed. The cost function can be expressed as
F ( n ) = G ( n ) + H ( n )
where n represents the current node; F ( n ) represents the total proxy value; G ( n ) represents the actual value of n from the start point to the current node; and H ( n ) is the heuristic function, which is the estimated value from the current node n to the target point.
The obstacles on the grid map are quantified and use w to represent the complexity of the environment and to optimize the heuristic function coefficients, as shown in Figure 1.
The percentage of the number of obstacle grids w can be expressed as
w = N 1 + x i x g × 1 + y i y g
where the coordinate of the green spot S at the start point of the vehicle is x i , y i , the coordinate of the red spot G at the target point of the vehicle is x g , y g , and N is the number of obstacle grids in the rectangular grid area composed of the start point to the target point (N is not zero).
The Euclidean distance is selected as the heuristic function that can be expressed as
H ( n ) = ( x i x g ) 2 + ( y i y g ) 2
The improved A* algorithm can be expressed as
F ( n ) = G ( n ) + ln ( 1 + H ( n ) w ) H ( n )
where w is introduced into the evaluation function H ( n ) and a logarithmic function is used to weigh. When w decreases, the coefficient of the heuristic function slowly increases. The search efficiency of A* is accelerated, and the sensitivity is improved. When w increases, the coefficient of the heuristic function gradually decreases. The search range of A* is expanded, which prevents it from getting stuck in local optimal and completing the adaptive adjustment of the evaluation function.

3.1.2. Key Node Selection Strategy

This paper proposes a key node selection strategy, based on the following principles: It is assumed that the red nodes M , P , Q are three contiguous nodes on the global path. If λ M P = λ P Q is satisfied, that is, three points are collinear, it indicates that P is a redundant node, P can be deleted, and the path set becomes M , Q , as shown in Figure 2.
If the red nodes M , P , Q are not collinear, that is, λ M P λ P Q , then whether or not there are obstacles between M and Q is determined, if so, then P is the key node and needs to be retained, and the path set is M , P , Q . If there is no obstacle between M and Q, P is a redundant node, and P can be eliminated, and the path set is M , Q . As shown in Figure 3.

3.1.3. Path Smoothing

In order to meet the requirements of the smoothness of the vehicle driving path and the curvature of the vehicle turning, it is necessary to smooth the path to ensure the feasibility of the path. In this paper, Clamped-B splines are compared with different degrees [29], as shown in Figure 4. The results show that the 3 times Clamped-B spline is closer to the original contour and meets the actual requirements, so the 3 times Clamped-B spline is used to smooth the path.

3.1.4. Simulation Experiment

In order to test the effectiveness of the improved A* algorithm, two scenarios (with a map size of 100 × 100) are set up to carry out simulation experiments via MATLAB. We compared traditional A*, extended A* [30], and improved A* in this paper. The results are shown in Figure 5, where the green rectangle indicates the start point and the red circle indicates the target point.
Table 1 shows the comparison of the number of nodes, planning time, and path length results of the three algorithms in the two experimental environments.
Table 1 shows that, in Scenario 1, the improved A* algorithm, compared to the A* and the extended A*, resulted in a decrease of 16.86% and 13.85% in the number of path nodes, a decrease of 12.91% and 3.56% in the algorithm planning time, and a decrease of 6.23% and 3.04% in the path length, respectively. In Scenario 2, the improved A* algorithm showed decreases of 16.74% and 9.57% in the number of nodes, 12.19% and 8.55% in the algorithm planning time, and 6.37% and 4.98% in the path length, respectively, when compared to the A* and the expanded A*. These results indicate that in different obstacle environments, compared to the A* and the extended A*, the improved A* algorithm significantly reduces the number of nodes and path length and has superior performance in path search.

3.2. Improved DWA Algorithm

3.2.1. DWA Algorithm

The DWA algorithm predicts the trajectory of a vehicle within a given time interval through a velocity window, evaluates these trajectories using an evaluation function, and selects the optimal trajectory and corresponding speed to achieve local dynamic obstacle avoidance [1]. The trajectory evaluation function can be shown as
G ( v , ω ) = σ ( α   h e a d ( v , ω ) + β   d i s t ( v , ω ) + γ v e l ( v , ω ) )
where G ( v , ω ) represents the position of the vehicle; h e a d ( v , ω ) represents the azimuthal deviation of the end of the simulated path from the target point; d i s t ( v , ω ) represents the distance of the end of the simulated path from the nearest obstacle; v e l ( v , ω ) represents the linear velocity of the simulated path; α , β , γ are the weighting coefficient of each subfunction; and σ is a normalisation parameter.

3.2.2. DWA Fuzzy Controller Design

Based on the principle of fuzzy control [31], a DWA fuzzy controller is designed which adjusts the weight coefficients in real-time according to environmental information variables to enhance the environmental adaptability of the algorithm.
  • Fuzzification
Inputs: The distance of the vehicle from the target point G-dist (G), the distance of the vehicle from the nearest obstacle O-dist (O). The fuzzy definition of input quantities: The fuzzy set of G is defined as {S,M,L}, that is, the distance between the corresponding vehicle and the target point is near (the red line), medium (the green line), and far (the purple line), and the domain is [0, 2]. The definition of the O fuzzy set is also {S,M,L}, where the distance of the vehicle from the nearest obstacle is near (the red line), medium (the green line), and far (the purple line), and the domain is [0, 3]. The membership functions of the fuzzy sets G and O are shown in Figure 6.
The output quantities are α, β, and γ, and the fuzzy sets of α, β, and γ are defined as {S,M,L}, that is, the corresponding weights are small (the red line), medium (the green line), and large (the purple line), and the domains are all [0, 1]. The membership function is shown in Figure 7.
  • Establish fuzzy rules.
The table of fuzzy control rules designed in this paper is shown in Table 2.

3.2.3. Simulation Experiment

In order to compare the environmental adaptability of the DWA algorithm and the improved DWA algorithm, 50 path planning simulation experiments are conducted in three experimental scenarios. The relevant parameter configuration is shown in Table 3, and the simulation experiment data are shown in Table 4.
In the Scenario 1 experiment, as shown in Figure 8, where the red rectangle represents the start point, and the yellow circle represents the target point. From the curve of change, the vehicle moves towards the obstacle and is far from the target point, the fuzzy controller prioritizes obstacle avoidance and outputs a larger β, a smaller α, and a moderate γ. As the vehicle gradually approaches the target point, around the number of iterations 360, the vehicle begins to approach the target point and moves away from obstacles. Finally, the fuzzy controller outputs a larger α, a moderate β, and a smaller γ to ensure that the vehicle slowly approaches the target point.
In the Scenario 2 comparison experiment, as shown in Figure 9, where the red rectangle represents the start point, and the yellow circle represents the target point. The distance between the initial vehicle and the obstacle and the target point is large, and the output of the fuzzy controller is a larger α and γ, and a moderate β, accelerating towards the target point. As the vehicle approaches the obstacle, priority is given to obstacle avoidance (the number of iterations is about 150), the β gradually increases, and the α and γ gradually decrease. As the vehicle gradually approaches the target point and moves away from the obstacle (about 375 iterations), the distance between the vehicle and the obstacle and the distance to the target point are both moderate and, at this time, the output is a moderate α and β, and a smaller γ.
In the Scenario 3 comparison experiment, as shown in Figure 10, where the red rectangle represents the start point, and the yellow circle represents the target point. Firstly, the distance between the vehicle and the obstacle and the target point is relatively large, resulting in a larger α and γ, and a moderate β, and the vehicle quickly moves towards the target point. As the obstacle slowly approaches, the output is a larger β, a moderate γ, and a smaller α, giving priority to ensuring the obstacle avoidance needs of the vehicle. Finally, when the distance between the vehicle and the target point and the obstacle is small (about 370 iterations), the fuzzy controller outputs a moderate α and β, and a smaller γ, to ensure the safety of the vehicle while approaching the target point.
From Table 4, the average planning time of the DWA algorithm is 225.044 s, and the average planning time of the improved DWA algorithm is 232.528 s. In the three experimental environments, the average path length of the improved DWA is shortened by 5.90%, 2.02%, and 3.45% compared to the DWA, respectively. From the above analysis, it can be seen that, although the improved DWA algorithm sacrifices a certain amount of time, the environmental adaptability of the algorithm is enhanced, and its success rate in the three environments is very high.

3.3. Fusion of Path Planning Method

The combination of the global path planning method and local path planning method is used to realize the path planning of the vehicle. The specific steps are as follows:
Step 1: The initial environment map is obtained.
Step 2: The coordinate sequence of the global critical path nodes of the improved A* is recorded, and the global key nodes are regarded as local target points.
Step 3: The distance between the current position of the vehicle and the local target point is determined, if the distance is less than the threshold, it is considered that the local target point has been reached, and the local target point is updated to continue local planning.
Step 4: When the local target point is not the last node in the global target point sequence, the next local target point is updated, and Step 3 will be repeated.
Step 5: When the local target point is the last node of the global sequence, the entire path planning is completed.
As shown in Figure 11, when the vehicle moves along the global path from the start point S, the key nodes n 1 , n 2 , n 3 , n 4 guide the vehicle separately to perform local planning and move towards the target point T.

4. Experiments

4.1. Experimental Settings

In order to verify the effectiveness of the path planning method, this experiment is carried out through the intelligent car experimental platform. The structure of the indoor long corridor is similar to that of underground tunnels, so it is chosen as the experimental scene, as shown in Figure 12.
The relevant parameters of the experimental vehicle are shown in Table 5, and the experimental device information is shown in Table 6.

4.2. Analysis of Experimental Results

  • Unknown environment
Experiment 1 is a path planning experiment conducted in an unknown environment with obstacles. Two sets of unknown obstacles are added to the known global map to form an unknown environment map, which is used to test the effectiveness of local path planning. The results are shown in Figure 13, A is defined as the start point and B is defined as the target point.
It can be seen from Figure 13 that the three algorithms can avoid obstacles and successfully reach the target point. However, the deviation between the path planned by the other two algorithms and the central axis of the tunnel excavation area is relatively large, which does not meet the requirements of underground mine vehicles. The deviation between the path planned by the fusion algorithm and the central axis of the simulated tunnel excavation area is generally small, with an average deviation controlled at ± 0.109   m , and the maximum deviation is ± 0.214   m at the corner. The path planned by the hybrid algorithm is smoother and more reasonable when the vehicle avoids obstacles.
  • Dynamic environment
This is a dynamic obstacle path planning experiment for the three algorithms mentioned above. The yellow dot represents the obstacle moving at a constant speed. A is defined as the start point. B is defined as the target point. The result is shown in Figure 14.
In Figure 14, it can be seen that the paths planned by the A*+DWA and A*+APF algorithms cannot smoothly bypass dynamic obstacles, and the generated paths are not smooth enough. Before encountering dynamic obstacles, the fusion algorithm can predict the current path and choose a safer path to bypass the obstacles. The path security is better, and the path basically conforms to the global path, with a smoother path, ensuring the global optimum of the path.

5. Conclusions

In this paper, the heuristic function of the A* algorithm is logarithmically weighted by introducing the proportion of environmental obstacles. The key node selection strategy and the 3 times Clamped-B spline are adopted to optimize and smooth the path. A DWA fuzzy controller is designed based on the principle of fuzzy control. Through simulation experiments, the improved hybrid path planning method is validated. The average deviation is controlled at ± 0.109   m , and the maximum deviation, which occurred at the corner, is ± 0.214   m . The results showed that, compared to other methods, the path planned by the proposed method is safer, more reasonable, and more in line with the global path, which is beneficial for vehicle tracking and driving.
Due to limitations in experimental conditions, it is currently not possible to achieve experimental verification of a real underground mine environment. At present, the application of underground mine drones has become a trend, so subsequent research will expand from path planning in 2D scenes to path planning in 3D scenes.

Author Contributions

Conceptualization, C.Z. and X.Y.; methodology, C.Z. and X.Y.; software, R.Z.; validation, X.Y. and Z.G.; formal analysis, X.Y.; investigation, C.Z.; resources, C.Z.; data curation, R.Z.; writing—original draft preparation, X.Y.; writing—review and editing, X.Y. and R.Z.; visualization, C.Z.; supervision, C.Z.; project administration, C.Z.; funding acquisition, C.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This paper was funded by the Shaanxi Innovation Talent Promotion Plan—Science and Technology Innovation Team (2021TD-27) and the 2022 Youth Innovation Team Construction Scientific Research Program of Shaanxi Provincial Education Department (22JP045).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Hao, J.W.; Xiang, H.M. Obstacle avoidance path planning of mobile robot based on improved DWA. J. Phys. 2022, 2383, 012098. [Google Scholar]
  2. Jian, B.W.; Jiang, H.H.; Zhen, C.W. Modeling and verification of the operation process control of underground unmanned locomotives. J. Hefei Univ. Technol. 2018, 41, 773–779. [Google Scholar]
  3. Jin, Y. Feasibility study on unmanned driving of explosion-proof vehicles in coal mines based on 4G communication technology. Coal Mine Mach. 2016, 6, 186–188. [Google Scholar]
  4. Kai, C.; Zhi, G.L.; Xiao, M.Y. Research on unmanned driving system of trackless rubber-tyred vehicle in coal mine. J. Mine Autom. 2022, 6, 36–48. [Google Scholar]
  5. He, H.T.; Liao, Z.W.; Guo, W. Research and exploration of driverless technology of derackless rubber wheel car in coal mine. Coal Sci. Technol. 2022, 50, 212–217. [Google Scholar]
  6. Xiao, B.Z.; Xiang, Y. Trajectory Planning and Tracking Strategy Applied to an Unmanned Ground Vehicle in the Presence of Obstacles. IEEE Trans. Autom. Sci. Eng. 2021, 18, 1575–1589. [Google Scholar]
  7. Abdallaoui, S.; Aglzim, E.-H.; Chaibet, A.; Kribèche, A. Thorough Review Analysis of Safe Control of Autonomous Vehicles: Path Planning and Navigation Techniques. Energies 2022, 15, 1358. [Google Scholar] [CrossRef]
  8. 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]
  9. Yu, X.W. Reform and development of coal mine safety in China: An analysis from government supervision, technical equipment, and miner education. Resour. Policy 2022, 77. [Google Scholar]
  10. Thi Thao, M.; Cosmin, C. Heuristic approaches in robot path planning: A survey. Robot. Auton. Syst. 2016, 86, 13–28. [Google Scholar]
  11. Lun, Q.; Lun, X.H. Survey of UAV motion planning. IET Cyber-Syst. Robot. 2020, 2, 14–21. [Google Scholar]
  12. Lin, Z.; Wu, K.; Shen, R.; Yu, X.; Huang, S. An Efficient and Accurate A-star Algorithm for Autonomous Vehicle Path Planning. IEEE Trans. Veh. Technol. 2023, 3348140, 1–6. [Google Scholar] [CrossRef]
  13. Zhou, P.; Xie, Z.; Zhou, W.; Tan, Z. A Heuristic Integrated Scheduling Algorithm Based on Improved Dijkstra Algorithm. Electronics 2023, 12, 4189. [Google Scholar] [CrossRef]
  14. Wu, B.; Zhang, W.; Chi, X.; Jiang, D.; Yi, Y.; Lu, Y. A Novel AGV Path Planning Approach for Narrow Channels Based on the Bi-RRT Algorithm with a Failure Rate Threshold. Sensors 2023, 23, 7547. [Google Scholar] [CrossRef]
  15. Li, M.; Li, B.; Qi, Z.; Li, J.; Wu, J. Optimized APF-ACO Algorithm for Ship Collision Avoidance and Path Planning. Mar. Sci. Eng. 2023, 11, 1177. [Google Scholar] [CrossRef]
  16. Wang, Q.; Li, J.; Yang, L.; Yang, Z.; Li, P.; Xia, G. Distributed Multi-Mobile Robot Path Planning and Obstacle Avoidance Based on ACO–DWA in Unknown Complex Terrain. Electronics 2022, 11, 2144. [Google Scholar] [CrossRef]
  17. Pan, Y.; Yang, Y.; Li, W. A deep learning trained by genetic algorithm to improve the efficiency of path planning for data collection with multi-UAV. IEEE Access 2021, 9, 7994–8005. [Google Scholar] [CrossRef]
  18. Chen, R.; Hu, J.; Xu, W. An RRT-Dijkstra-Based Path Planning Strategy for Autonomous Vehicles. Appl. Sci. 2022, 12, 11982. [Google Scholar] [CrossRef]
  19. Li, X.; Tong, Y. Path Planning of a Mobile Robot Based on the Improved RRT Algorithm. Appl. Sci. 2024, 14, 25. [Google Scholar] [CrossRef]
  20. Zen, L.W. Improved A* algorithm and model predictive control- based path planning and tracking framework for hexapod robots. Ind. Robot 2023, 50, 135–144. [Google Scholar]
  21. Li, S.L.; Bin, W.; Hui, X. Research on Path-Planning Algorithm Integrating Optimization A-Star Algorithm and Artificial Potential Field Method. Electronics 2022, 11, 3660. [Google Scholar] [CrossRef]
  22. Algabri, R.; Choi M, T. Target recovery for robust deep learning-based person following in mobile robots: Online trajectory prediction. Appl. Sci. 2021, 11, 4165. [Google Scholar] [CrossRef]
  23. Tian, Y.L.; Rui, X.Y.; Guang, R.W.; Lei, S. Local Path Planning Algorithm for Blind-guiding Robot Based on Improved DWA Algorithm. Chin. Control. Decis. Conf. 2019, 31, 871–875. [Google Scholar]
  24. Hong, J.Z. Research on the path planning of coal mine scene inspection robot. Coal Mine Mach. 2022, 43, 45–47. [Google Scholar]
  25. Meng, J.L.; Xi, A.Z.; Zhan, G.W.; De, M.L. Research on the application of mine flood escape path based on bidirectional A* algorithm. Coal Eng. 2019, 51, 42–47. [Google Scholar]
  26. Jiu, S.B.; Mu, M.Z.; Shi, R.G. Based on the improved A * and artificial potential field algorithm Path planning. J. China Coal Soc. 2022, 47, 1347–1360. [Google Scholar]
  27. Zi, J.T.; Xue, H.G. Path planning of mine navigation device based on improved artificial potential field. J. China Coal Soc. 2016, 41, 589–597. [Google Scholar]
  28. Yuan, X.M.; Ming, R.H. Research on the key technology of mine-assisted transportation robot. Ind. Mine Autom. 2020, 46, 8–14. [Google Scholar]
  29. Noreen, I. Collision Free Smooth Path for Mobile Robots in Cluttered Environment Using an Economical Clamped Cubic B-Spline. Symmetry 2020, 12, 1567. [Google Scholar] [CrossRef]
  30. Zhen, Z.; Hua, L.Z. Real Time Path Planning of Robot by Combing Improved A∗ Algorithm and Dynamic Window Approach. Radio Eng. 2022, 52, 1984–1993. [Google Scholar]
  31. Lin, Z.; Yue, M.; Chen, G.; Sun, J. Path planning of mobile robot with PSO-based APF and fuzzy-based DWA subject to moving obstacles. Trans. Inst. Meas. Control. 2022, 44, 121–132. [Google Scholar] [CrossRef]
Figure 1. Quantifying obstacle information.
Figure 1. Quantifying obstacle information.
Applsci 14 03103 g001
Figure 2. Three-point collineation.
Figure 2. Three-point collineation.
Applsci 14 03103 g002
Figure 3. Three-point non-colinear.
Figure 3. Three-point non-colinear.
Applsci 14 03103 g003
Figure 4. Results of Clamped-B spline fitting with different number of times.
Figure 4. Results of Clamped-B spline fitting with different number of times.
Applsci 14 03103 g004
Figure 5. Three algorithm simulation comparison experiments. (a) Comparison of experimental results in Scenario 1; (b) comparison of experimental results in Scenario 2.
Figure 5. Three algorithm simulation comparison experiments. (a) Comparison of experimental results in Scenario 1; (b) comparison of experimental results in Scenario 2.
Applsci 14 03103 g005
Figure 6. Membership functions for fuzzy sets G and O. (a) G’s membership function; (b) O’s membership function.
Figure 6. Membership functions for fuzzy sets G and O. (a) G’s membership function; (b) O’s membership function.
Applsci 14 03103 g006
Figure 7. The membership function of α, β, and γ. (a) α’s membership function. (b) β’s membership function. (c) γ’s membership function.
Figure 7. The membership function of α, β, and γ. (a) α’s membership function. (b) β’s membership function. (c) γ’s membership function.
Applsci 14 03103 g007
Figure 8. Simulation experiment results of Scenario 1. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Figure 8. Simulation experiment results of Scenario 1. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Applsci 14 03103 g008
Figure 9. Simulation experiment results of Scenario 2. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Figure 9. Simulation experiment results of Scenario 2. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Applsci 14 03103 g009
Figure 10. Simulation experiment results of Scenario 3. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Figure 10. Simulation experiment results of Scenario 3. (a) The resulting graph of the path comparison experiment; (b) output variation chart.
Applsci 14 03103 g010
Figure 11. Global path information guides local planning.
Figure 11. Global path information guides local planning.
Applsci 14 03103 g011
Figure 12. Simulated experimental scene.
Figure 12. Simulated experimental scene.
Applsci 14 03103 g012
Figure 13. Comparison of experiments on three path planning algorithms in an unknown environment. (a) The results of the A*+DWA path planning experiment; (b) the results of the A*+APF path planning experiment; (c) the results of the fusion method path planning experiment.
Figure 13. Comparison of experiments on three path planning algorithms in an unknown environment. (a) The results of the A*+DWA path planning experiment; (b) the results of the A*+APF path planning experiment; (c) the results of the fusion method path planning experiment.
Applsci 14 03103 g013
Figure 14. Comparison of experiments of three path planning algorithms in a dynamic environment. (a) The results of the A*+DWA path planning experiment; (b) the results of the A*+APF path planning experiment; (c) the results of the fusion method path planning experiment.
Figure 14. Comparison of experiments of three path planning algorithms in a dynamic environment. (a) The results of the A*+DWA path planning experiment; (b) the results of the A*+APF path planning experiment; (c) the results of the fusion method path planning experiment.
Applsci 14 03103 g014
Table 1. Comparison of simulation results for three environments.
Table 1. Comparison of simulation results for three environments.
AlgorithmNumber of NodesPlanning Time (ms)Path Length
Scenario 1A*172213.915159.682
Extended A*166193.178154.424
Improved A*143186.308149.731
Scenario 2A*227562.713231.812
Extended A*209540.341228.453
Improved A*189494.104217.036
Table 2. Table of fuzzy rules.
Table 2. Table of fuzzy rules.
Rule NumberInputOutput
GOαβγ
1SSMMS
2SMLMS
3SLLSS
4MSMMS
5MMMMM
6MLMSM
7LSSLM
8LMSLM
9LLLML
Table 3. Parameter configuration of simulation experiment.
Table 3. Parameter configuration of simulation experiment.
ParameterValueParameterValue
α0.15Maximum angular rate60 rad/s
β0.4Maximum linear acceleration0.1 m/s2
γ0.3Trajectory prediction time2 s
Maximum linear speed1 m/s
Table 4. Simulation experiment data results of three experimental environments.
Table 4. Simulation experiment data results of three experimental environments.
ExperimentAlgorithmPlanning Time (s)Path LengthSuccess Rate
Scenario 1DWA235.172196.34290%
improved DWA246.374184.75196%
Scenario 2DWA219.532174.28594%
improved DWA224.784170.76498%
Scenario 3DWA220.429175.47986%
improved DWA226.425169.42796%
Table 5. Structural parameters of the vehicle.
Table 5. Structural parameters of the vehicle.
NameParameters
Shape2490 × 1550 × 616 mm
Bearing spacing1900 mm
Wheel spacing1355 mm
Maximum speed40 km/h
Steering typeFour-wheel steering
Braking typeFour-wheel disc brake
Table 6. Information on experimental devices.
Table 6. Information on experimental devices.
EquipmentModel
ComputerCPU i7-9700
Graphics card
RTX3060
LIDARVelodyne VLP-16
IMULPMS-IG1
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

Zhang, C.; Yang, X.; Zhou, R.; Guo, Z. A Path Planning Method Based on Improved A* and Fuzzy Control DWA of Underground Mine Vehicles. Appl. Sci. 2024, 14, 3103. https://doi.org/10.3390/app14073103

AMA Style

Zhang C, Yang X, Zhou R, Guo Z. A Path Planning Method Based on Improved A* and Fuzzy Control DWA of Underground Mine Vehicles. Applied Sciences. 2024; 14(7):3103. https://doi.org/10.3390/app14073103

Chicago/Turabian Style

Zhang, Chuanwei, Xinyue Yang, Rui Zhou, and Zhongyu Guo. 2024. "A Path Planning Method Based on Improved A* and Fuzzy Control DWA of Underground Mine Vehicles" Applied Sciences 14, no. 7: 3103. https://doi.org/10.3390/app14073103

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