1. Introduction
Automated guided vehicle (AGV) plays a major function in Industry 4.0, the most recent industrial revolution. For robots in motion, planning a path has been a significant area of research throughout their evolution. The steps needed to navigate an environment full of obstacles in the best way are referred to as “path planning” [Reference Yao, Zhang, Shi, Li, Liang, Li and Huang1]. These issues have to be taken into consideration by AGV path planning algorithms. The optimization goals of routing computations are the shortest route, the least path nodes, and minimizing turn magnitude. These computations are made to take an autonomous vehicle from its current position to its objective location, avoid obstacles, and improve its motion track [Reference Tanveer, Recchiuto and Sgorbissa2]. The local path planner is in service of making changes in real time so that the path stays on track with the global path and avoids any moving or fixed obstacles that the global path planner doesn’t see. The vehicle’s navigation system uses both methods of planning. Effective global and local path planning are crucial for autonomous vehicle navigation, particularly for mecanum wheeled-based vehicles. They have different goals and use different methods of navigation. When the AGV operates in a static or dynamic environment, there is a need to determine its path planning type [Reference Sharma and Voruganti3]. Using real-time local path and sensor data integration, AGV may maneuver in unexpected and dynamic environments [Reference Khan, Khatoon, Gaur, Abbas, Saleel and Khan4]; however, because it heavily relies on the environment around it, dynamic route planning alone might not be sufficient to identify the completely ideal route [Reference Wahhab and A.5]. Before the AGV moves, the global perfect path is found by scanning the current environment map model utilizing a static path planning mechanism. With unparalleled flexibility and efficiency, omnidirectional mecanum wheels on AGVs transformed complex industrial mobility. Traditional path planning and control algorithms struggle with static and dynamic real-time control. Conventional techniques such as A* can provide optimal pathways, but they aren’t appropriate for dynamic applications since they are computationally costly and lead to jerky trajectories. Although effective, Probabilistic Roadmap (PRM)-based global travel planning is not adaptable in real-time or in densely populated places. Large regions can be rapidly investigated with Random Tree (RRT) and Bidirectional RRT (Bi-RRT) methods, but they also generate less-than-ideal pathways that must be relaxed after processing, adding to the computational load [Reference Liu, Liu and Xiao6].
While state-of-the-art techniques such as the Modified Elman Recurrent Neural Network are effective for learning-based dynamic control, their relevance to real-world AGV navigation is constrained by their difficulty with standardization in unstructured circumstances and their enormous data set requirements [Reference Kanoon, Al-Araji and Abdullah7]. Hybrid swarm optimization techniques integrate various meta-heuristics to optimize routes; yet, they are slow for convergence and ineffective when running in real time [Reference El Aziz, Ewees, Hassanien, Bhattacharyya, Dutta, De and Klepac8]. Kinematic path-tracking controls employ the Back-Stepping Slice Genetic robust Algorithms being durable but computationally costly and challenging to scale in applications that require real-time control [Reference Al-Araji9]. Recent hybrid algorithms like RRT*-PSO [Reference Rasheed, Al-Araji and Abdullah10] and the A*–FAHP Hybrid Algorithm [Reference Kim, Suh and Han11] incorporate path planning with Particle Swarm Optimization [Reference S. and R.12] and Fuzzy Analytic Hierarchy Process [Reference Tolossa, Gunasekaran, Halder, Verma, Parswal, Jorwal, Maria Joseph and Hote13]; however, they have significant computational costs and impoverished convergence in unpredictable circumstances. A more durable and effective solution is needed due to these limitations. To solve these issues, this article suggests a Hybrid Modified A* method that combines modified A*’s path optimal with PSO real-time adaptability and efficient swarm-based techniques and compares with A*, PRM, RRT, and Bi-RRTs to prove the effectiveness of HMA*. This complete method simplifies and speeds up omnidirectional AGV path planning in complicated and dynamic contexts.
AGV setups with omnidirectional mecanum wheels are highly useful due to their distinctive feature of being able to move in any direction regardless of orientation. This feature allows them to move across restricted spaces with more dexterity and accuracy, which makes it ideal for complicated and rapid industrial environments [Reference Yuan, Chang, Song, Lin and Jing14]. Although mecanum wheel AGVs have several benefits, operating and maneuvering them is very challenging. Precise and efficient path planning is necessary to fully utilize them, and this necessitates the inclusion of advanced algorithms capable of handling the intricacies of omnidirectional movement. Traditional path planning algorithms, such as A*, are still commonly used, but they often fall short of optimizing routes for mecanum wheel AGVs due to their reliance on predetermined movement patterns and restrictions when it comes to handling dynamic obstacles [Reference Nfaileh, Alipour, Tarvirdizadeh and Hadi15].
The Hybrid Modified A* algorithm was created especially for omnidirectional mecanum wheel AGVs in order to overcome difficulties stated above. The proposed algorithm synergizes the robust pathfinding capabilities of the MA* algorithm with dynamic path optimization techniques tailored for omnidirectional navigation. Through the utilization of multi-sensor fusion, the algorithm is able to dynamically adapt to continuous changes in the surrounding environment, thereby guaranteeing the most effective route selection and avoiding obstacles.
The paper’s outline is as follows: Section 2 provides literature review, and Section 3 provides the detail about AGV’s locomotion. Section 4 provides a summary of Modified A* and PSO evolutionary algorithms, while Section 5 provides Hybrid Modified A* (HMA*) algorithm in detail. Section 6 presents the experiment of path planning and simulation. Section 7 examines obstacle environment-based simulation and real-time experiments. Section 8 offers experimental validation, and Section 9 gives the conclusion and the scope for the future.
2. Literature review
One of the biggest problems with the task is that the algorithms used to plan paths for autonomous vehicles are very complicated. Static route design employs procedures that can be broadly classified into artificial intelligence algorithms and heuristic algorithms [Reference Mao, Chen, Spyrakos-Papastavridis and Dai16]. Numerous heuristic techniques have been thoroughly studied, including A* [Reference Guo, Huo, Guo and Xu17], Dijkstra [Reference Wei, Gao, Zhang and Lin18], D* [Reference Guo, Liu, Liu and Qu19], LPA* [Reference Karur, Sharma, Dharmatti and Siegel20], RRT [Reference Wang, Wei, Zhou, Xia and Gu21], and PRM [Reference Li, Xu, Bu and Yang22]. A* algorithm based on guidelines, inverted length weighted interpolation for the D* Lite method [Reference He, Xing and Ma23], enhanced PRM algorithm [Reference Gopika, Bindu, Ponmalar, Usha and Haridas24], hybrid heuristic-based A* method [Reference Yang, Han, Xiang, Liu, Ma and Ruan25], B-spline curve combined with A* [Reference Eshtehardian and Khodaygan26], bidirectional alternate searching A* technique [Reference Li, Huang, Ding, Song and Lu27], RRT method with an APF background [Reference Katiyar and Dutta28], Triangle inequality-based RRT-connect algorithm [Reference Zhang, Shi, Yi, Tang, Peng and Zou29], and quickly growing arbitrary tree algorithm [Reference Wang, Chi, Shao and Meng30] are a few of the recent advances. Furthermore, a multitude of artificial intelligence optimization techniques, including genetic algorithms (GAs) [Reference Umar, Ariffin, Ismail and Tang31], divergent evolutionary [Reference Wang, Dong, Zhang and Qin32], ants colonies optimizing (ACO) [Reference Xiao, Yu, Sun, Zhou and Zhou33], and particle swarm optimizing (PSO) [Reference Cao and Zhu34], are employed in static path planning. The path planning process is optimized through the application of these solutions. Several novel methods, including enhanced PSO with minimum-maximum normalization [Reference Ruiz Molledo and Sierra Garcia35], adaptive ACO [Reference Lin36], GA based on the Bessel curve [Reference Gad37], and PSO based on the smoothing principle [Reference Qiao, Fu and Yuan38], have been developed to solve difficulties in static path planning. A method integrating a logarithmic decline strategy with Cauchy perturbation, drawing on a bat method [Reference Durst, Jia and Li39], a combination of whale optimization approach [Reference Yuan, Yuan and Wang40] and differential evolution for vehicle routing [Reference Si and Li41], an enhanced artificial fish swarm approach with continuous segmented Bessel curve for mobile robot trajectory planning [Reference Jiang, Yuan and Cheng42], and optimization of chemical processes for global route planning [Reference Dai and Kuh43] are a few examples of the new solutions to global path planning issues that have been made possible by the continuous evolution of AI optimization algorithms. Additionally, in order to circumvent the constraints that are associated with single-approach systems, hybrid path planning approaches have been investigated [Reference Korayem, Nosoudi, Khazaei Far and Hoshiar44]. Two different static approaches are combined in these methods. Examples include a hybrid Dijkstra-BFS algorithm to enhance processing efficiency and path accuracy [Reference Bhargava, Suhaib and Singholi45], a hybrid A*-ACO method to reduce running time and improve the planning of paths in complex environments [Reference Abi, Benhala and Bouyghf46], Dijkstra-ACO that optimizes the route using ACO after initial path planning [Reference Nie and Zhao47], D*-GWO demonstrating its practicality and effectiveness [Reference Shial, Sahoo and Panigrahi48], and ACPSO that combines PSO with the A* algorithm’s heuristic function [Reference Shami, El-Saleh, Alswaitti, Al-Tashi, Summakieh and Mirjalili49, Reference Shami, El-Saleh and Kareem50]. While a single A* processing is quick but produces a lot of pivot points, extra nodes, and erroneous paths, a single PSO’s path search is precise but struggles with population initialization in complex environments [Reference Chen, Zhao, Fan and Liu51]. Most of the previous emphasis has been concentrated on enhancing the path smoothness and heuristic function of A* in static circumstances; there have been very few attempts to simultaneously enhance A* and PSO. The comparative performance of the algorithms found in literature review is as follows (Table I):
Several hybrid approaches have been proposed, some of which are as follows Dijkstra-BFS, A*-ACO, and Dijkstra-ACO hybrid techniques are examples; however, these approaches primarily address specific constraints of individual algorithms instead of offering a comprehensive solution that tackles multiple issues simultaneously. These innovations have not been properly integrated with heuristic approaches in order to make use of their combined strengths, despite the fact that several research have proposed improvements to PSO and ACO, such as adaptive ACO and PSO with smoothing principles. A lack of uniformity is frequently observed in the evaluation of algorithms, with different measurements and experimental setups being utilized. Because of this inconsistency, it is difficult to arrive at conclusive results regarding the effectiveness of various treatments [Reference Guan and Wang52]. PSO is known for its sensitivity to initial population settings. Although there has been a lot of research on individual improvements to heuristic algorithms like A*, Dijkstra, and RRT, as well as AI optimization techniques like PSO and ACO, there aren’t the comprehensive solutions that successfully combine the advantages of these methods to address multiple constraints at once. Dijkstra-BFS, A*-ACO, and Dijkstra-ACO hybrid algorithms optimize processing speed and path correctness but often focus on technique restrictions [Reference Cao, Yang, Yu and Zhang53].
Hybrid methods increase efficiency in challenging circumstances by solving multiple problems at once while offering a broader response. Robust, effective, and adaptive algorithms to handle AGVs' many real-world challenges are lacking. The limitations of this demonstrate the need for additional study and improvement in path planning for AGVs. These domains mostly concern the development of algorithms that are more dependable, efficient, and flexible. The Hybrid Modified A* (HMA*) algorithm, which combines Modified A* with PSO, was created in response to this situation. The Modified A* algorithm first establishes the initial path, from which duplicate point elimination is used to remove essential nodes. The best global path is subsequently identified by PSO, which is seeded with these significant nodes and mixes a random opposition-based method of learning with a random inertia weight. AGV path planning models are used to assess a method with a more expansive goal function. Its unique features are below:
-
• The Hybrid Modified A* method improves multiple constraints by combining MA* heuristics with Particle swarm optimization.
-
• The algorithm’s dynamic heuristic enhances path planning precision by adjusting to changing environmental conditions and PSO findings. The Hybrid Modified A* uses PSO to optimize the initial population, that is, minimizing the dependence on initial population decisions.
-
• In hybrid technique, the PSO’s multi-objective capabilities optimize path length, smoothness, and obstacle avoidance simultaneously. The system responds to environmental changes, constructing it ideal for instantaneous applications with unexpected challenges.
-
• The hybrid approach finds optimal or near-optimal routes faster than either alone by MA* and PSO. The suggested approach is flexible for multiple uses as it operates under various AGV types and operating circumstances.
3. Locomotion of the AGV
AGVs with four Mecanum wheels are agile and can go anywhere. Each roller on a Mecanum wheel is 45 degrees; thus, the AGV can go sideways, diagonally, forward, and backward without moving orientation. Mecanum wheel AGVs are ideal for flexible, accurate industrial applications since they can negotiate confined spaces and complex situations. By managing each wheel’s speed and direction, the AGV can conduct precise actions, including spinning on the spot, improving its operational efficiency in multiple settings [Reference Bhargava, Singholi and Suhaib54].
As shown in Figure 1, four-wheel omnidirectional AGV is made up of four Mecanum wheels. The following is the nomenclature of symbols used, ψ is the constant slope angle of the rollers, Or is the moveable AGV coordinate framework, Oq is an abbreviation for fixed coordinating framework, Owi is the wheel coordinating framework, Pwi is the wheel position vector in Owi [Reference Bhargava, Singholi and Suhaib54].
The rollers around the edges of these wheels are tilted at a constant angle. For this case, the angle ψ is 45 degrees, which means that the wheel can move easily at an angle of 45 degrees with the motion that is pushing it. Each wheel has a permanent magnet direct current motor connected to it. This motor provides the torque that the AGV needs to move. It is now considered that the AGV is moving across a level, uniformly distributed surface. To discover the equation of motion, it is presumed that each component of the AGV, including the wheels, is rigid. We make use of the Or and Oq coordinate frames within the framework of the kinematic modeling scenario as in ref. [Reference Bhargava, Singholi and Suhaib54, Reference Bhargava, Singholi and Suhaib65].
There is a wheel coordinate frame denoted by Owi (where i = 1 to 4). Pwi is the wheel’s position vector in Owi as in ref. [Reference Li, Gu, Li, Li, Guo, Gao, Zhao, Yang, Li and Dong55]:
$\dot{\theta}_{ix}$ (where i = 1 to 4) shows how fast the wheel is turning around the hub, $\dot{\theta}_{ir}$ (where i = 1 to 4) represent the roller angular velocity, and $\dot{\theta}_{iz}$ (where i = 1 to 4) represents the wheel angular velocity around the contact point where it is located. Ri (where i = 1 to 4) represents the radius of the wheel, ψi (where i = 1 to 4) is the angle of the roller slope for each wheel, and a roller’s radius is denoted by the letter r. This is how we can write the AGV’s motion vector as in ref. [Reference Li, Gu, Li, Li, Guo, Gao, Zhao, Yang, Li and Dong55]:
Let
In the given equation, the rotating angle of Owi concerning Or is denoted by $\phi _{\textrm{wi}}^{\textrm{r}}$ (where i = 1 to 4). In addition, the distance in radians between two coordinate frames is shown by $\textrm{d}_{\textrm{wix}}^{\textrm{r}}$ and $\textrm{d}_{\textrm{wiy}}^{\textrm{r}}$ .
Let us say that the equation for the AGV’s position vector in Or is Pr = [xr yr φr]T, then the relationship between Pr and Pwi may be expressed as Pr = $\textrm{T}_{\textrm{wi}}^{\textrm{r}}$ .Pwi. Furthermore, it is evident from Figure 1 that the value of $\phi _{\textrm{w}1}^{\textrm{r}} = \phi _{\textrm{w}2}^{\textrm{r}}=\phi _{\textrm{w}3}^{\textrm{r}}=\phi _{\textrm{w}4}^{\textrm{r}}=0$ . Consequently, the AGV’s velocity vector may be stated as [Reference Bhargava, Singholi and Suhaib65]:
From (3b) and (3d) we get,
where
$\textbf{J} _{\textbf{i}}$ is the Jacobian matrix of the ith wheel and
Remark 1: |Ji|=0 and ψi = 0
Consequently, Mecanum wheels do not exhibit any signs of singularity.
Remark 2: rank(Ji) = 3
Therefore, there are three degrees of freedom associated with each wheel.
As each of the four wheels is the same, the following equations are used to figure out its geometric and kinematic properties:
R1 = R2 = R3 = R4 = R and,
$\textrm{d}_{\textrm{w}1\textrm{x}}^{\textrm{r}}=a;\ \textrm{d}_{\textrm{w}1\textrm{y}}^{\textrm{r}}=b;\ \textrm{d}_{\textrm{w}2\textrm{x}}^{\textrm{r}}=-a;\ \textrm{d}_{\textrm{w}2\textrm{y}}^{\textrm{r}}=b;\ \textrm{d}_{\textrm{w}3\textrm{x}}^{\textrm{r}}=-a;\ \textrm{d}_{\textrm{w}3\textrm{y}}^{\textrm{r}}=-b;\ \textrm{d}_{\textrm{w}4\textrm{x}}^{\textrm{r}}=a;\ \textrm{d}_{\textrm{w}4\textrm{y}}^{\textrm{r}}=-b$
Regarding this, the Jacobian matrix for each wheel can be found as follows:
The solution to the inverse kinematics problem can be obtained by using equations (3e) and (3f) as in ref. [Reference Chen, Zhang, Wang and Xia56].
where $\dot{\theta}_{i} $ (where i = 1 to 4) is the angular velocity of each wheel.
Remark 3: It is possible for the AGV to follow any desired trajectory even if the value of $\phi$ r is equal to zero. This is something that can be observed from the kinematic solution that has been constructed. As an illustration, the AGV need not alter its orientation if it follows a curved path, one of the primary justifications for its usage in cramped spaces. Within the global coordinate system Oq, the velocity vector may be expressed as follows since position and rotation are closed-loop feedback [Reference Bhargava, Singholi and Suhaib54]:
where
is the rotation matrix of Or with regard to Oq.
The above equations are essential for finding out the wheel velocities and the needed revolutions per minute (rpm) necessary for a mecanum wheel AGV in order to accomplish the required linear and angular motions in various environments for real-time obstacle avoidance and path planning. The next section discusses about the algorithms that are implemented on the AGV for its control in static and dynamic environments.
4. Modified A* and PSO evolutionary algorithms
By the implementation of Modified A*, the conventional A* algorithm, which is frequently used in the process of path finding and network travel, is enhanced. In contrast to A*, which finds the shortest path by calculating the expense of traveling from one location to another using a heuristic, MA* usually performs modifications for the intention of improving the computational effectiveness, accuracy, or flexibility of the system in surroundings that are complex and dynamic [Reference Li, Gu, Li, Li, Guo, Gao, Zhao, Yang, Li and Dong55].These changes might include the following:
Dynamic re-planning: Altering current routes to take account of new circumstances or impediments. Heuristic improvement is a method of adjusting the heuristic function to the specific issue in order to incorporate discovery and extraction in an appropriate manner.
Integration of hybrid systems: To overcome its limitations in extremely dynamic or unpredictable environments, MA* is sometimes used in conjunction with other optimization techniques such as PSO.
PSO is an algorithm for evolution that draws influence from the way groups of animals, such as fish or birds, behave together. A population, or swarm, of particles looks for the most suitable solution in PSO by traveling over the correct space [Reference Cao and Zhu34]. Every particle modifies its place of existence according to two criteria.
-
• Personal best (pBest): A fundamental idea in PSO, pBest, or personal best, is the finest location that a single particle possesses thus far while moving across the solution space. When moving, the particle assesses the objective function at its current position. For that particle, the current position becomes the new pBest if it provides a better objective value than the previous position.
-
• Global best (gBest):The best position or solution that each particle in the swarm discovered after all iterations is often referred as gBest. The gBest place is one that behaves the greatest among all the particle locations at every iteration, determined using an objective function.
4.1. The modified–A* (MA*) algorithm
The MA* algorithm merges the Dijkstra algorithm with Breadth-First Search (BFS), combining Dijkstra’s heuristic global search with BFS’s systematic approach [Reference Zhang, Li, Ren and Ren57]. This fusion is known for its robustness and effectiveness in AGV path planning. The algorithm commences at the initial node and evaluates its child nodes, processing them in turn. It continues this process until the target node is found and added to the OpenList. The next node to process is chosen based on the lowest A(n) value, using the function formula to estimate costs as in ref. [Reference Pak, Kong and Ri58].
In the MA* algorithm, the estimated total cost A(n) for achieving the target from the start to the current position is divided into two parts, that is B(n), the real cost, and C(n), the heuristic estimate [Reference Pak, Kong and Ri58]. Manhattan distance, which aggregates absolute coordinate differences, or the distance from Euclid, the distance in a straight line, can be used by C(n). The heuristic chosen is Euclidean distance, in this study because of its accuracy, and the algorithm uses an eight-way search on a raster map with obstacles [Reference Liu, Wang, Zhang and Liu59].
Here, yn and zn are the current node’s abscissa and ordinate, respectively, and ys and zs are for the source or starting nodes. The target node’s abscissa and ordinate are yt and zt (Figure 2).
Two sets are created from all extended nodes by the MA* algorithm:
-
• OpenList: There are nodes in the OpenList that have been found but not thoroughly investigated. The algorithm selects the node having less overall estimated cost among these nodes, which are candidates for expansion.
-
• CloseList: Nodes that have previously been processed are stored in the CloseList to avoid having to be revisited. This eliminates the requirement for repeated calculations and improves search times by avoiding needless node expansion.
-
• Together, the OpenList and CloseList allow the MA* algorithm to effectively achieve its objective through enabling it to systematically examine the most probable paths, removing recurrent checks and loops.
The MA* algorithm has many advantages like faster path finding, efficient handling of dynamic environments, reduced computational complexity, improved memory utilization, better scalability, more accurate heuristics, handling of multiple objectives, and smoother path generation as compared to traditional A* algorithm. Below is the compression between A* and MA* algorithm.
The A* algorithm, tested using MATLAB 2023 on an Intel i7 workstation, demonstrates the following results on 10 x 10, 20 x 20, and 30 x 30 grid maps (Figure 3).
The workflow of the MA* algorithm is shown in Figure 4. The Modified A* (MA*) algorithm, tested using MATLAB 2023 on an Intel i7 workstation, demonstrates superior efficiency compared to the traditional one. Tested on 10 x 10, 20x 20, and 30 x 30 grid maps, the MA* algorithm decreases the number of nodes searched, minimizes turn points, and shortens computation time, as shown in Table II. While the overall path length reduces as compared to A*, MA* excels in optimizing route smoothness and driving performance, especially as map size increases [Reference Liu, Feng, Zhou and Yang60] (Figure 5).
4.2. Particle swarm optimization (PSO) algorithms
From bird feeding data, Kennedy and Eberhart created Particle Swarm Optimization (PSO) [Reference Jingjing, Xun, Wenzhe, Xin and Dong61]. A cluster of randomly initialized particles indicating potential fixes searches for the ideal solution in a multidimensional space in PSO. The simplicity and fast convergence of PSO make it popular in flow shop scheduling, medical picture classification, nonlinear power system optimization, and AGV path planning [Reference Jingjing, Xun, Wenzhe, Xin and Dong61, Reference Demir and Demirok62].
The PSO method iteratively refines particle positions and velocities to obtain the optimal solution by evaluating Gbest and Pbest. As an example, the following equation shows how its position and speed are updated [Reference Demir and Demirok62]:
An increase in the potential for self-learning factor denoted by c1 of a bird increases the bird’s incentive to arrive in its most advantageous spot, where ω represents inertia, that is indicates the amount of weight that is carried by flying to its ideal place [Reference Demir and Demirok62]. $\textrm{v}_{\textrm{i}}^{\textrm{j}+1}$ indicates the i-th particle’s total process velocity in the (j + 1)th iteration. A bird is more likely to fly to the group’s optimum position if its social learning factor, or c2, is high. Here, r1 and r2 are uniformly distributed random values, and $\text{pbest}_{\textrm{i}}^{\textrm{j}}$ is the particle’s optimal solution identified in the i-th search after j iterations. After the jth iteration, Gbestj is the optimal solution. The symbol $\textrm{x}_{\textrm{i}}^{\textrm{j}}$ positions the i-th particle after j repetitions [Reference Ding, Zheng, Liu, Guo and Guo63]. The Workflow of the PSO algorithm is shown below with Matlab 2023 simulation result (Figures 6 and 7).
5. Implementing the Hybrid Modified A* algorithm
The Hybrid Modified A* (HMA*) method combines PSO and modified A* (MA*) to improve path finding. The method of “particle swarm optimization,” or “PSO,” optimizes populations by modifying particle placements and speeds. This technique also considers fish and avian behavior [Reference Khan, Khatoon and Gaur64]. By using MA*’s ordered search and PSO’s optimization, HMA* can find network routes efficiently and effectively while improving path quality. HMA* improves the path planning and navigation for automated guided vehicle. Dynamic heuristics adapt to environmental changes, enhancing accuracy of the system [Reference Khan, Khatoon and Gaur64]. HMA* changes paths in real time for best routing accuracy and smoother navigation in congested areas, unlike PRM, which employs pre-computed maps [Reference S. and R.12]. HMA* provides high-performance obstacle avoidance, and post-processing enables stable paths [Reference Bhargava, Singholi and Suhaib65]. Lowering search space and processing time improves HMA*’s scalability and computational efficiency, making it suited for complex, dynamic AGVs.
5.1. Steps of algorithm
Step 1: The raster method creates the raster map and initiates the MA* method’s parameters.
Step 2: Make two void sets, designated as closeList and openList. The nodes that have been investigated are included in a closeList, whilst the nodes that have not yet been explored are included in an openList.
After the first node has been incorporated into openList, the current node will be demolished if it is on a path that includes both the previous and next nodes in the current node’s sequence, indicating that the node is redundant. For example, node A will be eliminated if it is collinear with node S, the node before it, and node B, the node after it. The redundant path node’s judging process can be written as in ref. [Reference Liu, Wang, Zhang and Liu59]:
For the current node n, the abscissa and ordinate are represented by y n and z n , respectively. On the other hand, y n−1 and z n−1 are meant to represent the node n −1, and similarly, yn + 1 and zn + 1 are for node n + 1. If $\textrm{J}_{1}$ is equals to $\textrm{J}_{2}$ , the present node is redundant and co-linear with both the nodes that came before it and the nodes that will come after it.. If J1 is not equal to J2, then the present node is not redundant and does not have any co-linearity with the nodes that came before or after it.
Step 3: Determine which node in openList has the lowest f(n) value, and then transform that node as an active node. When evaluating duplicated transition nodes, the implicit function listed below is employed as in ref. [Reference Liu, Wang, Zhang and Liu59]:
Here, yobs and zobs represent each obstacle’s abscissa and ordinate and robs is the obstacle area radius following expansion. There are barriers between the two turning sites when path = obs; in opposite case, that is when path ≠ obs, the intermediate turning locations are superfluous or redundant because there are no obstacles between them.
Step 4: Remove the current node “n” and add it to closeList rather than openList.
Step 5: The goal is to determine whether or not the node “n” to be targeted. In the event that it is the node of interest, the current node identified as `n' should be used as the source node in order to scan the eight neighbors.
Step 6: It is necessary to ascertain which of the eight nearby neighbors of the points of node “n” are included in list, if they are not obstacles. If this is the case, figure out each node’s f(n) value, choose whatever node has the lowest value of f(n) to be the upcoming node n + 1, and then go back to step number four. Add it to openList and compute f(n) if it is not in openList.
Step 7: The redundant node removal technique is utilized to eliminate the points that were present in the initial path, that is, remove path nodes and transition points that are redundant in nature.
Step 8: When traveling through the remaining nodes in the route points set or path-points set , each PSO optimization iteration should start and terminate at the separated nodes n and n + 2.
Step 9: One must provide the population no. (possize), the maximum no. of repetitions (Tmax), the factor based on self-learning (c1), the factor based on social learning (c2), the inertia weights correlation coefficients ( $\omega$ max and $\omega$ min), and the iteration to establish the PSO parameters. In order to enhance the PSO algorithm’s performance, the adaptive inertia weight [Reference Sandoval-Castro, Muñoz-Gonzalez, Garcia-Murillo, Ferrusca-Monroy and Ruiz-Torres66] is frequently employed.
where ω min is the minimum inertia weight; ω max is the maximum inertia weight, the ideal fitness (global) at the jth iteration is denoted by pj gbest , the ideal fitness (global) at the j-1th iteration is denoted by pj −1 gbest and Tmax represents the highest possible quantity of possible iteration.
The algorithm can quickly depart from the optimal local solution by changing the inertia weight to a random number with a predetermined range. The algorithm’s search is improved as a result of these efforts, which also preserve the population’s diversity. It is for this reason that this research suggests a stochastic inertia weight by employing the following equation, which is derived from the linear declining inertia weight as in ref. [Reference Sandoval-Castro, Muñoz-Gonzalez, Garcia-Murillo, Ferrusca-Monroy and Ruiz-Torres66].
ρ is a number that can be chosen at random and falls anywhere between −0.1 and 0.1.
Step 10: In order to produce a new historical ideal population, every element of the group undergoes disruption to the individual ideal gbest as well as the individual ideal pbest, respectively. This is done in order to build an entirely novel population. The new population is supposed to be increased as the main objective. The random technique, which can be expressed as follows, is used to first randomly generate the initial particles with a particular population size as in [Reference Chen, Cheng, Zhang, Wu, Liu and Men67].
Here, the random particle coordinates are presented by posy and posz, respectively, and the node coordinates are represented by y n and z n , respectively.
The y and z coordinates of nodes that are divided from node n are denoted by the symbols y n+2 and z n+2, respectively. A random number that falls somewhere between 0 and 1 is denoted by the symbol $r_{\textrm{o}}$ . After the population has been initialized, a random approach is utilized to initialize the velocity of each individual particle once more as in ref. [Reference Wang, Li, Yang, Hu and Zhao68]. This can be represented as follows:
Here, vmax represents the maximum speed, and the velocities of each particle on the abscissa and ordinate coordinates are represented by vy and vz respectively.
Each particle’s fitness is computed following the initialization of the population and population velocity. The particles that doesn’t avoid barriers have a fitness value of zero, whereas the other particles lacking it are the individual optimum solution pbest. The most advantageous group solution, denoted by letter gbest, is found to be the particle that has the greatest efficiency or highest fitness. The fitness calculation is as follows [Reference Chen, Cheng, Zhang, Wu, Liu and Men67, Reference Wang, Li, Yang, Hu and Zhao68]:
where f, k, and c denote the fitness value of particle, particle path distance, and collision test function respectively; zm and ym denote ordinate and abscissa of the node m. The ordinate and abscissa of node m’s adjacent nodes are denoted by zm + 1 and ym + 1. The fact that the value of m equals one indicates that the node m is the launching node of the local route is indicated by this value. On the other hand, when m equals n, it signifies that m is the node that serves as the aim or target of the local path [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69].
Step 11: The fitness values of the global ideal, denoted by `gbest’, and the individual ideal, denoted by `pbest' should be compared to the fitness value determined for the opposite position [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69]. In the event that the particle’s fitness value is sufficiently high at the opposite position, it will be moved to its original location. If that not be the case, it will not be transferred.
Step 12: Find out if the maximum quantity of repetitions, Tmax, has been reached; if it has not, return to the eleventh step and terminate the iteration while preserving the local optimization route.
Step 13: Check to see if the destination node is included in the iteration; if it is, the process should be terminated and the total path, which is the sum of the local pathways, should be reported. If not, proceed to step eight once more (Figures 8, 9 and 10).
5.2. Problem modeling
Path planning must reduce AGV runtime. Most path planning algorithm research measures path length. AGV running time depends on path length, turning radius, path planning method, computation time, and path nodes. Therefore, these variables are in the following objective functions.
-
A. Objective function for minimizing path length
Path length directly impacts AGV’s linear travel time; hence, the path design method aims to minimize it. Therefore, the goal function should prioritize path length that must be the shortest. The objective function of shortest length of the path is given as in ref. [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69]:
Here, n is the nodes in total number, while yi and zi are node i’s abscissa and ordinate and yi + 1 and zi + 1 for node i + 1.
-
B. Objective function for the shortest Path node
The AGV must choose its next move at each node. Decision-making frequency increases with node count, limiting AGV motion fluency. The objective function should reduce path nodes to handle this. The formula for this function is given as in ref. [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69]:
-
C. Objective function for the shortest Turning amplitude
The AGV’s motion stability, path smoothness, and overall travel time are directly influenced by the amplitude of its turns. Smaller turning amplitudes lead to greater stability, smoother paths, and shorter travel durations. Consequently, the AGV’s objective function should be designed to minimize the turning amplitude [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69]. The corresponding formula is as follows:
(n = nth node in the path.)
-
D. Objective function for minimizing operating time
Vehicle efficiency depends on AGV path planning algorithm execution time, which influences operational effectiveness. Thus, the objective function should minimize algorithm operation time. This objective function formula is given as in [Reference Liu, Wang and Yang71]:
where Rt is the algorithm running time.
The goal-oriented functions are able to influence the execution time of the AGV in either a direct or indirect manner without causing any conflicts. We may integrate these objective functions into a single, complete objective function that minimizes AGV running time [Reference Weidong, Xianlin, Xiao-Zhi and Hongjun69, Reference Raptis, Hansen and Sinclair70]. Presenting the combined objective function:
where vL denotes the AGV’s linear speed of motion. In this work, vL = 1 m/s. When the AGV arrives at a node, to stands for the amount of time it needs to make a decision. This paper uses to = 0.1 s. The AGV’s turning speed, or the amount of time it takes to turn one radian, is represented by vs. This paper uses π rad/s for vs.
6. Experiment of path planning simulation
To prove that the Hybrid Modified A* algorithm is a good way to plan routes for AGVs, experiment will utilize it. To do this, it will be necessary to evaluate the Hybrid Modified A* algorithm in conjunction with A*, PRM, RRT, and Bi-RRT. Researchers discovered that even when faced with substantial challenges depicted on the environment map, the hybrid intelligent optimization technique autonomously produced a path that maximized efficiency [Reference Liu, Wang and Yang71].
6.1. Description of the problem
In addition to its other functions, the intelligent warehouse also serves as the environment for path planning. Despite obstacles, the automated guided vehicle (AGV) continues to navigate towards completing its tasks [Reference Liu, Wang and Yang71]. When it comes to the process of planning a path, it is of the utmost importance to determine the smallest possible length of the path and to reduce the overall rotating radius [Reference Gao, Li, Liu, Ge and Song72]. In order to generate the environment map, the following assumptions were taken into consideration:
-
1. There are fixed, predefined areas wherein obstructions will be detected.
-
2. The AGV operates at a constant rate.
-
3. Because the environment map only appears in two dimensions, it is feasible to ignore the AGVs and barriers height information.
6.2. Composition of models
Raster, visible, and topological diagrams are frequently employed for environment modeling in path planning. This study builds an environment map model using a raster technique. The workspace where the AGV is tested is represented by a 20 x 20 decimeter (or 200 × 200 cm) two-dimensional raster map. The raster-based environment map models that were employed for assessment are shown in Figure 11. The percentage of environment maps with obstacles covered is 25% on map 1, 30% on map 2, 35% on map 3, 40% on map 4, 45% on map 5, and 20% on map 6. On these maps, physical barriers are shown in blue, and derivable areas are shown in white. For the AGV to operate correctly, the starting and target nodes should be (1,1) and (20,20), respectively. The most crucial element in determining the path planning algorithm’s evaluation is path length. AGV runtime is influenced by path length, node count, turning amplitude, and algorithm planning time. Linear transit time is impacted by path planning, which shortens AGV paths [Reference Tolossa, Gunasekaran, Halder, Verma, Parswal, Jorwal, Maria Joseph and Hote13]. Number of nodes that are located along the path affects AGV’s decision-making time and motion fluency, which in turn affects how quickly it moves in the direction of its destination. Turn amplitude affects AGV smoothness, motion stability, and travel time; smoother, more stable, and faster motion times are achieved with smaller turning amplitudes (Figure 11).
7. Simulation and real-time experiments
Setting up the conditions for obstacle environment simulations includes setting limits, goals, and rules. The following step is to select effective routing and obstacle avoidance algorithms. The chosen method is optimized for higher efficiency by a series of testing and data-gathering steps pertaining to path length, finish time, and rate of success [Reference Tolossa, Gunasekaran, Halder, Verma, Parswal, Jorwal, Maria Joseph and Hote13, Reference Liu, Jiang, Zhao and Mei73]. This systematic technique helps the design and evaluation of obstacle simulations by assisting robotics and navigation analysis. Mecanum wheel AGV navigation is tested in simulations to make sure algorithms and strategies work in actual situations. The following describes the various parts and process.
For the purpose of evaluating navigation algorithms, the virtual setting of an AGV is replicated in either two or three dimensions, including walls and barriers. The size, form, and position of sensors of an AGV must be incorporated into a precise model so as to offer realistic simulations that’s particularly true for mecanum wheels. The evaluation and control of AGVs is accomplished through the modeling of navigating, routing, and avoiding obstacles algorithms in Matlab (R2023a) and ROS environment specially for dynamic obstacle avoidance [Reference Bhargava, Singholi and Suhaib65]. The evaluation regarding the trajectory of the AGV, the amount of crashes, the length of the route, and the duration of execution are employed to determine performance. A comparison of algorithms provides data on their advantages, disadvantages, and ways of improvement. Improvements in the speed and navigational efficiency of automated guided vehicles (AGVs) may have achieved via recurring simulations, updated analysis-based programs, and enriched the situations.
Table III to Table VIII show the functional values of simulation and real-time experimental data from Map 1 to Map 6; comparison of the percentage deviation in the experimental path length and simulation path length is presented in Table IX; comparison of the percentage deviation in experimental motion time and simulation motion time is presented in Table X; comparison of the percentage difference or enhancement in experimental path length and experimental motion time between HMA* and other algorithms is presented in Table XII and Table XIII respectively (Figures 12–23).
8. Experimental validation
Mecanum wheels allow omnidirectional movement in automated guided vehicles (AGVs) by using inclined rollers to enable movement in any direction without rotation. This capability, unlike traditional wheels that require steering, allows AGVs to move sideways, diagonally, or rotate in place, offering exceptional maneuverability in tight spaces. To fully leverage this, advanced algorithms for path planning, navigation, localization, and collision avoidance are essential. Path planning must account for dynamic limits such as maximum speed and acceleration, while navigation and control algorithms must optimize trajectory planning for smooth and precise movement. Localization algorithms need to incorporate the AGV’s motion model and sensors, like odometry and wheel encoders, for accurate positioning. Collision avoidance algorithms must ensure safe navigation by considering the AGV’s unique movement capabilities (Figures 24, 25, 26, 27 and 28).
The Hybrid Modified A* (HMA*) approach-based AGV control in random environment, as shown in Figure 29, combines the optimization powers of PSO with the heuristic search efficiency of MA*. In this way, HMA* is able to analyze intricate settings. The AGV is equipped with two lidar sensors to detect obstacles and measure distance accurately, as well as two vision sensors to improve its ability to perceive its surroundings and identify objects. The CPU is a Jetson Nano, that performs complex calculations for the Hybrid Modified A* method, sensor data fusion, as well as making decisions. The mecanum wheels travel effortlessly and precisely because of an STM32 motor controller, which provides precise motor control. To further improve avoiding obstacles and safety in difficult circumstances, six ultrasonic sensors are set all around the AGV to provide additional detection of proximity abilities. For the framework to work, the connections among the sensors and the Jetson Nano controller are crucial. The interfaces between the lidar sensors and the Jetson Nano enable real-time distance measurement processing and high-speed information transmission. The vision sensors are connected by CSI (Camera Serial Interface) ports, which enable the Jetson Nano to receive high-definition video feeds for object detection and environmental mapping. The Jetson Nano’s GPIO (General-Purpose Input/Output) links can be used to connect the ultrasonic sensors to transmit proximity data, that is needed to detect obstructions in close proximity. Precise motor controls and feedback have been rendered feasible by the UART (Universal Asynchronous Receiver-Transmitter) connection that connects the STM32 motor control module to the Jetson Nano. With this sophisticated configuration, which guarantees precise navigation, localization, and collision avoidance in a variety of experimental circumstances, the AGV’s omnidirectional capabilities may be fully utilized [Reference Nguyen74]. The main block diagram of the hardware arrangement is as follows (Figure 30):
A thorough description of the hardware setup of the AGV to be found in Table XIV. After implementing the HMA* algorithm into the AGV to evaluate its effectiveness the real-time experiment is performed with the following procedures:
-
1. Create a map illustrating the surroundings. Figure 31(a) shows both the experimental area and the map constructed on the ROS platform.
-
2. Identify a desired initial position and target location on the map.
Place arbitrary obstacles along the planned path of the AGV and observe whether the AGV can successfully navigate these random obstacles. This procedure verifies that the HMA* algorithm works as intended when faced with unforeseen obstacles.
The AGV begins global path planning for traveling from its current initial position to the target location, as shown in Figure 31(b). It travels along the route that has been planned globally, moving through tight spaces with ease. The AGV uses sensor data to determine the first random barrier, avoids it, and then re-enters the global path to keep moving in the direction of the goal. As seen in Figure 31(c), the AGV uses sensors to detect and maneuver through new obstacles as it moves, finally arriving at the designated target location. The navigational area is 500 cm by 150 cm in size. Due to the HMA* algorithm, the automated guided vehicle (AGV) successfully traversed a 548 cm course in 55 s, avoiding every obstacle and proving its effectiveness in a matter of seconds. The experimental findings show that when the Modified A* and PSO (HMA*) path optimization methods are combined, the AGV can travel through restricted areas effectively. The AGV is able to avoid random obstacles and plan globally the best paths because of this method. The relationship between linear and angular velocities and different obstacle configurations is also investigated in this study. The surroundings with one obstacle are depicted in Figure 32(a), which shows the changes in angular and linear velocities as the AGV approach and avoids the obstacle. The two-obstacle environment shown in Figure 32(b) illustrates how velocities change when the AGV maneuvers around both obstacles. Lastly, an environment with three obstacles is shown in Figure 32(c), where the graphs illustrate the greatest changes in the AGV’s velocities as it navigates around the obstacles.
9. Conclusion
This study shows how a Hybrid Modified A* (HMA*) method can find AGV’s collision-free shortest path quickly. As seen in Figures 12–23, the different algorithms adopt different paths to reach their goals. In each map, various algorithms are applied to determine the optimal path. The HMA* algorithm consistently produces smoother pathways across the six maps because the routes it selects are generally shorter, have fewer path nodes, and involve fewer turns. This efficiency is primarily due to the algorithm’s ability to identify more direct routes. The tables accompanying the maps offer a clear comparison of the algorithm’s success in achieving efficient path planning. The HMA* algorithm can avoid static and random obstacles for AGVs as shown in Figure 31. It also adjusts local pathways and provides collision-free navigation in complex settings. The hybrid algorithm can avoid random obstacles, alter local pathways, and navigates in complex environments without colliding and quickly reaching the objective.
-
• The HMA* algorithm outperforms A*, PRM, RRT, and Bi-RRT in average path length by 12.08%, 10.26%, 7.82%, and 4.69%, respectively, across six maps. Additionally, HMA* demonstrates superior performance in average motion time, achieving improvements of 21.88%, 14.84%, 12.62%, and 8.23% over the same algorithms as shown in Table XII and Table XIII.
-
• The HMA* algorithm shows promising results with an average deviation of 4.34% in path length and 3% in motion time between simulation and experiments as shown in Table IX and Table X, demonstrating a close approximation to real-world conditions.
-
• The HMA* method effectively avoids collisions in situations with static and random barriers (Figure 31). Its dynamic local path adjustment ensures reliable navigation in complicated and uncertain environments. Real-world AGVs must be adaptable to quickly changing environmental conditions.
-
• The HMA* algorithm’s collision-free and fast navigation under various conditions makes it practical and versatile for industrial and logistical applications.
-
• Further research may examine to improve the HMA* algorithm’s ability to recognize and avoid obstacles in real-time at extremely dynamic situations by integration of sophisticated sensor fusion methodologies.
Anyone can download the codes and videos created for this purpose by visiting this link: https://github.com/ankurgsb21/Hybrid-Modified-A-star-Algorithm-Modified-A-star-PSO-
Author Contributions
Under the guidance of Prof. (Dr.) Mohd. Suhaib and Prof. (Dr.) Ajay K.S. Singholi, Ankur Bhargava was responsible for the study’s conception, design, data collection, methodology, visualization, and investigation. Prof. Mohd. Suhaib and Prof. Ajay K. S. Singholi provide assistance with writing, reviewing, editing, and statistical analysis.
Financial Support
This research received no specific grant from any funding agency, commercial or not-for-profit sectors.
Competing interests
The authors declare no competing interests exist.
Ethical Approval
Not applicable.