Next Article in Journal
Denoising Single Images by Feature Ensemble Revisited
Next Article in Special Issue
Building a Real-Time Testing Platform for Unmanned Ground Vehicles with UDP Bridge
Previous Article in Journal
Global Vibration Comfort Evaluation of Footbridges Based on Computer Vision
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Dynamic Path Planning for Forklift AGV Based on Smoothing A* and Improved DWA Hybrid Algorithm

College of Mechanical and Electronic Engineering, Nanjing Forestry University, Nanjing 210037, China
*
Author to whom correspondence should be addressed.
Sensors 2022, 22(18), 7079; https://doi.org/10.3390/s22187079
Submission received: 15 August 2022 / Revised: 15 September 2022 / Accepted: 15 September 2022 / Published: 19 September 2022
(This article belongs to the Special Issue Automated Guided Vehicle Integrated with Collaborative Robot)

Abstract

:
FAGV is a kind of heavy equipment in the storage environment. Its path needs to be simple and smooth and should be able to avoid sudden obstacles in the process of driving. According to the environmental characteristics of intelligent storage and the task requirements of FAGV, this paper proposed a hybrid dynamic path planning algorithm for FAGV based on improved A* and improved DWA. The improved A* algorithm can plan the global optimal path more suitable for FAGV. The improved evaluation function of DWA can ensure that the local path of FAGV is closer to the global path. DWA combines the rolling window method for local path planning to avoid sudden unknown static and dynamic obstacles. In addition, this paper verifies the effectiveness of the algorithm through simulation. The simulation results show that the algorithm can avoid obstacles dynamically without being far away from the global optimal path.

1. Introduction

Forklift Automated Guided Vehicle (FAGV) is a kind of transport vehicle with a rechargeable battery as the energy source. Under the guidance of automatic navigation and positioning devices such as navigation laser scanners and binocular cameras, it can run according to the desired path planned by the guiding system. FAGV has the functions of autonomous obstacle avoidance and fault alarm, and can also carry out various transfer functions. As an important part of AGV, FAGV plays an irreplaceable role in heavy load, special handling, and other scenes. Figure 1a shows the working environment of FAGV, and Figure 1b is a photograph of a FAGV. AGV is currently widely used in warehouses [1], ports [2], and factories [3]. In recent years, forklift unmanned transformation has become a trend. In the storage environment, the main tasks of FAGV include road scene recognition, path planning, tracking control [4], and local obstacle avoidance [5]. Among them, path planning and local obstacle avoidance are the key points in the research of forklift unmanned transformation.
Path planning refers to finding collision-free handling paths that meet the requirements of AGV operation according to the rules set in advance (with the least time or the shortest distance) when AGV carries out cargo handling tasks [7]. Path planning includes the following three aspects [8]: (1) starting point and target point; (2) bypassing the known static obstacles; (3) the best path according to the set rules. Due to the large size and weight of FAGV, the path of FAGV needs to be smoother than ordinary AGV. Moreover, there are often unknown static or dynamic obstacles in the storage environment, such as the running FAGV or walking people. FAGV usually carries heavy goods. If they cannot avoid obstacles in time, it will cause serious consequences. Therefore, the path planning of FAGV should not only have shorter distance and less time but also avoid obstacles in time and safety. According to these characteristics of FAGV, this paper studies the path planning algorithm that meets the requirements of FAGV.
According to the mastery of warehouse map information, FAGV path planning can be divided into local dynamic path planning and global path planning [9]. Global path planning is to plan a barrier-free shortest path [10] for FAGV with known warehouse map information [11]. The global path search methods mainly include heuristic search algorithms, sampling search algorithms, and intelligent algorithms. The heuristic search algorithm includes the Dijkstra algorithm [12] and BFS algorithm [13], etc. The Dijkstra algorithm can find the shortest path, but the efficiency is relatively lower [14]. The BFS algorithm uses a heuristic function to search and the efficiency is high, but the planned path is not the shortest. The A* algorithm [15] is composed of the best-first search algorithm (BFS) and the Dijkstra algorithm, so it not only has the search speed of the BFS algorithm (using a heuristic function to guide itself to quickly guide the target node) but also can make the search path the shortest like the Dijkstra algorithm. Sampling search algorithm including fast extended random tree (RRT) [16] and its optimization algorithm [17]. This algorithm takes the initial position as the root node of the random tree and randomly points out the growth direction of the tree on the map. When the target node is included in the sub-node of the tree, the search ends. This method is fast and can search in multidimensional space. Chi W Z et al. [18] proposed a heuristic path planning algorithm based on a generalized Voronoi diagram (GVD) to generate heuristic paths, guide the sampling process of RRTs, and further improve the efficiency of motion planning of RRTs. Jiang et al. [19] proposed an improved bidirectional A* search algorithm from the perspective of heuristic function and search direction. In the heuristic function of the A* algorithm, the chord factor was introduced to optimize the direction of the path search. The unidirectional search from the starting point to the endpoint was changed to a bidirectional simultaneous search, which improved the problems of long planning paths and low unidirectional search efficiency in the path planning of electric disinfection vehicles. Tang G et al. [20] proposed a geometric A* algorithm for AGV global path planning in a port environment, which reduced the number of path nodes and the number of turns. Intelligent algorithms include particle swarm optimization (PSO), genetic algorithms, ant colony algorithms, simulated annealing algorithms, etc. Intelligent algorithms such as the PSO algorithm for path planning have the characteristics of easy implementation, high precision, and fast convergence speed, but there are problems such as easy to fall into local optimum and long planning path [21]. Xu L et al. [22] proposed a smooth path planning method for mobile robots based on the quartic Bezier transition curve and an improved PSO algorithm. By analyzing the stability of the algorithm, the parameter relationship to ensure the convergence of the proposed adaptive weighted delay speed PSO algorithm is derived. Dang et al. [23] proposed a chain navigation grid for a virtual reality large-scale crowd evacuation simulation. However, the above separate global planning algorithms cannot be used in unknown dynamic environments, and are not suitable for heavy equipment such as FAGV. Therefore, it is necessary to optimize the global planning algorithm and combine it with local planning.
Local path planning is to detect the surrounding environment of FAGV by means of a safety laser scanner, motion sensor, and other tools to obtain the location information and motion of unknown static and dynamic obstacles around and find a path that can bypass obstacles. The local path planning algorithm integrates environmental modeling and path searching and has good anti-interference ability to environmental error and noise, which can provide real-time feedback and correction for planning results. Local path planning algorithms mainly include classical algorithms such as dynamic window algorithms [24], artificial potential field algorithms [25], and intelligent algorithms such as neural network algorithms and reinforcement learning algorithms. In order to further improve the path planning of mobile robots in complex dynamic environments, Liwei Yang et al. [26] proposed an improved hybrid algorithm combining the excellent searchability of the ant colony algorithm (ACO) for global path and the advantages of the dynamic window method (DWA) for local obstacle avoidance. Sollehudin I. M et al. [27] introduced the artificial potential field method into the electric wheelchair control system to help the electric wheelchair complete its daily work. Lin, Zenan, et al. [28] proposed an improved artificial potential field model, using a sub-objective strategy to solve a local minimum problem. In order to show the adaptive selection characteristics of robot sub-goals, the obstacle potential field function is established, and the effectiveness of adaptive characteristics is verified by path planning simulation. Vahide Bulut [29] proposed an improved ε-greed epsilon-greed Q-learning (IEGQL) algorithm and proposed a new reward function and mathematical model to ensure that mobile robots can obtain environmental knowledge in advance and provide optimal selection while ensuring rapid convergence. Simple local path planning cannot complete the task of FAGV, so it is necessary to optimize the local planning algorithm and mix the global planning algorithm.
An ideal dynamic path planning algorithm for FAGV should not only be able to plan a path with a short length and less time—which meets the dynamics requirements of FAGV, namely a simple and smooth path—but also avoid static and dynamic obstacles in the process of driving. In order to solve the above problems, this paper proposes a hybrid dynamic path planning algorithm for FAGV based on improved A* and improved DWA. The contribution of the proposed algorithm to the FAGV path planning problem is as follows:
  • Aiming at the problem of redundant path points and multiple turning points in the planning path of the traditional A* algorithm. This paper improves the A* algorithm in path smoothing.
  • When the dynamic window method is used to avoid obstacles, the local path may be far away from the global optimal path. And the excessive speed of the forklift may cause accidents when it is close to the obstacle. To solve the above problems, this paper introduces two evaluation indexes in the trajectory evaluation function: the distance between the local path and the global path and the distance between the trajectory point and the local sub-target point, which can make the local path closer to the global optimal path, and reduce the speed of the FAGV approaching the local sub-target point, and avoid the FAGV crossing the target point or oscillation due to the excessive speed. The FAGV uses the rolling window method for collision prediction in the process of moving and then calls the improved DWA for local path planning and safe avoidance of obstacles to return to the global optimal path in time.

2. Global Path Planning Based on Improved A * Algorithm

2.1. Traditional A* Algorithm

The A* algorithm [15] uses the path length evaluation function f(n) to evaluate the path length. The basic idea is to sort the cost of the optional nodes around the current node, select the least-cost node, and repeat the cycle until it extends to the target point. The formula is as follows:
f ( n ) = g ( n ) + h ( n )
In the formula, g(n) is the actual cost from the starting point of the FAGV path to the current node n, and h(n) is the minimum estimation cost from node n to the target endpoint. If h(n) is zero, then only g(n) works and the A* algorithm degenerates into the Dijkstra algorithm; if h(n) is much larger than g(n), then g(n) can be approximately regarded as zero, and the A* algorithm degenerates into the BFS algorithm. h(n) can be selected according to the actual working environment, h(n) selection should meet a requirement that is not higher than the actual minimum cost of node n to the endpoint.

2.2. Improved A* Algorithm

In the known obstacle space, the A* algorithm can avoid obstacles correctly, find the shortest path and complete the global path planning requirements in the initial stage. However, the number of path turns is relatively large, and the smoothness is relatively poor. The traditional A* algorithm is not suitable for large transport equipment such as FAGV. To solve this problem, this paper proposes an improved A* algorithm that can remove redundant nodes and reduce the turning times.
As shown in Figure 2, the path planned by the A* algorithm is (S, n 1 , n 2 , n 3 , n 4 , n 5 , n 6 , n 7 , n 8 , n 9 , n 10 , T), which has multiple turns and poor smoothness. To solve the above problems, this paper optimizes the smoothness of the A* algorithm. The specific optimization steps are as follows:
Step 1: If the connection distance between non-adjacent nodes is less than the planned connection path distance and the connection does not collide with the obstacle, then the intermediate node belongs to redundant nodes, which can be deleted. Therefore, other nodes outside the first and last two nodes in the same direction are redundant nodes, which should be deleted. Only the initial node, the target node, and the middle inflection point are saved, and the reserved path is (S, n 7 , n 8 , n 9 , T).
Step 2: Starting from the starting point S, a node is taken every certain step between the reserved two inflection points n i , n j , such as n 13 , and the selected node is connected to the previous path node to check whether there is an obstacle between the two points. If there is no obstacle, the current node is selected as a new path node. If there is an obstacle, the node is abandoned, and the reserved path is (S, n 11 , T).
Step 3: Change the optimization direction and retake the point from the target point to the starting point step by step. The remaining path is (S, n 12 , T). Output optimization path, path optimization end.

3. Local Path Planning Based on Improved DWA

Under the global map with complete information about the environment and obstacles, the A* algorithm can conduct navigation well. However, there are some emergencies in the actual situation, such as unexpected obstacles or walking people on the original path. If appropriate measures are not taken, FAGV collides easily with obstacles. Therefore, to realize the real-time obstacle avoidance of the robot, this paper uses the DWA algorithm with local obstacle avoidance ability to plan the local path and avoid obstacles to ensure the safety of FAGV.

3.1. Basic Principle of DWA

The dynamic window algorithm mainly samples a variety of speeds in the speed space (including linear velocity and angular velocity) and uses this group of speeds to simulate the motion trajectory of FAGV within a certain time. After obtaining multiple sets of corresponding trajectories of speed, it uses certain evaluation rules to evaluate them and selects the corresponding speed of the optimal trajectory to drive the FAGV forward.

3.2. Kinetic Model of FAGV

The premise of using the dynamic window method to simulate the motion trajectory is to know the kinetic model of FAGV. In this paper, the discrete kinematic model of the Ackerman steering vehicle [30] is used as the kinetic model of FAGV, and the relationship between vehicle pose (x, y, θ) and velocity (v, ω) can be obtained. Assuming that the trajectory is a circular arc, when the rotation speed is 0, the circular arc is approximately a straight line, and a pair of linear velocity and angular velocity (v, ω) represents a circular arc trajectory. When calculating the moving trajectory of FAGV at adjacent moments, the moving trajectory at adjacent moments can be approximated as a straight line due to the short time interval and moving distance. Since the FAGV does not move in all directions, it can only move forward and rotate, and cannot move longitudinally, thus the distance of the FAGV moving along the y r axis of its own coordinate system is not considered when calculating the trajectory of the FAGV. Assuming that the FAGV moves v∙∆t along the x r axis of its own coordinate system, the distance is projected on the x-axis and y-axis of the world coordinate system, as shown in Figure 3, and the coordinate increments ∆x and ∆y of the FAGV in the world coordinate system at the next moment relative to the previous moment can be obtained:
{ x = v   · t   · cos ( θ t ) y = v   · t   · sin ( θ t )
In order to calculate the trajectory of FAGV in a period of time, the displacement increment in this period can be accumulated:
{ x = x 0 + v t cos ( θ t ) y = y 0 + v t sin ( θ t ) θ t = θ t + ω t

3.3. The Optimized Trajectory Evaluation Function

In the traditional dynamic window approach, the indicators of the evaluation function are azimuth, void, and velocity. Its evaluation function G(v, ω) [31] is:
G ( v , ω ) = σ ( α heading ( v , ω ) + β vel ( v , ω ) + γ dist ( v , ω ) )
In the formula, heading ( v , ω ) is the direction angle evaluation index, dist ( v , ω ) is the distance between the current trajectory and the nearest obstacle, and vel ( v , ω ) is the current speed evaluation function. α, β, and γ are the weighting coefficients of the three evaluations. To avoid one of the three values being too large and too dominant, the evaluation function is obtained by multiplying and adding the corresponding coefficients after smoothing. Finally, the smoothing factor σ is used to normalize the objective function.
The main purpose of this paper is to avoid obstacles by using the DWA for local path planning. The local path planned by DWA usually deviates greatly from the global path when avoiding obstacles, which not only causes the global optimality of the path to deteriorate but also makes FAGV walk many useless paths, resulting in a waste of time and energy. Therefore, the distance from the reference trajectory to the global path is considered as an evaluation index to make the obstacle avoidance path as close as possible to the global optimal path, so as to improve the global optimality of the dynamic window method.
At the same time, the distance between the reference trajectory point and the local sub-target point is added as the evaluation index, which can reduce the speed of FAGV approaching the local sub-target point and avoid the phenomenon of FAGV crossing the target point or shaking due to the excessive speed.
In summary, in order to improve the global and local optimality of the dynamic window method, a new evaluation function is designed in this paper. The distance between the reference trajectory and the global path dist − 1(v, ω) and the distance between the reference trajectory point and the local sub-target point dist − 2(v, ω) is added to the evaluation index. The trajectory with the lowest cost of the evaluation function G(v, ω) is the optimal trajectory, and the evaluation function can be rewritten as:
G ( v , ω ) = σ ( α heading ( v , ω ) + β × vel ( v , ω ) + γ dist ( v , ω ) + η dist 1 ( v , ω ) + λ dist 2 ( v , ω ) )

4. Collision Prediction Based on Rolling Window

4.1. Local Collision Prediction

Before the local planning, it is necessary to predict the local collision to determine whether the FAGV will collide with the obstacle. If the collision is going to occur, the corresponding collision avoidance strategy will be taken according to the type of obstacle. In this section, the obstacle collision is predicted based on the rolling window method [32], and the corresponding obstacle avoidance measures are formulated according to different collision situations. The rolling window method takes the moving FAGV as the center and the detection range of the laser radar as the radius to construct the rolling window (Figure 4). According to the environmental information collected by the laser radar, the environmental information in the window is updated to analyze and predict the trajectory of the obstacle and plan the local path.
If the FAGV detects static obstacles on the road, the improved dynamic window algorithm is used for local path planning before the safe distance from static obstacles.
If the FAGV detects the dynamic obstacle on the road, the collision prediction is carried out to calculate whether the shortest distance between the FAGV and the dynamic obstacle is less than the safe distance. If it is less than, the collision will occur, and if it is greater, the collision will not occur.
The detection range of lidar is a fan-shaped region with its own center and radius r . The running speed of FAGV is v 1 , the cycle is T, the step size is s, the direction is θ 1 , and the position is p 1 r ; the moving speed of dynamic obstacle o is v 2 , the direction is θ 2 , and the position is p 2 o ; according to obstacle avoidance requirements:
( v 1 + v 2 ) T < r
T = s/v, then:
v 2 < ( r s 1 ) v 1
Figure 4 is the model observation diagram. According to the motion relationship between the FAGV and the obstacle, the collision point between the forklift AGV and the dynamic obstacle is calculated.
Knowing from the motion relationship of an object that:
d 1 v 1 = d 2 v 2
And:
{ d 0 = p b = p c 2 + b c 2 b c = | d 2 r cos ( α ) | p c = r sin ( α )
Simultaneous (8) and (9):
( v 2 2 v 1 2 ) d 1 2 2 r d 2 v 2 2 cos ( α ) + r 2 v 2 2 = 0
Solution of d2 is:
{ d 2 = 2 r v 2 2 cos ( α ) ± Δ 2 ( v 2 2 v 1 2 ) Δ = 4 r 2 v 2 2 ( v 1 2 v 2 2 sin 2 ( α ) )
If ∆ ≥ 0, indicating that the FAGV will collide with the dynamic obstacle, d 2 is the distance of the dynamic obstacle movement.
Assuming that the current speed direction of FAGV is constant, the speed direction of dynamic obstacles is also constant. According to the current rolling window, the position and orientation of the FAGV and the dynamic obstacle p 2 r and p 2 o are predicted at the next moment.
{ p 2 r = p 1 r + T v 1 θ 1 norm ( θ 1 ) p 2 o = p 1 o + T v 2 θ 2 norm ( θ 2 )
In the Formula, norm ( θ 1 ) and norm ( θ 2 ) are two-norms of θ 1 and θ 2 . According to Formulas (11) and (12), the collision point position between FAGV and dynamic obstacles can be obtained.

4.2. Selection of Local Sub-Target Points

In the local path planning algorithm based on the rolling window method, the most important thing is to select the local sub-goal points of the current window. The rolling window at time t is denoted as W (t). The selection idea of the local sub-goal point p 1 is that if the global goal point p 2 is located in the current rolling window, the local sub-goal point of the current window is p 2 . If the global target point p 2 is not in the current scroll window, select the window boundary point p which minimizes f(p) as the local sub-target point. After selecting the local sub-target, the current speed direction of the FAGV is changed, and the dynamic window algorithm is used for local path planning to control the FAGV to the local sub-target point, so as to achieve the purpose of obstacle avoidance. The selection formula of local sub-target points is as follows:
p 1 = { p 2 , p 2 w ( t ) m i n f ( p ) , p w ( t ) , p 2 w ( t )
In the formula, f(p) draws on the idea of the heuristic function of the A* algorithm. The formula of f(p) is f ( p ) = g ( p ) + h ( p ) . g(p) is the cost from the current position to p, and h(p) is the cost from p to the end. gip) is determined by whether p is in the reachable region. If the window boundary point p is in the reachable region, then g(p) = 0. If the window boundary point p is not in the reachable region, g(p) = +∞, the reachable region is divided as shown in Figure 5. Since the information outside the rolling window of FAGV is unknown, h(p) is estimated by the Euclidean distance from the point p 1 to the global target point p 2 . This method of selecting local target points can fully cope with the sudden static and dynamic obstacles on the route of FAGV, and ensure the FAGV avoids obstacles smoothly.

4.3. Collision Avoidance Strategy

Now, we analyze the collisions that can be encountered in the warehouse environment and give the corresponding strategies.
  • Static obstacles in front: Call the improved DWA for local path planning to avoid obstacles.
  • Dynamic obstacles coming opposite: Make collision prediction and calculate collision location, then call DWA for local path planning.
  • Obstacles on the front side: Predict whether a collision occurs and if so, call DWA to avoid obstacles; if not, continue along the global path.

5. Dynamic Path Planning Algorithm of FAGV Based on Improved A* and Improved DWA Hybrid

By improving the traditional A* and DWA algorithm, the dynamic path planning algorithm for FAGV can be concluded as follows. In the process of driving along the global shortest path planned by the improved A* algorithm, the FAGV constantly updates the map information in the rolling window and makes collision predictions. Improved DWA is called for local path planning if there are unknown obstacles in front of the collision. After avoiding obstacles, the FAGV returns to the global path to continue driving. The process of the hybrid algorithm is shown in Figure 6.
The algorithm process is as follows:
Step 1: Build an environment map, and set the starting point and end point of forklift AGV operation.
Step 2: Using an improved A* algorithm for global path planning, find the shortest barrier-free path.
Step 3: Determine whether the FAGV is exercised to the target point and if so, end the algorithm, otherwise execute step 4.
Step 4: Use laser radar and other sensors carried by FAGV to collect environmental information around the body, update the internal environment of the rolling window, and determine whether there are unknown static and dynamic obstacles.
Step 5: If there is no obstacle, continue to follow the global path, if there are obstacles, collision prediction, according to the corresponding results to take different obstacle avoidance measures.
Step 6: Use the improved dynamic window algorithm for local path planning to avoid obstacles. FAGV travels along the local path and returns to the global path after obstacle avoidance is completed. Return to step 3.
The flow chart of the FAGV dynamic path planning hybrid algorithm based on improved A* and DWA is shown in Figure 7.

6. Simulation Analysis

6.1. Simulation Results of Global and Local Path Planning

Firstly, we simulate the global path planning. As shown in Figure 8, black blocks represent known obstacles and blank areas represent movable areas. The starting point is S, and the target point is T. The number of inflection points of the path can be regarded as the number of turns. Compared with the A* algorithm and improved A* algorithm, in the same map, the path planned by the traditional A* algorithm turns eight times in total, while the path planned by the improved A * algorithm only turns three times, and the turning times of the improved path are reduced by 62.5%. Moreover, the improved A* planning has a smaller turning angle and higher smoothness, which is more in line with the dynamic characteristics of FAGV.
In order to verify the effectiveness of the new indicators of the trajectory evaluation function, the improved DWA is simulated (Figure 7 and Figure 8). Set the traditional evaluation function parameters α = 0.2, β = 0.3, γ = 0.5. The evaluation function parameters designed in this paper are α = 0.2, β = 0.3, γ = 0.15, η = 0.2, λ = 0.15. Speed parameter settings are shown in Table 1.
Figure 9, Figure 10 and Figure 11 show the path planning of the algorithm under the original evaluation function and the improved evaluation function, respectively. The path starting point is S, and the target point is T. The linear velocity of the initial state of the FAGV is v = 0 m/s, and the initial angular velocity is ω = 0 m/s.
Comparing the original path and the improved path in Figure 9, it can be seen that after the introduction of the new evaluation function, the local path of FAGV is closer to the global path under the premise of ensuring safe obstacle avoidance. After improving the DWA, the actual moving distance of FAGV is significantly reduced, and the overall path smoothness is better, which conforms to the dynamic characteristics of FAGV. Comparing the linear velocity of FAGV in Figure 10a and Figure 11a, when approaching the obstacle and the target point, the speed of the FAGV controlled by the original evaluation function is larger, between 0.6 m/s and 0.7 m/s. After improving the evaluation function, the speed of FAGV approaching the obstacle is between 0.3 m/s and 0.4 m/s or 0.5 m/s and 0.6 m/s, and the speed is smaller when avoiding obstacles. Driving at high speed near obstacles cannot guarantee the safety of forklifts and cargo, and will also cause the actual moving direction of the angular velocity of FAGV to deviate from the global path and the actual moving distance to be larger. After introducing the new evaluation function, the FAGV line speed is lower, which is in line with the principle of slowing down near obstacles. At the same time, comparing the area of the graph surrounded by the linear velocity image and the x-axis, it can be seen that the area is smaller after the improved evaluation function, which also verifies that the actual moving distance of the improved FAGV is smaller. By comparing Figure 10b and Figure 11b, it can be concluded that under the condition of the original evaluation function, the amplitude of forklift angular velocity is [−0.4,0.4]. After the introduction of the new evaluation function, the amplitude of FAGV angular velocity is [−0.3,0.4]. The amplitude of FAGV angular velocity becomes smaller, which shows that when approaching obstacles, FAGV angle adjustment is stable, jitter is small, and obstacle avoidance is smooth.

6.2. Simulation Results of Local Obstacle Avoidance

To test the effectiveness of the algorithm in the face of sudden obstacles, unknown static and dynamic obstacles are added to the raster map.
FAGV continuously scans the surrounding environment information when driving along the global shortest path planned by the improved A* algorithm, updates the rolling window, and determines whether there are unknown static or dynamic obstacles.
As shown in Figure 12 and Figure 13, the red block is an unknown dynamic obstacle, and the red line is an unknown dynamic obstacle motion route. FAGV continuously scans the surrounding environment information when driving along the global shortest path planned by the improved A* algorithm, updates the rolling window, and determines whether there are unknown static or dynamic obstacles. If an obstacle with too large or too small of a speed is detected and it is judged that the obstacle will not collide with FAGV, FAGV will continue to move forward along the global path.
Figure 14 shows that FAGV encounters unknown dynamic obstacles that will collide during driving. Figure 14a indicates that after the safety laser scanner and motion sensor detect the unknown dynamic obstacles, the rolling window method predicts that the FAGV is about to collide with the obstacle on the global path. According to the obstacle avoidance strategy, the forklift calls DWA for local path planning. Figure 14b indicates that the FAGV travels along the local path, and there is no collision when the dynamic obstacle travels to the original path of the forklift. Figure 14c indicates that after the FAGV avoids obstacles, it returns to the global path to continue driving.
As shown in Figure 15, when the safety laser scanner and motion sensor detect unknown static obstacles in the front path, the improved DWA is called for local path planning to avoid. After avoiding the unknown dynamic obstacles, the FAGV returns to the global path and continues to move toward the target point.
According to the above simulation, the dynamic path planning algorithm of FAGV based on A* and DWA proposed in this paper can find the shortest barrier-free path for FAGV and guide FAGV to avoid static and dynamic obstacles in a warehouse and complete the handling task safely and reliably.
Table 2 compares the five algorithms mentioned in this paper. It can be seen from the table that the hybrid algorithm proposed in this paper takes into account both global optimality and local optimality, and can avoid obstacles in a dynamic environment.

7. Conclusions

As heavy equipment in the storage environment, FAGVs need a simple and smooth driving path, and at the same time, they should be able to avoid sudden obstacles in the driving process. In view of the above two requirements, this paper proposes a hybrid dynamic path planning algorithm suitable for FAGV. Firstly, we improve the A* algorithm to make the global path smoother. Then, we design a new evaluation function to improve the global optimality and local optimality of DWA in path planning and combine the rolling window method to solve the dynamic obstacle avoidance problem of FAGV. The simulation results show that the number of path turns of the improved A* algorithm is reduced by 62.5%, the turning angle is smaller, and the smoothness is higher. The local path of the improved DWA planning is closer to the global optimal path, and the FAGV has lower linear velocity and smaller angular velocity amplitude when it is close to the obstacle, which conforms to the principle of slowing down near the obstacle. After the collision is predicted by the rolling window method, FAGV runs according to the local path to avoid obstacles and returns to the global optimal path in time after successful avoidance.
The algorithm proposed in this paper can be used for the path planning of the FAGV in the working environment. However, the map environment and positioning information obtained by the navigation laser scanner used in the FAGV is limited to the two-dimensional level, and a comprehensive map environment cannot be established. Therefore, it can be considered to add binocular cameras or other sensors to the FAGV. The combination of visual positioning and laser positioning is used to fuse the collected data through corresponding algorithms to increase the accuracy of the map environment and positioning information.

Author Contributions

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

Funding

This research received no external funding.

Acknowledgments

All individuals included in this section have consented to the acknowledgments.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Digani, V.; Sabattini, L.; Secchi, C.; Fantuzzi, C. Ensemble Coordination Approach in Multi-AGV Systems Applied to Industrial Warehouses. IEEE Trans. Autom. Sci. Eng. 2015, 12, 922–934. [Google Scholar] [CrossRef]
  2. Yang, Y.; Zhong, M.; Dessouky, Y.; Postolache, O. An Integrated Scheduling Method for AGV Routing in Automated Container Terminals. Comput. Ind. Eng. 2018, 126, 482–493. [Google Scholar] [CrossRef]
  3. Chen, C.; Huy, D.T.; Tiong, L.K.; Chen, I.-M.; Cai, Y. Optimal Facility Layout Planning for AGV-Based Modular Prefabricated Manufacturing System. Autom. Constr 2019, 98, 310–321. [Google Scholar] [CrossRef]
  4. Sun, B.A.; Gu, Z.; Xiong, T.Y. Event-Triggered Formation Tracking Control for Unmanned Aerial Vehicles Subjected to Deception Attacks. Electronics 2021, 10, 2736. [Google Scholar] [CrossRef]
  5. Liu, G.; Zhang, R.X.; Wang, Y.Y.; Man, R.J. Road Scene Recognition of Forklift AGV Equipment Based on Deep Learning. Processes 2021, 9, 1955. [Google Scholar] [CrossRef]
  6. Available online: Http://Www.Zcnest.Com/Product/Product-Fen/7 (accessed on 31 July 2022).
  7. Draganjac, I.; Miklic, D.; Kovacic, Z.; Vasiljevic, G.; Bogdan, S. Decentralized Control of Multi-AGV Systems in Autonomous Warehousing Applications. IEEE Trans. Autom. Sci. Eng. 2016, 13, 1433–1447. [Google Scholar] [CrossRef]
  8. Qiu, L.; Hsu, W.-J.; Huang, S.-Y.; Wang, H. Scheduling and Routing Algorithms for AGVs: A Survey. Int. J. Prod. Res. 2002, 40, 745–760. [Google Scholar] [CrossRef]
  9. Marin-Plaza, P.; Hussein, A.; Martin, D.; Escalera, A. Global and Local Path Planning Study in a ROS-Based Research Platform for Autonomous Vehicles. J. Adv. Transp. 2018, 2018. [Google Scholar] [CrossRef]
  10. Mac, T.T.; Copot, C.; Tran, D.T.; De Keyser, R. Heuristic Approaches in Robot Path Planning: A Survey. Robot. Auton. Syst. 2016, 86, 13–28. [Google Scholar] [CrossRef]
  11. Borges, C.D.B.; Almeida, A.M.A.; Júnior, I.C.P.; de MesquitaSá Junior, J.J. A Strategy and Evaluation Method for Ground Global Path Planning Based on Aerial Images. Expert Syst. Appl. 2019, 137, 232–252. [Google Scholar] [CrossRef]
  12. Sun, Y.; Fang, M.; Su, Y. AGV Path Planning Based on Improved Dijkstra Algorithm. In Proceedings of the Journal of Physics: Conference Series; IOP Publishing: Bristol, UK, 2021; Volume 1746, p. 12052. [Google Scholar]
  13. Wibowo, N.; Widodo, C.E.; Adi, K. Implementing the Shortest Time Route Search Algorithm in Semarang Using the Best First Search Method. In Proceedings of the IOP Conference Series: Materials Science and Engineering; IOP Publishing: Bristol, UK, 2020; Volume 879, p. 12165. [Google Scholar]
  14. Lyu, X.; Song, Y.; He, C. Approach to Integrated Scheduling Problems Considering Optimal Number of Automated Guided Vehicles and Conflict-Free Routing in Flexible Manufacturing Systems. IEEE Access. 2019, 7, 74909–74924. [Google Scholar] [CrossRef]
  15. Hart, P.E.; Nilsson, N.J.; Raphael, B. A formal basis for the heuristic determination of minimum cost paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  16. Kuffner, J.J.; LaValle, S.M. RRT-Connect: An Efficient Approach to Single-Query Path Planning. In Proceedings of the Proceedings 2000 ICRA. Millennium Conference. IEEE International Conference on Robotics and Automation. Symposia Proceedings (Cat. No. 00CH37065), San Francisco, CA, USA, 24–28 April 2000; IEEE: New York, NY, USA, 2000; Volume 2, pp. 995–1001. [Google Scholar]
  17. Gammell, J.D.; Srinivasa, S.S.; Barfoot, T.D. Informed RRT*: Optimal Sampling-Based Path Planning Focused via Direct Sampling of an Admissible Ellipsoidal Heuristic. In Proceedings of the 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems, Chicago, IL, USA, 14–18 September 2014; IEEE: New York, NY, USA, 2014; pp. 2997–3004. [Google Scholar]
  18. Chi, W.; Ding, Z.; Wang, J.; Chen, G. A Generalized Voronoi Diagram-Based Efficient Heuristic Path Planning Method for RRTs in Mobile Robots. IEEE Trans. Ind. Electron. 2022, 69, 4926–4937. [Google Scholar] [CrossRef]
  19. Jiang, H.; Sun, Y. Research on Global Path Planning of Electric Disinfection Vehicle Based on Improved A* Algorithm. Energy Rep. 2021, 7, 1270–1279. [Google Scholar] [CrossRef]
  20. Tang, G.; Tang, C.; Claramunt, C.; Hu, X.; Zhou, P. Geometric A-Star Algorithm: An Improved A-Star Algorithm for AGV Path Planning in a Port Environment. IEEE Access 2021, 9, 59196–59210. [Google Scholar] [CrossRef]
  21. Jayaweera, H.; Hanoun, S. UAV Path Planning for Reconnaissance and Look-Ahead Coverage Support for Mobile Ground Vehicles. Sensors 2021, 21, 4595. [Google Scholar] [CrossRef]
  22. Xu, L.; Cao, M.; Song, B. A New Approach to Smooth Path Planning of Mobile Robot Based on Quartic Bezier Transition Curve and Improved PSO Algorithm. Neurocomputing 2022, 473, 98–106. [Google Scholar] [CrossRef]
  23. Dang, P.; Zhu, J.; Pirasteh, S. A Chain Navigation Grid Based on Cellular Automata for Large-Scale Crowd Evacuation in Virtual Reality. Int. J. Appl. Earth Obs. Geoinf. 2021, 103, 102507. [Google Scholar] [CrossRef]
  24. Lee, D.H.; Lee, S.S.; Ahn, C.K.; Shi, P.; Lim, C.C. Finite Distribution Estimation-Based Dynamic Window Approach to Reliable Obstacle Avoidance of Mobile Robot. IEEE Trans. Ind. Electron. 2021, 68, 9998–10006. [Google Scholar] [CrossRef]
  25. Sang, H.; You, Y.; Sun, X.; Zhou, Y.; Liu, F. The Hybrid Path Planning Algorithm Based on Improved A* and Artificial Potential Field for Unmanned Surface Vehicle Formations. Ocean Eng. 2021, 223, 108709. [Google Scholar] [CrossRef]
  26. Yang, L.; Fu, L.; Li, P.; Mao, J.; Guo, N. An Effective Dynamic Path Planning Approach for Mobile Robots Based on Ant Colony Fusion Dynamic Windows. Machines 2022, 10, 50. [Google Scholar] [CrossRef]
  27. Sollehudin, I.M.; Heerwan, P.M.; Ishak, M.I.; Zakaria, M.A. Electric Powered Wheelchair Trajectory Planning on Artificial Potential Field Method. In Proceedings of the IOP Conference Series: Materials Science and Engineering; IOP Publishing: Bristol, UK, 2021; Volume 1068, p. 12012. [Google Scholar]
  28. 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]
  29. Bulut, V. Optimal Path Planning Method Based on Epsilon-Greedy Q-Learning Algorithm. J. Braz. Soc. Mech. Sci. Eng. 2022, 44, 1–14. [Google Scholar] [CrossRef]
  30. Economou, J.T.; Colyer, R.E. Fuzzy-Hybrid Modelling of an Ackerman Steered Electric Vehicle. Int. J. Approx. Reason. 2006, 41, 343–368. [Google Scholar] [CrossRef]
  31. Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef] [Green Version]
  32. Li, C.H.; Wang, F.Y.; Song, Y.; Liang, Z.Y.; Wang, Z.Q. A Complete Coverage Path Planning Algorithm for Mobile Robot Based on FSM and Rolling Window Approach in Unknown Environment. In Proceedings of the 2015 34th Chinese Control Conference (CCC), Hangzhou, China, 14 September 2015; IEEE: New York, NY, USA, 2015; pp. 5881–5885. [Google Scholar]
Figure 1. (a) FAGV working environment diagram, (b) forward-moving FAGV [6].
Figure 1. (a) FAGV working environment diagram, (b) forward-moving FAGV [6].
Sensors 22 07079 g001
Figure 2. Raster path map (the starting point is S, and the target point is T).
Figure 2. Raster path map (the starting point is S, and the target point is T).
Sensors 22 07079 g002
Figure 3. Kinetic model diagram of FAGV.
Figure 3. Kinetic model diagram of FAGV.
Sensors 22 07079 g003
Figure 4. Model observation map.
Figure 4. Model observation map.
Sensors 22 07079 g004
Figure 5. Reachable area division.
Figure 5. Reachable area division.
Sensors 22 07079 g005
Figure 6. Process diagram of hybrid algorithm.
Figure 6. Process diagram of hybrid algorithm.
Sensors 22 07079 g006
Figure 7. Flow chart of the FAGV dynamic path planning hybrid algorithm.
Figure 7. Flow chart of the FAGV dynamic path planning hybrid algorithm.
Sensors 22 07079 g007
Figure 8. Algorithm simulation results: (a) traditional A* (b) improved A*.
Figure 8. Algorithm simulation results: (a) traditional A* (b) improved A*.
Sensors 22 07079 g008
Figure 9. Comparison of local paths before and after improvement of the evaluation function.
Figure 9. Comparison of local paths before and after improvement of the evaluation function.
Sensors 22 07079 g009
Figure 10. Simulation results of original evaluation function: (a) linear speed of FAGV (b) angular velocity of FAGV.
Figure 10. Simulation results of original evaluation function: (a) linear speed of FAGV (b) angular velocity of FAGV.
Sensors 22 07079 g010
Figure 11. Simulation results of improved evaluation function: (a) linear speed of FAGV, (b) angular velocity of FAGV.
Figure 11. Simulation results of improved evaluation function: (a) linear speed of FAGV, (b) angular velocity of FAGV.
Sensors 22 07079 g011
Figure 12. Dynamic obstacles for high-speed movement. (a) There is an unknown high-speed dynamic obstacle in front of the FAGV and it is predicted that the FAGV will not collide with the obstacle. (b) FAGV continues on the current path.
Figure 12. Dynamic obstacles for high-speed movement. (a) There is an unknown high-speed dynamic obstacle in front of the FAGV and it is predicted that the FAGV will not collide with the obstacle. (b) FAGV continues on the current path.
Sensors 22 07079 g012
Figure 13. Dynamic obstacles for low-speed movement. (a) There is an unknown low -speed dynamic obstacle in front of the FAGV and it is predicted that the FAGV will not collide with the obstacle. (b) FAGV continues on the current path. When FAGV travels to the intersection point of the track, the obstacle is still not reached.
Figure 13. Dynamic obstacles for low-speed movement. (a) There is an unknown low -speed dynamic obstacle in front of the FAGV and it is predicted that the FAGV will not collide with the obstacle. (b) FAGV continues on the current path. When FAGV travels to the intersection point of the track, the obstacle is still not reached.
Sensors 22 07079 g013
Figure 14. Dynamic path planning algorithm for FAGV returns a global path after avoiding dynamic obstacles. (a) FAGV detects a dynamic obstacle that is about to collide. (b) FAGV drives along the local path for obstacle avoidance. (c) FAGV returns the global path after obstacle avoidance.
Figure 14. Dynamic path planning algorithm for FAGV returns a global path after avoiding dynamic obstacles. (a) FAGV detects a dynamic obstacle that is about to collide. (b) FAGV drives along the local path for obstacle avoidance. (c) FAGV returns the global path after obstacle avoidance.
Sensors 22 07079 g014
Figure 15. Dynamic path planning algorithm for FAGV returns a global path after avoiding static obstacles. (a) FAGV detects a static obstacle that is about to collide. (b) FAGV returns to the global path after avoiding static obstacles.
Figure 15. Dynamic path planning algorithm for FAGV returns a global path after avoiding static obstacles. (a) FAGV detects a static obstacle that is about to collide. (b) FAGV returns to the global path after avoiding static obstacles.
Sensors 22 07079 g015
Table 1. Speed Parameters of DW.
Table 1. Speed Parameters of DW.
Parameter NameNumerical Value
maximum/ minimum line velocity1/0 m/s
maximum/ minimum angular velocity0.35/−0.35 rad/s
maximum/ minimum linear acceleration0.2/0 m/s2
maximum/ minimum angular acceleration0.9/−0.9 rad/s2
prediction time T3 s
interval time ∆t0.1 s
Table 2. Comparison of algorithms mentioned in this paper.
Table 2. Comparison of algorithms mentioned in this paper.
AlgorithmGlobal OptimalitySmooth PathLocal OptimalityDeceleration Obstacle AvoidanceDynamic Obstacle Avoidance
Tradition A*××××
Improved A*×××
Tradition DWA××××
Improved DWA×
Hybrid Algorithm
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Wu, B.; Chi, X.; Zhao, C.; Zhang, W.; Lu, Y.; Jiang, D. Dynamic Path Planning for Forklift AGV Based on Smoothing A* and Improved DWA Hybrid Algorithm. Sensors 2022, 22, 7079. https://doi.org/10.3390/s22187079

AMA Style

Wu B, Chi X, Zhao C, Zhang W, Lu Y, Jiang D. Dynamic Path Planning for Forklift AGV Based on Smoothing A* and Improved DWA Hybrid Algorithm. Sensors. 2022; 22(18):7079. https://doi.org/10.3390/s22187079

Chicago/Turabian Style

Wu, Bin, Xiaonan Chi, Congcong Zhao, Wei Zhang, Yi Lu, and Di Jiang. 2022. "Dynamic Path Planning for Forklift AGV Based on Smoothing A* and Improved DWA Hybrid Algorithm" Sensors 22, no. 18: 7079. https://doi.org/10.3390/s22187079

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