Next Article in Journal
Federated Learning and Reputation-Based Node Selection Scheme for Internet of Vehicles
Previous Article in Journal
Mitigating Randomness Leakage in SM2 White-Box Implementations via Trusted Execution Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Fusion Algorithm of Robot Path Planning Based on Improved Gray Wolf Algorithm and Dynamic Window Approach

1
School of Computer Science and Engineering, Wuhan Institute of Technology, Wuhan 430205, China
2
School of Mechanical Engineering, Hubei University of Technology, Wuhan 430068, China
*
Author to whom correspondence should be addressed.
Electronics 2025, 14(2), 302; https://doi.org/10.3390/electronics14020302
Submission received: 6 December 2024 / Revised: 1 January 2025 / Accepted: 6 January 2025 / Published: 14 January 2025

Abstract

:
To tackle the problems of sluggish convergence rates, low precision, and limited applicability to static settings, a fusion algorithm of the improved Gray Wolf Algorithm and the improved Dynamic Window Approach is proposed. With regard to the Gray Wolf Algorithm, an adjustable nonlinear convergence factor is used to search and optimize the balance of the algorithm in the initial phase of the iteration process, and the candidate wolves are accepted through a simulated annealing operation in the late stage of iteration to prevent local optima and achieve the global path planning. With regard to the Dynamic Window Approach, an adaptive weight is introduced to safely control the speed for passing obstacles and an offset evaluation function is enrolled to prevent excessive local path deviation. Then, the algorithm extracts key waypoints from the global path for detailed local planning, so that the initial orientation angle succeeds the orientation angle that attained the local target point on the previous occasion and generate the shortest and smooth path from the start point to the target point. Finally, the algorithm is applied to various test scenarios for path planning simulation tests, demonstrating that the proposed algorithm is feasible and possesses superior exploration capabilities.

1. Introduction

Path planning is one of the most important fields of research in the field of mobile robots. Path planning of mobile robots involves planning a collision-free path that meets certain conditions (usually the optimal) to achieve the objective position amidst stationary or shifting surroundings [1,2]. Good path planning technology for mobile robots can be applied to explore harsh environments that humans cannot reach and can also be applied to the field of intelligent warehousing, reducing manpower and material resources and improving the overall transportation efficiency, which is a very meaningful research topic [3,4,5].
The path planning algorithms of mobile robots have been deeply studied both at home and abroad, including global path planning in known territories and local path planning in uncharted territories [6]. The primary focus of the global planning algorithm is on navigating through static, known environments, where prior map construction allows the robot to efficiently reach its destination along the shortest possible route. Common global path planning algorithms include the intelligent bionic algorithm (Genetic Algorithm, etc.) and graph search algorithm (A* Algorithm, etc.) [7]. Local path planning refers to the navigation strategy of a robot that leverages immediate sensory data to maneuver dynamically and adapt to uncharted surroundings. The disadvantage is the lack of global nature, and it may be caught up in local optimization [8], mainly including the Artificial Potential Field Approach (APF) and Dynamic Window Approach (DWA). Global path planning and local path planning focus on different aspects. The former involves overall planning, aiming at obtaining the global optimal path [9,10]. The latter dynamically evades obstacles. To achieve efficient route planning for mobile robots, it is essential to integrate the two components.
The Gray Wolf Algorithm (GWO) is widely used in path planning because of its simple structure and easy implementation, but the traditional GWO algorithm has some defects such as low convergence accuracy and prematurity [11,12,13]. Zhang et al. set the distance change rate according to the distance between wolf pack individuals, introduced dynamic weights to improve the position update formula, and successfully applied the improved algorithm to three-dimensional path planning. Yin Lingyi et al. put forward the concept of node priority and utilized the vertices from improved GWO algorithm global path planning as provisional goals within the artificial potential field approach to address the issue of inaccessible provisional goals caused by the presence of moving obstacles. However, the above defects have not been significantly solved.
Addressing the issues of sluggish convergence rates, the limitation to static settings in the GWO algorithm, and the limitations inherent to the global path planning component of the DWA algorithm, this study enhances both the GWO and DWA algorithms. Consequently, a fusion algorithm that integrates the improved GWO (GSGWO) with the improved DWA (IDWA) is presented. The algorithm utilizes genetic mutation and simulated annealing processes to optimize its performance, facilitating global path planning.
Following that, the algorithm extracts local key points building upon the existing path, subsequently employs the DWA to execute local path planning, and generates the shortest and smooth path from the origin to the destination.

2. GWO Algorithm

The optimization process of the GWO algorithm is carried out through the collaborative dynamics within a pack of wolves. Within this pack, each wolf assumes a distinct role, establishing a rigid hierarchy, as depicted in Figure 1. The algorithm’s best solution is indicated by the alpha wolf, while the beta wolf and delta wolf denote the secondary and tertiary optimal solutions, respectively. These lead the omega wolf in its search for targets. Throughout the optimization phase, the coordinates of the alpha, beta, delta, and omega wolves are modified [14].
The model of a gray wolf surrounding its prey can be represented by the following equation:
D = C X n ( t ) X ( t )
X ( t + 1 ) = X p ( t ) A D
In Formula (1), D denotes the geographical distance each wolf maintains from its pursued objective. Formula (2) is the position update formula of wolf pack individuals: in the t-th generation, the symbol X p ( t ) denotes the site of quarry, while X ( t + 1 ) indicates the site of a wolf during the (t + 1)-th generation. A and C are the coefficients, and the computation procedure is detailed hereafter:
A = 2 a r 1 a
C = 2 r 2
In this formula, a is the convergence factor, as the iterative process decreases linearly from two to zero. r 1 and r 2 are random values Between zero and one. A and C are the coefficient vector.
Alpha wolves generally direct the hunt, with the pack’s gray wolves capable of pinpointing and encircling their prey. Within the wolf pack hierarchy, the α wolf, the β wolf and the δ wolf exhibit the keenest awareness of the prey’s probable whereabouts. The positional adjustments of the remaining wolves are guided by the positions of these three dominant individuals. The mathematical model of a gray wolf searching for prey is shown in Figure 2 [15].
D α = C 1 X α X , D β = C 2 X β X , D δ = C 3 X δ X
X 1 = X α A 1 D α , X 2 = X β A 2 D β , X 3 = X δ A 3 D δ
X ( t + 1 ) = X 1 + X 2 + X 3 3
In Formula (5), D α , D β , and D δ denote the distance that separates the ω wolf from the α wolf , the β wolf and the δ wolf, respectively. Formula (6) specifies the orientation and separation between the ω wolf and α wolf, β wolf, δ wolf. Formula (7) denotes a new generation of individual gray wolves.

3. Algorithm Improvement of GWO Algorithm

3.1. Nonlinear Convergence Factor

In the GWO algorithm, nonlinear convergence factors control the hunting process, specifically the search and encircle of prey. When the magnitude of |A| exceeds 1, the gray wolf and prey exhibit a tendency to move apart, suggesting the algorithm’s strength in global optimization. Conversely, when |A| is less than 1, it implies the gray wolf is near the prey, signaling an impending attack, which reflects the algorithm’s proficiency in local exploration. Clearly, a value of |A| greater than 1 indicates a shortcoming in local exploitation, while a value less than 1 signifies a limitation in global search capability [16]. The linear variation cannot be fully adapted to the GWO search process. Therefore, in order to make the convergence factor decrease slowly during the preliminary period and greatly during the subsequent period, this paper makes nonlinear adjustments and uses the Sigmoid function to express
a = a 1 + a 1 + a 2 1 + e ( 2 S max K k K S max )
In Formula (8), a 1 and a 2 correspond to the lower and upper thresholds of the values. K represents the maximum iteration threshold, and k signifies the iteration count at present. The comparison of convergence factors is demonstrated in Figure 3.

3.2. Adaptive Cross Mutation Strategy

With the intention of bolstering the GWO algorithm’s global exploration capabilities and enriching the diversity within the gray wolf population, an adaptive probabilistic cross mutation strategy has been integrated. In order to prevent premature convergence during the initial iterations, it is essential to elevate the probabilities of crossover and mutation. Conversely, as iterations progress, these probabilities should be decreased to prevent the loss of optimal solutions [17]. Following the adaptive crossover and mutation operations on the initial population, a refreshed population denoted by X’ is generated and merged with the existing gray wolf population X. The fitness of the merged gray wolf individuals is ranked, and the subset with superior fitness—constituting half of the total population—is advanced to the subsequent iteration. The schema for crossover mutation is delineated henceforth:
X 1 = [ x 1 1 , x 1 2 , , x 1 dim ]
X 2 = [ x 2 1 , x 2 2 , , x 2 dim ]
X 3 = [ x 3 1 , x 3 2 , x 3 3 , , x 3 dim ]
X 1 = [ x 1 1 , x 1 2 , x 2 n , , x 1 dim ]
X 2 = [ x 2 1 , x 2 2 , x 1 n , , x 2 dim ]
X 3 = [ x 3 1 , x 3 2 , y n , x 3 n + 1 , , x 3 dim ]
In this formula, X 1 and X 2 denote two gray wolf individuals ready for hybridization. X 1 and X 2 denote the gray wolf individuals after hybridization. X 3 is the gray wolf entity before the mutation occurred. X 3 is the gray wolf entity after the mutation occurred. Dim denotes dimension.
The cosine-based adaptive crossover mutation probability formula is outlined below:
P c = ( P c 1 + P c 2 ) / 2 × cos ( ( f f a v g ) / ( f max f a v g ) π / 2 ) f f a v g P c 1 f <   f a v g
P m = ( P m 1 + P m 2 ) / 2 × cos ( ( f f a v g ) / ( f max f a v g ) π / 2 ) f f a v g P m 1 f <   f a v g
In this formula, P c 1 and P m 1 indicate the upper bounds of the crossover and mutation probabilities., respectively. P c 2 and P m 2 are the minimum. The individual fitness value is f . f a v g and f max represent the mean fitness value and the peak fitness value, respectively.

3.3. Simulated Annealing Operation

During the intermediate and final phases of the GWO optimization, the population of gray wolves often gravitates towards the α wolf, β wolf, and δ wolf. When the α wolf, β wolf, and δ wolf are trapped in a local region while hunting, the entire gray wolf population will fall into a limited search space, hindering further evolutionary progress. Motivated by the strategy of the elite, the algorithm incorporates simulated annealing operations in its later stages to improve the disadvantage of the GWO algorithm easily falling into local optimal in the late stages of optimization [18]. Towards the end of the optimization process, once the fitness of the new wolf pack generation is determined, individuals with the top fitness scores have a certain likelihood of being promoted to the rank of alpha wolf, which effectively decreases the risk of the algorithm getting stuck in local optima during the later period of the algorithm optimization. The principal steps are presented below:
First, the initial temperature and the cooling function are determined:
T 0 = f g ( l ) log ( 5 )
T l + 1 = λ T l
In this formula, f g ( l ) stands for the fitness of the best-performing individual (α wolf) in the population for the present iteration. l is the number of cooling. λ is the cooling constant.
Then, the probability of accepting the candidate wolf is calculated according to the temperature:
P = exp [ f p ( l ) f g ( l ) T l ]
Within this formula, f p ( l ) signifies the value of the optimal individual fitness of the wolf pack after l time of cooling.
Finally, the α wolf is updated according to the Metropolis criterion, denoted as
g b e s t ( l ) = p b e s t ( l ) f p ( l ) < f g ( l ) g b e s t ( l 1 ) f p ( l ) f g ( l ) & P < r   p b e s t ( l ) f p ( l ) f g ( l ) & P r  
In this formula, r represents a uniformly distributed stochastic variable across the range zero to one. If the optimal individual fitness value f p ( l ) after l time of cooling is less than the optimal individual fitness (α wolf) f g ( l ) , the individual corresponding to f p ( l ) is called the α wolf. If the fitness of the optimal individual f p ( l ) after l time of cooling is greater than the fitness of the optimal individual (α wolf) f g ( l ) , then we continue to determine whether the acceptance probability P is greater than the random number r. If P r , the individual corresponding to f p ( l ) is promoted to α wolf; otherwise, the α wolf from the previous iteration is retained.

3.4. Algorithm Testing and Analysis

The improved algorithm underwent evaluation utilizing seven standard test functions that are widely recognized globally, as shown in Table 1. After running 50 experiments, the results were compared with GWO, COGWO, FMGWO, and IGWO to verify the superiority of various performance indexes of the algorithm [19,20,21].
Within the scope of this experimental simulation, the pertinent parameter settings for the GSGWO algorithm are displayed in Table 2.
Table 3 presents the average value and standard deviation derived from 50 simulation trials. Among them, GWO1 represents the GWO algorithm improved by the adaptive cross-mutation strategy and simulated annealing operation, and GWO2 represents the GWO algorithm improved by the nonlinear convergence factor only. It can be seen that the GWO1 algorithm performs better on single-peak functions f1-f4 and multi-peak functions f4 and f6, while the traditional GWO algorithm performs poorly on these functions, which verifies the effectiveness of the cross-mutation strategy and simulated annealing operation.

4. DWA Algorithm

The Dynamic Window Approach (DWA) is instrumental in the domain of local path planning algorithms, exerting a significant influence, capable of generating secure paths in real time by taking into account the robots’ dynamic capabilities. Its principle involves establishing a two-dimensional velocity space v , ω composed of linear and angular velocities. Within a short time interval Δ t , it constructs a search space consisting of feasible trajectories corresponding to all velocities under dynamic constraints. An objective function is then used to opt for the most advantageous trajectory, and the mobile robot is driven according to the corresponding velocities v , ω for path planning [22,23,24].
The motion state of the mobile robot is described by velocity space v , ω . Assuming that the time interval Δ t is small and the robot progresses in a straight direction with constant velocity within Δ t , the subsequent kinematic model is presented [25]:
x t + 1 = x t + v x Δ t cos ( θ t ) v y Δ t sin ( θ t ) y t + 1 = y t + v x Δ t sin ( θ t ) + v y Δ t cos ( θ t ) θ t + 1 = θ t + ω Δ t
In this formula, x t and x t + 1 specify the x-axis locations of the mobile robot at t , t + 1 , respectively. y t and y t + 1 specify the y-axis locations of the mobile robot at t , t + 1 , respectively. θ t and θ t + 1 , respectively, indicate the orientation angle of the mobile robot at t , t + 1 . v indicates linear velocity. ω expresses angular velocity.
Once the kinematic model has been formulated, the subsequent step involves determining the velocity, essentially developing a model to solve for velocity. In the velocity space v , ω , there is an infinite set of velocity possibilities, which must be narrowed down based on the robot’s actual conditions to derive a viable velocity range:
(1) Velocity constraint:
The robot’s velocity is restricted by the limits of its own speed capacity and the applied safety factor, and its velocity constraint space is characterized by V m :
V m = ( v , ω ) | v V min , V max , ω ω min , ω max
In this formula, V min , V max and ω min , ω max correspond to the minimum and maximum values of the robot’s linear and angular velocities, respectively.
(2) Dynamic constraint:
According to the different motor performance of the applied mobile robot, the acceleration and deceleration speed are different, so it is necessary to apply dynamic performance constraints:
V d = ( v , ω ) | v v c v b Δ t , v c + v a Δ t , ω ω c ω b Δ t , ω c + ω a Δ t
In this formula, V d denotes the dynamic constraint space. v c and ω c denote the mobile robot’s existing linear and angular velocity. v a and ω a express maximum acceleration. v b and ω b indicates the maximum deceleration speed.
(3) Braking distance constraints:
To guarantee safety, considering the maximum deceleration requirement, the mobile robot must be able to come to a halt prior to colliding with any obstacle, meaning the velocity should be reduced to 0. V a represents the braking distance constraint space:
V a = v , ω | v 2 D i s ( v , ω ) v b 1 / 2 , ω 2 D i s ( v , ω ) ω b 1 / 2
In this formula, D i s ( v , ω ) denotes the nearest distance between the path related to v , ω and the obstacle.
And, the objective function assesses the trajectory associated with the velocity space generated under constraints. It primarily includes the cost function H e a d ( v , ω ) of the target position, the cost function O b s ( v , ω ) associated with proximity to obstacles, and the speed cost function V e l ( v , ω ) . Consequently, the aggregate cost function Cos t ( v , ω ) is articulated in the subsequent manner:
Cos t ( v , ω ) = α H e a d ( v , ω ) + β O b s ( v , ω ) + γ V e l ( v , ω )
In this formula, H e a d ( v , ω ) denotes the angle between the line segment connecting the mobile robot to the target position and the robot’s current heading. O b s ( v , ω ) denotes the minimum distance to the obstacle. V e l ( v , ω ) denotes the speed cost of the immediate simulation. α , β , and γ are the respective weighting factors applied to the cost functions.

5. Algorithm Improvement of DWA Algorithm

5.1. Adaptive Weights

The mobile robot uses lidar to achieve distance measurement functionality. Within lidar’s detection scope, it is capable of determining the distances between the mobile robot and surrounding obstacles. The density of the area is calculated by measuring the distances between obstacles within the detection range. If the gap falls below a predetermined limit, it is classified as a dense obstacle area, and the weights are adjusted in correspondence with the new parameters. The formula for the distance between obstacles is as follows:
D a b = O b s ( v , ω ) a 2 + O b s ( v , ω ) b 2 O b s ( v , ω ) a O b s ( v , ω ) b cos θ a θ b
In Formula (26), D a b denotes the minimal distance between obstacles O a and O b . O b s ( v , ω ) a and O b s ( v , ω ) b , respectively, indicate the minimal separations among the obstacles. O a and O b are the mobile robots. The corresponding heading angles of the mobile robot with respect to obstacles O a and O b are denoted as θ a and θ b , respectively. Figure 4 provides a depiction.
Set the criteria for whether the robot can safely pass by obstacles:
If D a b > 2 R c , the mobile robot can pass safely. R c is the expansion radius of the obstacle.
Obs ( v , ω ) a l l represents the set of shortest distances between all obstacles in the sector and the robot. The minimum value min O b s ( v , ω ) all   from this set is chosen as the input for the cost function. The ensuing algebraic formulation specifies
O b s ( v , ω ) all   = { O b s ( v , ω ) 1 , O b s ( v , ω ) 2 , , O b s ( v , ω ) n }
And, the formula for safety distance threshold D s is
D s = γ v max v a
In Formula (28), γ is the threshold factor. v max and v a denote the peak forward speed and linear acceleration capabilities of the mobile robot, respectively. An increase in acceleration correlates with a reduced safety distance threshold, while a higher linear velocity is associated with an increased safety distance threshold.
If min O b s ( v , ω ) all   is greater than D s , there is no necessity to decrease the speed, so the parameters of the speed function can be set to the maximum value.
If min O b s ( v , ω ) all   is less than or equal to D s , introduce the adaptive parameter ξ to control the speed function, as shown in the following formula:
ξ = ξ min + ξ max ξ min sin min O b s ( v , ω ) a l l D s , min O b s ( v , ω ) a l l D s ξ max , min O b s ( v , ω ) a l l > D s
In Formula (29), the range of ξ is ξ min , ξ max with ξ min and ξ max corresponding to the values for successfully passing through densely packed obstacles and for passing through areas with a higher density of obstacles in the shortest time, respectively. The weighted coefficient of the speed function in the traditional DWA algorithm’s cost function is replaced by the improved adaptive weights.

5.2. Offset Evaluation Function

Incorporating adaptive weights into the velocity function, a novel offset evaluation function Mis ( v , ω ) is proposed to ensure that the Dynamic Window Approach (DWA) better aligns with the optimal trajectory generated by the improved global path planning algorithm (GSGWO). This function assesses the degree by which the local path generated by the DWA algorithm deviates from the global optimal path. It ensures that while achieving local obstacle avoidance and path planning, the generated trajectory follows the global path with the highest possible precision.
The offset evaluation function Mis ( v , ω ) serves to determine the smallest gap between the anticipated trajectory of the DWA algorithm at a given position and the global path. The cluster of nodes in the path generated by the global path planning algorithm is represented as P global   = x 1 , y 1 , x 2 , y 2 , , x k , y k , with a total of K nodes. The projected positional coordinates derived from the DWA at time t is x t , y t . The corresponding equation is articulated subsequently:
D i s k t = x t x k 2 + y t y k 2
D i s t = Dis 1 t , Dis 2 t , , D i s k t }
Mis ( v , ω ) = min D i s t
In this formula, x t , y t are the horizontal and vertical coordinates, respectively, of the approximated location of the DWA algorithm at time t , while x k , y k are the horizontal and vertical coordinates, respectively, of the k -th node in the path. D i s k t represents the Euclidean distance between the approximated location of the DWA algorithm at time (t) and the k -th node in the path. D i s t is the set of distances to the nodes.
Based on this, the refined cost function N Cos t ( * ) is hereby specified:
N Cos t ( v , ω ) = α Head ( v , ω ) + β Obs ( v , ω ) + ξ Vel ( v , ω ) + φ M i s ( v , ω )
In Formula (33), H e a d ( v , ω ) denotes the deviation in angle between the line from the robot to the target and the robot’s current directional heading. O b s ( v , ω ) denotes the smallest distance to the obstacle. c represents the speed cost of the current simulation. α , β , ξ , and φ are the respective weighting factors applied to the cost functions.

6. Fusion Algorithm Based on GSGWO and IDWA

The improved GWO algorithm enhances the capacity of global path planning, but only for static environments, and there are cusps in the path. The DWA algorithm is a well-established local path planning algorithm with strong practicability, but it is prone to getting stuck in local optima and lacks a global perspective. After optimizing the GWO algorithm, it further adopts the DWA algorithm to execute real-time evasion of obstacles in a dynamic environment, while optimizing the path’s smoothness to satisfy the robot’s motion performance, and puts forward a fusion algorithm building upon the improved Gray Wolf Algorithm (GSGWO) and improved DWA (IDWA) [26,27,28].
The underlying mechanism behind the fusion algorithm is as follows: The GSGWO algorithm is applied to derive a global trajectory, followed by the extraction of critical nodes as local target locations. The primary factor influencing the trajectory’s smoothness is heading angle. Therefore, the initial heading angle inherits the heading angle that reached the local target point last time when the IDWA algorithm is implemented to design the robot’s local path, to therefore ensure the smoothness of the path. The flow chart is depicted in Figure 5.
The detailed execution procedure is outlined below:
  • Initialize the parameters of the GSGWO algorithm for global path planning.
  • Utilize the GSGWO algorithm to calculate fitness and identify the alpha wolves, which represent the best solutions in the current iteration.
  • Update position X and convergence factor a within the GSGWO algorithm.
  • Perform crossover mutation and simulated annealing operations to avoid local optima and enhance solution diversity until the termination condition is met, and then, generate the global path.
  • Extract the key node P 0 , P 1 , P n + 1 of the global path serving as the local target, and the initiation of each local trajectory is S S 1 , S 2 , S n = P 0 , P 1 , P n . Each local target point is G G 1 , G 2 , G n = P 1 , P 2 , P n + 1 , and the path is divided into n local paths composed of S 1 G 1 , S 2 G 2 , S n G n .
  • For the local path S 1 G 1 , the IDWA algorithm is utilized to determine the trajectory, and the velocity space v , ω and course angle θ 1 s (referring to the course angle at the starting point S 1 ) are initialized. A 2D velocity space v , ω comprising linear and angular components is established.
  • Build the robot kinematic model.
  • The ideal path is chosen based on the criteria defined by the objective function Cos t , and the corresponding speed ( v , ω ) is used to drive the mobile robot for path planning. Record the heading angle θ 1 G when the robot reaches G 1 .
  • The IDWA algorithm is utilized for the trajectory S 2 G 2 , and the initial heading angle of θ 2 S = θ 1 G , that is, the second path’s local path planning retains the orientation angle from the prior phase to ensure the smoothness of the generated path.
  • The IDWA algorithm is repeatedly utilized for the trajectory S 3 G 3 , S n G n successively.
  • Record the planned route S 1 G 1 , S 2 G 2 , S n G n , and finally, output the complete path.

7. Experimental Simulation and Analysis

The experimental setup for this algorithm utilizes a 64-bit WIN10 operating system with a memory capacity of 16G, and the experimental platform is MATLAB 2016. In order to maintain a good comparison effect, the commencement and termination points of the route in the experiment are, respectively, (0,0) and (10,10). The subsequent parameters are detailed in Table 4:

7.1. Global Path Planning

The experimental procedure is initiated within the parameters defined by Scenario 1, which entailed a comparison of the algorithm’s path planning performance against both the conventional GWO and PSO algorithms. Scenario 1 was a mixed map of black solid squares and black solid round obstacles, with a total of eight obstacles. And, the black hollow circles represent robots of a certain size. Owing to the high density of these obstacles, the algorithm was configured to use five path nodes. The classical test function is used to train the algorithm, and it was established that the enhanced version of the GSGWO algorithm is capable of attaining the optimal solution under a small population. Consequently, the aggregate number of individuals in the population becomes 20 and the supreme number of iterations becomes 100.
Figure 6 illustrates the optimal paths of several algorithms. Among them, the black solid squares and black solid round obstacles represent obstacles. The combination of black hollow circles and curves represents the path planned by robots and the triangle represents the endpoint. One can observe that the GWO algorithm and PSO algorithm have larger turning angles and fall into local optima, while the GSGWO algorithm generates smoother paths.
Table 5 lists the average fitness, optimum fitness, worst fitness, and standard deviation of the outcomes of fifty runs. It is observable that relative to conventional heuristic methods, the GSGWO algorithm has a better path optimization ability, a shorter generated path length, a smaller standard deviation, and better stability.

7.2. Local Path Planning

In this experiment, the algorithm of fusion of the improved GSGWO and IDWA algorithm is substantiated by experimental results and subjected to a comparative analysis with the traditional dynamic window method in Scenario 2. Scenario 2 is a hybrid map of both fixed and moving obstacles, with eight static black solid round obstacles and a black solid square obstacle moving uniformly to the left. And, the black hollow circles represent robots of a certain size. The commencement and termination points of the route in the experiment are (0,0) and (10,10), respectively.
In Figure 7, the black solid squares and black solid round obstacles represent obstacles. The combination of black hollow circles and curves represents the path planned by robots and the triangle represents the endpoint. As illustrated in Figure 7a, the path obtained by the DWA algorithm gets stuck in local optimal, which, despite being smooth, contains redundant sections. Figure 7b shows that subjected to a comparative analysis with the traditional algorithm, the path generated by the fusion algorithm is significantly shorter and has higher path smoothness. The fusion algorithm improves the problem of poor smoothness and real-time performance of the global path planning algorithm and overcomes the issue of local path planning algorithms being prone to getting stuck in local optima, and the generated path conforms to the robot kinematic model.
With the intention to evaluate the performance of the fusion algorithm more comprehensively, the number of dynamic obstacles is increased for experimental testing. By modeling a higher degree of environmental complexity, we observe how the algorithm performs against multiple dynamic obstacles. During the experiment, the path planning results of the fusion algorithm under multiple moving obstacles were recorded, and the corresponding path diagram was depicted, as illustrated in Figure 8. Among them, the black solid squares and black solid round obstacles represent obstacles. The combination of black hollow circles and curves represents the path planned by robots and the triangle represents the endpoint.
As is observable in Figure 8b, when encountering dynamic obstacles, the path can quickly be adjusted and avoid the obstacles immediately. Figure 8c shows the final path graph generated by the fusion algorithm.
After continuing to increase the number of dynamic obstacles and observing the path planning capabilities of the DWA and fusion algorithm, the delineated trajectory’s extent is depicted within Figure 9. Among them, the black solid squares and black solid round obstacles represent obstacles. The combination of black hollow circles and curves represents the path planned by robots and the triangle represents the endpoint. The dashed curve is used to mark the path generated by the traditional DWA algorithm, while the solid curve is used to represent the path generated by the new algorithm after fusion.
Figure 10 shows the path length variation diagram.
Figure 10 demonstrates that with the increase in obstacles, the path generated by the traditional DWA algorithm increases significantly, while the fusion algorithm has little change in path length, high stability, and strong ability to pass through dense obstacle areas when obstacles increase. The experimental outcomes thoroughly confirm the efficacy of the improved algorithm.

7.3. Experimental Scenario Verification

An indoor environment with obstacles arranged in the corridor as depicted in Figure 11 was constructed. On the Ubuntu 16.04 platform, path planning was implemented for an autonomous robot utilizing the Robot Operating System (ROS). Initially, it was connected to the Wi-Fi signal emitted by the mobile robot to communicate with the host. Then, lidar was used to build a map of the experimental scenario, and map visualization was implemented. After that, global localization was conducted for the mobile robot. Figure 12 shows a map constructed using a laser radar (Shenzhen Yuedeng Intelligent Technology Co., Ltd., Shenzhen, China), where the regions of black areas indicate the locales of impediments.
The path planning results in the real scenario are shown in Figure 13, with the black square indicating the mobile robot’s placement and the dark red regions denoting the obstacles’ presence. The yellow curve represents the optimal path planned by the mobile robot using the path planning algorithm.
As represented in Figure 14, the mobile robot successfully made its way to the target position along the planned trajectory, and empirical trials have conclusively substantiated the efficacy of the refined algorithm.

8. Conclusions

Firstly, a novel iteration of the GSGWO algorithm is introduced to address the inherent limitations of traditional global path planning methodologies, including slow convergence velocities, diminished precision, and constraints to static environmental conditions. Initially, an adjustable nonlinear convergence factor is used to search and optimize the balance of the algorithm during its initial phase. At the same time, an adaptive genetic hybridization strategy is adopted to breed new individuals in pairs with a certain probability, so as to broaden the diversity of the gray wolf population in an effective manner. The simulated annealing operation is used to accept the candidate wolves in the later iterations, preventing the algorithm from becoming trapped in local optima. The GSGWO algorithm is tested on the classical test function, and the data demonstrate that the proposed algorithm has higher optimization ability and stability than other optimization algorithms. Ultimately, the GSGWO algorithm is subjected to a comparative analysis with other path planning algorithms, with experimental results demonstrating its superiority in terms of faster iterative speeds and enhanced optimization capabilities.
Then, aiming at the problems of local path planning algorithm, such as poor possibility and unreachable targets in dense environments and building upon the foundational principles of the conventional DWA algorithm, this study presents an improved IDWA algorithm. The algorithm divides the map into a dense obstacle map and a sparse obstacle map and adds adaptive weights for speed constraints. The offset evaluation function is added to the objective function for cost to make the generated path as close as possible to the global path planning trajectory.
Finally, the GSGWO algorithm and IDWA algorithm are integrated to ensure that the mobile robot has a global planning ability and local obstacle avoidance. The proposed algorithm is applied to the built simulation experiment environment for test verification and compared with the traditional DWA algorithm. Dynamic obstacle avoidance tests are carried out by continuously adding dynamic obstacles. The test data reveal that the algorithm exhibits better abilities of path optimization and obstacle avoidance.

Author Contributions

Conceptualization, F.L. and D.Y.; methodology, F.L. and D.Y.; validation, X.W. and L.M.; writing—original draft preparation, F.L., X.W. and L.M.; writing—review and editing, F.L. and X.W. All authors have read and agreed to the published version of the manuscript.

Funding

This research received startup funding from the National Natural Science Foundation of China (Project No. 51875180).

Data Availability Statement

The original contributions presented in this study are included in the article; further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest exist.

References

  1. Huai, C.-F.; Guo, L.; Jia, X.-Y.; Zhang, Z.H. Improved A* algorithm and dynamic window method for robot dynamic path planning. Comput. Eng. Appl. 2021, 57, 244–248. [Google Scholar]
  2. Nguyen, Q.-H.; Vu, H.; Tran, T.-H.; Nguyen, Q.-H. Developing a way-finding system on mobile robot assisting visually impaired people in an indoor environment. Multimed. Tools Appl. 2017, 76, 2645–2669. [Google Scholar] [CrossRef]
  3. Tang, L.; Hao, P.; Zhang, X.-J. An UAV path planning method in mountainous area based on an improved ant colony algorithm. J. Transp. Syst. Eng. Inf. Technol. 2019, 19, 158–164. [Google Scholar]
  4. Lin, Y.-S.; Li, Q.-S.; Lu, P.-H.; Sun, Y.-N.; Wang, L.; Wang, Y.-Z. Shelf and AGV path cooperative optimization algorithm used in intelligent warehousing. J. Softw. 2020, 31, 2770–2784. [Google Scholar]
  5. Luo, X.; Ding, X.-J. Research and prospective on motion planning and control of ground mobile manipulators. J. Harbin Inst. Technol. 2021, 53, 1–15. [Google Scholar]
  6. Yadav, R.K.; Anubhav. PSO-GA based hybrid with adam optimization for ANN training with application in Medical Diagnosis. Cogn. Syst. Res. 2020, 64, 191–199. [Google Scholar] [CrossRef]
  7. Cao, X.; Li, X.; Wei, X.; Li, S.; Huang, M.; Li, D. Dynamic Programming of emergency evacuation path based on Dijkstra-ACO hybrid algorithm. J. Electron. Inf. Technol. 2020, 42, 1502–1509. [Google Scholar]
  8. Chen, L. Research on Path Planning Method for Mobile Robots in Dynamic Unknown Environment. Master’s Thesis, Harbin University of Science and Technology, Harbin, China, 10 March 2024. [Google Scholar] [CrossRef]
  9. Niu, H.; Sahoo, A.; Bhowmick, C.; Jagannathan, S. An optimal hybrid learning approach for attack detection in linear networked control systems. IEEE/CAA J. Autom. Sin. 2019, 6, 1404–1416. [Google Scholar] [CrossRef]
  10. Yu, Z.-Z.; Li, Q.; Fan, Q.-G. Survey on application of bioinspired intelligent algorithms in path planning optimization of mobile robots. Appl. Res. Comput. 2019, 36, 3210–3219. [Google Scholar]
  11. Liu, N.; Wang, H. Path planning for mobile robots based on improved grey wolf optimization algorithm. Electr. Meas. Instrum. 2020, 57, 76–83+98. [Google Scholar]
  12. Liu, Z.; He, L.; Yuan, L.; Zhang, H. Path Planning for Mobile Robots Using Improved Grey Wolf Algorithm. J. Xi’an Jiaotong Univ. 2022, 56, 49–60. [Google Scholar]
  13. Liu, Q. Improvement of Grey Wolf Algorithm and Its Application in Robot Path Planning; Henan University: Kaifeng, China, 2022. [Google Scholar] [CrossRef]
  14. Chen, Z.-W.; Xia, S.; Li, J.-X. Serial strategy for rendezvous of multiple UAVS based on directional A* algorithm. Control Decis. 2019, 34, 1169–1177. [Google Scholar]
  15. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey Wolf Optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef]
  16. Gan, F.; Wang, Z.; Lian, Y.; Zhang, S.; Lan, S. Path planning method for mobile robots based on improved grey wolf optimization algorithm. Sens. Microsyst. 2024, 83, 110–113. [Google Scholar]
  17. Wang, H.; Yin, P.; Zheng, W.; Wang, H.; Zuo, J. Mobile robot path planning based on improved A* algorithm and dynamicwindow method. Robot 2020, 42, 346–353. [Google Scholar]
  18. Zhang, H.; Lin, W.; Chen, A. Path planning for the mobile robot: A review. Symmetry 2018, 10, 450. [Google Scholar] [CrossRef]
  19. Li, G.; Chou, W. Path planning for mobile robot using self-adaptive learning particle swarm optimization. Sci. China Inf. Sci. 2018, 61, 052204. [Google Scholar] [CrossRef]
  20. Kang, Y.-X.; Jiang, C.-Y.; Qin, Y.-H.; Ye, C. Robot path planning and experiment with an improved PSO algorithm. Robot 2020, 42, 71–78. [Google Scholar]
  21. Chi, X.; Li, H.; Fei, J.-Y. Research on robot random obstacle avoidance method based on fusion of improved A* algorithm and dynamic window method. Chin. J. Sci. Instrum. 2021, 42, 132–140. [Google Scholar]
  22. Zhang, W.; Shan, L.; Chang, L. Distributed collision avoidance algorithm for multiple unmanned surface vessels based on improved DWA. Control Decis. 2023, 38, 951–962. [Google Scholar]
  23. Wang, H.; Ma, X.; Dai, W.; Jin, W. Research on Improved DWA Algorithm for Mobile Robot Obstacle Avoidance. Comput. Eng. Appl. 2023, 59, 326–332. [Google Scholar]
  24. Deng, Y.; Huang, Y. Improved DWA obstacle avoidance algorithm in dense obstacle environments. Comput. Mod. 2023, 40, 65–70. [Google Scholar] [CrossRef]
  25. Shi, X.; Ni, L.; Qi, H.; Cao, X.; Chen, S.; Xie, X.; Pei, L. A Local Path Planning Method Based on Dynamic Window Method and Applicable to Ackermann Model Robots. CN202011464715.4[P] CN112506199A, 10 March 2024. [Google Scholar]
  26. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the IEEE International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; pp. 1942–1948. [Google Scholar]
  27. Shi, Y.; Eberhart, R. A modified particle swarm optimizer. In Proceedings of the 1998 IEEE International Conference on Evolutionary Computation Proceedings: IEEE World Congress on Computational Intelligence (Cat. No.98TH8360), Anchorage, AK, USA, 4–9 May 1998; pp. 69–73. [Google Scholar]
  28. Wu, W.-H.; Guo, X.-F.; Zhou, S.-Y.; Liu, J.-T. Adaptive constrained differential evolution algorithm based on generalized reverse learning. J. Northwest. Polytech. Univ. 2019, 37, 1000–1010. [Google Scholar] [CrossRef]
Figure 1. Gray wolf hierarchy.
Figure 1. Gray wolf hierarchy.
Electronics 14 00302 g001
Figure 2. Gray wolf location update strategy.
Figure 2. Gray wolf location update strategy.
Electronics 14 00302 g002
Figure 3. Convergence factor comparison diagram.
Figure 3. Convergence factor comparison diagram.
Electronics 14 00302 g003
Figure 4. A graphical representation of the mobile robot’s relation to obstacles.
Figure 4. A graphical representation of the mobile robot’s relation to obstacles.
Electronics 14 00302 g004
Figure 5. Fusion algorithm flow chart.
Figure 5. Fusion algorithm flow chart.
Electronics 14 00302 g005
Figure 6. Path planning.
Figure 6. Path planning.
Electronics 14 00302 g006
Figure 7. Comparison diagram of path planning.
Figure 7. Comparison diagram of path planning.
Electronics 14 00302 g007
Figure 8. Multi-dynamic obstacle path planning.
Figure 8. Multi-dynamic obstacle path planning.
Electronics 14 00302 g008
Figure 9. Multi-dynamic obstacle comparison diagram.
Figure 9. Multi-dynamic obstacle comparison diagram.
Electronics 14 00302 g009
Figure 10. Path length growth curve.
Figure 10. Path length growth curve.
Electronics 14 00302 g010
Figure 11. Map of the experimental scenario.
Figure 11. Map of the experimental scenario.
Electronics 14 00302 g011
Figure 12. Map constructed using a laser radar.
Figure 12. Map constructed using a laser radar.
Electronics 14 00302 g012
Figure 13. Robot path planning process.
Figure 13. Robot path planning process.
Electronics 14 00302 g013
Figure 14. Path diagram of the mobile robot.
Figure 14. Path diagram of the mobile robot.
Electronics 14 00302 g014
Table 1. International standard test function.
Table 1. International standard test function.
FunctionExpressionSearch AreaMinimum
Sphere f 1 x = i = 1 D x i 2 [−100,100]0
Schwefel f 2 x = i = 1 D x i + i = 1 D x i [−10,10]0
Schwefel 1.2 f 3 x = i = 1 D j = 1 i x j 2 [−100,100]0
Schwefel 2.21 f 4 x = max i x i , 1 i D [−100,100]0
Rastrigin f 5 x = i = 1 D x i 2 10 cos 2 π x i + 10 [−5.12,5.12]0
Six-hump camel back f 7 x = 4 x 1 2 2.1 x 1 4 + 1 3 x 1 6 + x 1 x 2 4 x 2 2 + 4 x 2 4 [−5,5]−1.03
Ackley f 6 x = 20 exp 0.2 1 d i = 1 D x i 2 exp 1 d i = 1 D cos 2 π i + e + 20 [−600,600]0
Table 2. GSGWO algorithm-related parameters.
Table 2. GSGWO algorithm-related parameters.
N dim t max a 1 a 2 S max P c 1 P m 1 P c 2 P m 2 λ
503050002200.80.50.080.050.85
Table 3. GSGWO and GWO compare the results of seven benchmark functions.
Table 3. GSGWO and GWO compare the results of seven benchmark functions.
FunctionPropertyGWOIGWOFMGWOGWO1GWO2GSGWO
f 1 average1.25 × 10−5801.64 × 10−15001.47 × 10−1050
standard1.16 × 10−5801.88 × 10−15001.36 × 10−1050
f 2 average1.46 × 10−302.68 × 10−2801.32 × 10−1201.56 × 10−3002.49 × 10−601.46 × 10−315
standard1.55 × 10−306.32 × 10−2801.49 × 10−1191.82 × 10−3001.77 × 10−601.83 × 10−315
f 3 average2.96 × 10−4003.49 × 10−13503.55 × 10−700
standard2.87 × 10−4003.65 × 10−13502.93 × 10−700
f 4 average1.24 × 10−352.12 × 10−2861.55 × 10−1211.67 × 10−2672.33 × 10−621.41 × 10−298
standard1.67 × 10−351.97 × 10−2862.33 × 10−1222.45 × 10−2671.73 × 10−621.23 × 10−298
f 5 average000000
standard000000
f 6 average1.73 × 10−141.89 × 10−151.95 × 10−131.55 × 10−141.72 × 10−121.55 × 10−15
standard1.62 × 10−142.32 × 10−151.32 × 10−132.13 × 10−141.43 × 10−121.32 × 10−15
f 7 average−1.031−1.022−1.033−1.032−1.030−1.021
standard00.0010.0030.0010.010.001
Table 4. DWA-related parameters.
Table 4. DWA-related parameters.
Maximum Linear VelocityMinimum Linear VelocityMaximum Angular VelocityMaximum Linear AccelerationMaximum Angular AccelerationSampling Period
1.5 m/s0 m/s30°/s0.2 m/s240°/s20.1 s
Table 5. Simulation result.
Table 5. Simulation result.
AlgorithmAverage FitnessOptimum FitnessWorst FitnessStandard Deviation
GSGWO14.9514.5015.510.62
GWO17.3214.9119.202.35
PSO16.8715.5320.011.52
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

Liu, F.; Wu, X.; Ma, L.; You, D. A Fusion Algorithm of Robot Path Planning Based on Improved Gray Wolf Algorithm and Dynamic Window Approach. Electronics 2025, 14, 302. https://doi.org/10.3390/electronics14020302

AMA Style

Liu F, Wu X, Ma L, You D. A Fusion Algorithm of Robot Path Planning Based on Improved Gray Wolf Algorithm and Dynamic Window Approach. Electronics. 2025; 14(2):302. https://doi.org/10.3390/electronics14020302

Chicago/Turabian Style

Liu, Fei, Xiankun Wu, Li Ma, and Dazhang You. 2025. "A Fusion Algorithm of Robot Path Planning Based on Improved Gray Wolf Algorithm and Dynamic Window Approach" Electronics 14, no. 2: 302. https://doi.org/10.3390/electronics14020302

APA Style

Liu, F., Wu, X., Ma, L., & You, D. (2025). A Fusion Algorithm of Robot Path Planning Based on Improved Gray Wolf Algorithm and Dynamic Window Approach. Electronics, 14(2), 302. https://doi.org/10.3390/electronics14020302

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