Abstract
Path planning is one of the most popular researches on mobile robots, and it is the key technology to realize autonomous navigation of robots. Aiming at the problem that the mobile robot may collide or fail along the planned path in an environment with random obstacles, a robot path planning scheme that combines the improved A algorithm with an enhanced dynamic window method is proposed. In the improved A algorithm, in order to improve the algorithm efficiency, so that a single planning path can pass through multiple target points, the search point selection strategy and evaluation function are optimized. In order to achieve local obstacle avoidance and pursuit of dynamic target points in dynamic and complex environments, an online path planning method combining enhanced dynamic window algorithm and global path planning information is proposed. The preview deviation angle tracking method is used to successfully capture moving target points. It also improves the efficiency of path planning and ensures that on the basis of the global optimal path, the random obstacle can be avoided in real time so that the robot can reach the target point smoothly. The simulation results show that compared with other methods, the proposed method achieves excellent global and local path planning performance, the planned trajectory is smoother, and the search efficiency is higher in complex environments.
1. Introduction
Mobile robot is an important branch of robotics research [1]. With the continuous development of the world economy and technology, mobile robots appear more and more frequently in scientific research, production environment, and daily life [2]. At the same time, with the development of computers and control technology, the application fields of mobile robots are becoming more and more extensive [3].
Mobile robot needs to plan a path from the initial position to the target position in the work scene. The path should meet a series of requirements such as short length, high efficiency, and high safety, and it must be able to avoid static and dynamic obstacles along the way [4]. At the same time, mobile robots should have certain computing capabilities to calculate the shortest and safest route in real time to save time and reserve energy [5].
According to the characteristics of mobile robot path planning, it can be divided into the intelligent search algorithm, artificial intelligence algorithm, geometric model algorithm, and local obstacle avoidance algorithm [6]. The intelligent search algorithm uses randomly generated initial solutions or sampling points to approach the optimal solution through multiple iterations. The biggest characteristic of this type of algorithm is randomness, so its solution is not unique [7]. Algorithms based on artificial intelligence include methods such as Q learning and deep learning, but such methods require a large number of different types of training samples, which limit their practicality in the real world [8].
The geometric model-based path planning method is to construct a geometric model on the basis of known environment, then select an appropriate path, and adjust the feasible solution based on the optimal strategy in real-time [9]. The paths obtained by such methods are all nonsmooth paths, so optimization is needed to achieve the smooth turning of the mobile robot. Such methods include A algorithm, Voronoi graph, and so on. In the global path planning, the A algorithm will select the square with the lowest current cost value until the search reaches the end, thereby planning the path with the lowest total costs. However, the traditional A algorithm suffers from poor global optimization capability, and there are too many redundant points and inflection points in the planned path [10].
The local obstacle avoidance algorithm is used to enhance the obstacle avoidance ability of mobile robots and improve safety. It aims to move the robot away from obstacles and plan a safe collision-free path. Commonly used local obstacle avoidance algorithms include artificial potential field method, dynamic window approach (DWA), and so on [11]. The DWA is a method of sampling the surroundings at the current moment to obtain the robot’s action state at the next moment. This method can quickly reach the target point while avoiding collisions between the robot and obstacles in the search space. However, it is highly dependent on global parameters and is prone to failure in unknown environments [12].
In order to solve the above problems, this paper proposes a random obstacle avoidance method for mobile robots that combines the improved A algorithm with an enhanced dynamic window approach (EDWA), which takes into account the smoothness of the planned path and the search efficiency of the A algorithm. Then based on the global planning path information and dynamic environment changes, the EDWA is used to complete the local path planning, so as to make up for the shortcomings of the traditional A algorithm with poor timeliness. The proposed method pursues dynamic obstacles on the basis of global path planning information, thereby planning the optimal path and improving real-time performance and flexibility.
The rest of this paper is organized as follows: the second part is the related work, which introduces the existing advanced robot path planning methods. The third part is the improved A algorithm. The fourth part is the enhanced version of the dynamic window method. The fifth part is the experimental part. The sixth part is the conclusion.
2. Related Methods
The A algorithm has the advantages of short planned paths and fast calculation speed, and it is a widely used global path planning method. Yuan and Han [13] successfully implement the improved A algorithm to achieve robot path planning in a static environment. Yu et al. [14] use an improved Dijkstra algorithm to complete global path planning, but its local path search speed is very slow, and a smooth and safe optimal path cannot be quickly planned. Kaplan et al. [15] introduce an improved multiorder B-spline curve for path smoothing, but this method cannot complete the smoothing of the dynamic path, and the running process is cumbersome. The efficiency of the algorithm is poor. When the environment changes or the robot is affected by other external factors, the established path will fail.
Artificial potential field method and DWA are currently widely used local path planning methods. Aiming at the problem that the robot is regarded as a single point in most planning, which leads to the problem of being unable to pass the narrowband, Kiss and Tevesz [16] propose a global dynamic window navigation scheme based on model predictive control in which the weighted objective function is omitted. Aiming at the energy consumption problem in the path planning process, Henkel et al. [17] propose an efficient local path planner suitable for omnidirectional mobile robot navigation in a dynamic environment. The experimental results show that compared with the DWA algorithm, the energy consumption is reduced by 9.79%.
In practical applications, robots often encounter unexpected obstacles such as unknown obstacles during the planning process, which may cause the robots to collide. Therefore, many methods combine the strong obstacle avoidance ability of local path planning algorithms with global path planning methods to improve performance. Aiming at the problem that the classic A algorithm cannot be applied in a dynamic environment, Zhong et al. [18] propose a hybrid method combining improved A algorithm and DWA algorithm. Experimental results show that the path planned by the improved algorithm is smoother and more efficient. But the disadvantage of this method is that it is only applicable to target points in the same direction. Wu et al. [19] propose a hybrid algorithm combining beetle antenna search algorithm and artificial potential field algorithm for the dynamic path planning problem. The experimental results verify the effectiveness and superiority of the method. The method proposed by Kashyap et al. [20] combines the DWA algorithm and teaching and learning optimization. Path planning and obstacle avoidance can be successfully implemented in both the dynamic terrain and the dynamic terrain.
For the path planning problem of mobile robots in complex environments, Ma et al. [21] propose a method combining improved A algorithm, minimum snap trajectory generation, and the timed elastic band, which improves the efficiency and flexibility of mobile robot path planning. The experimental results show that this method can shorten the length of the planned path, reduce the total turning angle, and effectively complete the global optimal path planning and local real-time obstacle avoidance.
3. Improved A Algorithm
3.1. Traditional A Algorithm
The A algorithm is a heuristic search algorithm that obtains the planned path of the mobile robot by continuously searching for the path approaching the destination. This method is simple and fast, and the heuristic search is very targeted. It only needs to search a part of the state space of the problem, so it can achieve the purpose of narrowing the search range and reducing the complexity of the problem, and the path finding efficiency is very high.
The A algorithm can be expressed as follows:where n is the current node, f(n) is the cost value of the optimal path from the starting node to the target point, and is the depth factor, which is the cost of the optimal path from the starting node to node n found by the heuristic search algorithm. h(n) is an estimated cost value of the optimal path from node n to the target node. The value of each decision is evaluated according to the evaluation function, and it is decided which scheme to try first in order to obtain the shortest path.
3.2. Improved A Algorithm
The traditional A algorithm has the following two shortcomings: (1) there are too many searching nodes, which affect the computational efficiency and (2) the path obtained by the A algorithm has redundant collinear nodes and redundant turning points. The robot walking along such a path will affect its movement continuity.
In view of the above problems, this paper proposes two improvements to the A algorithm: (1) in order to improve the searching efficiency, an optimized search point selection strategy is proposed, and the heuristic function is improved; (2) in order to further optimize the path, the redundant point deletion strategy is introduced. Redundant nodes are eliminated so that the final path contains only the starting point, end point, and key turning points.
3.2.1. Optimization of Search Point Selection Strategy
The traditional A algorithm expands the eight neighborhood grids of the current node during path planning. As shown in Figure 1, the pink grid is the current point, and n1 to n8 are the eight directions in which the current grid can move. Too many options of the orientation for the target point will cause unnecessary grids in the eight-neighbor grids, resulting in a waste of computing time and storage space.

In order to further improve the searching efficiency, an optimized search point selection strategy is introduced. According to the relative position of the target point and the current point, three search directions are discarded, and five search directions are retained. Let the angle between the segment from the target point to the current point and the direction of n2 as ε, then the corresponding relationship between the angle ε and the 3 discarded directions is shown in Table 1. After the above optimization, the number of search nodes can be reduced, and the computational efficiency can be improved.
3.2.2. Heuristic Function of the Optimization Algorithm
The traditional A algorithm will traverse many unnecessary nodes during the path searching process, which affects the searching efficiency. The key factor causing this problem is the heuristic function design of the A algorithm. If the estimated value of the heuristic function is less than the actual cost value, too many search nodes will be generated, reducing the computational efficiency, though the optimal path can be obtained. However, if the estimated value of the heuristic function is greater than the actual cost value, a relatively smaller number of searching nodes will be generated, which will improve efficiency, but it is difficult to obtain an optimal path. When the estimated value of the heuristic function is equal to the actual cost value, the highest search efficiency can be achieved. Since the heuristic function adopts Euclidean distance, the value of the heuristic function will always be less than or equal to the actual distance from the current point to the target point. When the current point is far from the target point, the estimated value of the heuristic function is much smaller than the actual value, which will cause the algorithm to search for more nodes and reduce efficiency. At this time, the weight of the estimated value should be increased to improve efficiency. When the current point is gradually approaching the target point, the estimated value gradually approaches the actual value. In order to prevent the estimated value from being too large and to avoid failure in searching for the optimal path, the estimated value weight should be reduced accordingly. In summary, we propose to improve the cost function as follows:where f(n) is the integrated cost value, h(n) is the estimated cost value from the current point to the target point, is the actual cost value from the starting point to the current point, R is the distance from the starting point to the target point, and r is the distance between the current point and the target point.
3.2.3. Multiobjective Optimization
The traditional A algorithm is only suitable for searching a single target point, and it has the shortcomings of low searching efficiency and poor compatibility. Nowadays, the work situation is complicated, and the tracking of multiple target points in one planning can greatly improve efficiency. Therefore, the proposed method first samples and compares the location information of the target points and then improves the searching algorithm to consider multiple target points in one planning.
The priority of different target points is an important prerequisite for multitarget path planning. The Euclidean distance is used as the cost function of selecting the optimal target point. The lower the selection cost, the higher the priority level. Specific steps are as follows:
(1) Calculate the cost function of the target points Ti, i = 1, 2, …, n; (2) compare the priority levels of the target points Ti; (3) preferentially plan the path for the target point Ti with the highest priority; (4) take the current target point Ti−1 as the starting point of the mobile robot and plan the path of the secondary target point Ti; and (5) judge whether to reach the n-th target point. If it arrives, stop searching; otherwise, go back to the last step.
4. Enhanced Dynamic Window Approach
In this paper, an enhanced dynamic window algorithm (EDWA) is proposed, which combines global path information to avoid obstacles and pursue dynamic targets. Even part of the environment information is unknown, the mobile robot can still perform local path planning, avoid obstacles, and reach the designated target point.
4.1. Kinematics Model of Mobile Robot
DWA mainly samples the speed space of the mobile robot in the window area and simulates the feasible motion trajectory within time t in the speed space . The changes of the linear velocity and the angular velocity ωt in the velocity space represent the motion states of the mobile robot. Among all feasible trajectories, the optimal trajectory is obtained with the evaluation function. Therefore, assuming that the mobile robot moves within the time interval Δt, the kinematics model can be formulated as follows [22]:
4.2. Speed Sampling of Mobile Robot
There are an infinite number of groups in the velocity space, but in actual operation, it is necessary to constrain the sampling velocity range based on the constraints of the mobile robot as well as environmental constraints.
The speed constraints of mobile robots can be expressed as follows:
In the moving time interval of the dynamic window, the speed constraint of the mobile robot caused by the addition and subtraction constraints of the motor can be calculated as follows:where and ωc denote current speed, and denote the maximum acceleration of the mobile robot, and and denote the maximum deceleration of the mobile robot.
Mobile robot braking distance constraint: when avoiding obstacles in a local environment, the safety of the mobile robot needs to be ensured. Under the constraint of maximum deceleration, the speed can be reduced to 0 m/s before the impact. The braking constraint is expressed as follows:where d(, ω) represents the shortest distance between the trajectory (, ω) and the obstacle.
4.3. Evaluation Function Considering Global Path Information
After simulating several trajectories based on the range of motion speed and the robot motion model, the optimal trajectory is obtained through the evaluation function. The traditional DWA often falls into the local optimum. In order to fix this problem, an evaluation function considering the global path information is proposed to ensure that the final local path is in accordance with the global optimal path. The improved evaluation function is as follows:where is the angle difference between the directions of the trajectory end points and the current target point, is the distance between the trajectory and the nearest obstacle, is the current speed evaluation function, σ is the smoothing function, and α, β, and λ are weighting coefficients. With the evaluation function, the path planned by the robot can avoid random obstacles and fit the global optimal path.
4.4. Dynamic Target Pursuing with Preview Deviation Angle Algorithm
In the current complex working environment, it is necessary for mobile robots to realize online path planning while avoiding obstacles and complete the task of pursuing dynamic targets as quickly as possible. In the process of pursuing the target, not only the dynamic path planning problem needs to be solved, but also the mobile robot needs to use its own sensors to continuously adjust the yaw angle and combine the weighted obstacle search algorithm to improve the chasing efficiency.
During the operation, the position information of the target point is constantly updated with the robot sensors; the center point of the target is regarded as the preview point; and the distance between the center of the mobile robot and the center of the target is the preview distance. The angle between the moving directions of the target point and the mobile robot is the preview angle. The schematic diagram of chasing strategy based on the preview deviation angle is shown in Figure 2. In Figure 2, L is the preview distance, and Md is the vertical distance between the mobile robot and the dynamic target point trajectory. Given L ≠ 0 and Md ≠ 0, then Md is always less than L, θ1 is the preview deviation angle, and it is stipulated that the preview deviation angle is positive when the preview point is in the frost-left of the moving direction of the mobile robot, and the center of the moving target point is the preview point.

It can be seen from Figure 2 that when θ1 ⟶ 0 and L ⟶ 0, the mobile robot can catch up with the moving target, so we get:
In the case of L ≠ 0 and Md = 0, it can be seen from Figure 2 that the robot is always behind the target point during the pursuit; we get N = L, , then θ1 = 0, and = 0; and the robot accelerates in a straight line to chase the target point. In the case of L ≠ 0 and Md ≠ 0, it can be derived that during the pursuing process N ≠ 0, and θ1 ⟶ 0, so . In Figure 2, if an arc is drawn with O as the center and tangent to the trajectory of the moving target, then the arc is the planned trajectory, and the arc radius R can be calculated as follows:
From the sensor readings of the mobile robot, the coordinates of the moving target point () and the mobile robot (x, y) can be measured, then the coordinates of the center O (xr, yr) can be obtained. The center O that is closer to the mobile robot will be selected:
Then the arc trajectory is expressed as follows:
5. Experiment
In order to verify the global and local path planning performance of the proposed method, we compare the proposed hybrid method with other methods in different environments. The experiment runs on a computer with a CPU of I5-9400 and a RAM of 16 GB, and the algorithm is implemented through MATLAB programming simulation. The parameters are set as follows: the maximum velocity is 1 m/s, the maximum angular velocity is 20°/s, the velocity resolution is 0.01 m/s, the angular velocity resolution is 1°/s, the acceleration is 0.2 m/s2, and the angular acceleration is 50°/s2. The parameters of the evaluation function are: α = 0.1, β = 0.05, and γ = 0.2.
5.1. Map and Environment Construction
In order to facilitate performance analysis, this article uses the following settings for mobile robots and environmental maps:(1)The grid method is used to mathematically model the environment map, and the feasible and infeasible areas are represented by white grids and black grids, respectively.(2)The starting point and ending point of the map are given, with some unknown obstacles in the map.(3)The mobile robot and dynamic obstacles are represented as dilated points.(4)The dynamic obstacle in the map moves in a straight line at a uniform speed, but the moving direction and position of the obstacle are unknown.(5)The mobile robot is equipped with sensors, which can perceive the information of the map within a limited range, such as the position and speed of obstacles.(6)The mobile robot moves at a constant speed and can move in all directions.
5.2. Trajectory Comparison
On the static global path planning problem, compared with the traditional A algorithm, the proposed algorithm mainly optimizes the planned path trajectory. In a 20 × 20 grid environment, global path planning is performed with (1, 1) as the starting point and (20, 20) as the ending point, and the performance of the proposed method is compared with the classic A algorithm [18]. The reference standards for optimizing the trajectory include the cumulative turning angles, the average turning angles, and the path length. Figure 3 shows the optimization process of path nodes, and the red line represents the generated global path. Figure 3(a) is the path trajectory generated by the traditional A algorithm, Figure 3(b) is the path trajectory generated with [18], and Figure 3(c) is the path trajectory generated by the proposed method. The statistics are shown in Table 2.

(a)

(b)

(c)
It can be seen from Table 2 that compared with the traditional A algorithm, the proposed method has significantly reduced the cumulative turning angles, average turning angles, and path length through path optimization strategy. The method in [18] only deletes redundant points for the trajectory. It can be seen from Table 2 that although the proposed algorithm has a slight increase in path length compared to [18], the cumulative turning angle and average turning angle have been reduced, making the planned trajectory smoother and more in line with the kinematics law of the mobile robot. In addition, the multiobjective strategy adopted in this paper shortens the average distance between nodes, which is more conducive to the selection of the subsequent local path planning range.
5.3. Comparison of Algorithm Efficiency
In order to alleviate the impact of environmental changes on the experiments and further improve the evaluation fairness, different data are used to simulate different algorithms on the same computer, and three environments of different complexity are established. The complexity of the environment is set as the size of the environment and the coverage of obstacles.
Table 3 compares the proposed algorithm with other methods from the path planning time (the number of cycles T) and the planned path length. From the results, it can be found that the proposed method has achieved good results in various environments and significantly reduced the computational complexity. The reason is that in the proposed method, a lot of the search nodes have been simplified compared with the traditional A algorithm and the method in [18]. In terms of the number of turning points, the proposed algorithm can reduce the number of turning points in most cases. And through the improvement of multiobjective optimization and heuristic function, the time and space cost of path planning is greatly reduced.
5.4. Dynamic Environment Simulation
In order to verify the dynamic programming ability of the proposed method, unknown dynamic obstacles are introduced in the simulation, and a simple environment is established for simulation verification. In this environment, according to the given map information, with S (1, 1) as the starting point and E (20, 20) as the end point, global path planning is performed. After optimization, the path shown in Figure 4 is obtained, which is represented by a red line. Select appropriate local subtarget points on the path and add two local subtarget points A and B.

In this environment, the path is divided into three subpaths, namely SA, AB, and BE. When the robot is at the starting position, the DWA does not detect any changes in the map, and the robot travels from point S to the first local subtarget point A along the path. At this time, the robot detects a dynamic obstacle M (blue square). According to the information feedback from the sensors, the robot will collide with the obstacle at the X position (red grid), as shown in Figure 5(a).

(a)

(b)
According to the sensor information, the traveling speed of the dynamic obstacle M is less than the robot, and the moving trajectory of M has an intersection with the path trajectory of the robot. The EDWA is used to replan the path in the local area and update the subpath AB. As shown in Figure 5(b), the original path is represented by a dashed line, and the path planned by the proposed method is represented by a solid line. When the second subtarget point B is reached, the obstacle is located on the left side of the robot, completing the dynamic obstacle avoidance process.
Table 4 shows the quantitative results of different algorithms when unknown dynamic obstacles are introduced in the 20 × 20 grid environment shown in Figure 4. The traditional A algorithm does not have the ability to avoid obstacles. After encountering unknown obstacles, the path planning fails, and the target location cannot be reached. The proposed algorithm and [18] both have the ability to replan the path when encountering unknown obstacles, and both reach the target position. The processing time and path length of the proposed algorithm are better than those of [18].
Figure 6 shows the simulation results of the proposed method for avoiding dynamic obstacles and chasing dynamic target points. The proposed hybrid algorithm can realize local path planning and at the same time use the preview deviation angle algorithm to complete the pursuit of dynamic target points. And after combining the global path information, the hybrid algorithm plans a path with a shorter length and higher smoothness.

6. Conclusion
This paper proposes a random obstacle avoidance method for robot path planning that combines the improved A algorithm with EDWA. By optimizing the search point selection strategy and evaluation function of the traditional A algorithm, the search efficiency is improved, and a redundant node deletion strategy is introduced to reduce the path length. The EDWA is used to realize the real-time path planning and make up for the shortcomings of the traditional A algorithm with poor timeliness. While chasing dynamic obstacles, the optimal path is planned in accordance with the global path planning information. Through comparative analysis, the effectiveness of the proposed hybrid algorithm is proved. In the future, we plan to incorporate machine vision techniques to further explore the path planning of mobile robots in complex environments and multitask conditions.
Data Availability
The data included in this paper are available without any restriction.
Conflicts of Interest
The authors declare that there are no conflicts of interest regarding the publication of this paper.