Next Article in Journal
Parametric Optimization Study of Novel Winglets for Transonic Aircraft Wings
Previous Article in Journal
Channel Characteristics of Hybrid Power Line Communication and Visible Light Communication Based on Distinct Optical Beam Configurations for 6G IoT Network
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Method of Dual-AGV-Ganged Path Planning Based on the Genetic Algorithm

College of Mechanical and Energy Engineering, Beijing University of Technology, Beijing 100124, China
*
Author to whom correspondence should be addressed.
Submission received: 22 July 2024 / Revised: 18 August 2024 / Accepted: 22 August 2024 / Published: 23 August 2024

Abstract

:
The genetic algorithm (GA) is a metaheuristic inspired by the process of natural selection, and it is known for its iterative optimization capabilities in both constrained and unconstrained environments. In this paper, a novel method for GA-based dual-automatic guided vehicle (AGV)-ganged path planning is proposed to address the problem of frequent steering collisions in dual-AGV-ganged autonomous navigation. This method successfully plans global paths that are safe, collision-free, and efficient for both leader and follower AGVs. Firstly, a new ganged turning cost function was introduced based on the safe turning radius of dual-AGV-ganged systems to effectively search for selectable safe paths. Then, a dual-AGV-ganged fitness function was designed that incorporates the pose information of starting and goal points to guide the GA toward iterative optimization for smooth, efficient, and safe movement of dual AGVs. Finally, to verify the feasibility and effectiveness of the proposed algorithm, simulation experiments were conducted, and its performance was compared with traditional genetic algorithms, Astra algorithms, and Dijkstra algorithms. The results show that the proposed algorithm effectively solves the problem of frequent steering collisions, significantly shortens the path length, and improves the smoothness and safety stability of the path. Moreover, the planned paths were validated in real environments, ensuring safe paths while making more efficient use of map resources. Compared to the Dijkstra algorithm, the path length was reduced by 30.1%, further confirming the effectiveness of the method. This provides crucial technical support for the safe autonomous navigation of dual-AGV-ganged systems.

1. Introduction

Under the impetus of the Internet of Things, Artificial Intelligence, and Industry 4.0, the manufacturing industry is rapidly moving toward intelligence and interconnection. However, in complex automated transportation scenarios, many requirements are difficult to meet due to the limitations of a single AGV. In contrast, dual-AGV systems are more efficient and versatile in transportation and application, and they are capable of performing complex tasks such as collaborative assembly and handling, making them an important development direction [1]. Compared to single AGVs, the navigation system of dual AGVs is more challenging and complex. In addition to ensuring the navigation accuracy of individual AGVs, it is also necessary to ensure the relative spatial pose accuracy of dual AGVs during motion to avoid collisions and other issues [2].
The AGV navigation system typically comprises three modules: information perception, path planning, and motion control. Among these, path planning acts as the bridge connecting information perception and motion control [3]. Its objective is to search for viable paths from the starting point to the goal point while circumventing obstacles [4]. Thus, realizing ganged transportation with dual AGVs hinges significantly on path-planning technology.
Common path-planning algorithms include traditional methods such as the A* algorithm (pronounced “A-star”), which is known for its completeness in graph traversal and pathfinding [5]; the artificial potential field method, which plans paths by simulating the repulsive force of obstacles and the attractive force of target points [6]; the rapidly-exploring random tree (RRT) algorithm, which is effective for efficient path searches in non-convex high-dimensional spaces [7]; and the Dijkstra algorithm, which finds the shortest path between nodes in a weighted graph [8]. In addition to these traditional methods, intelligent optimization algorithms have also been widely applied. These include the ant colony optimization (ACO) algorithm, which mimics the behavior of ants in finding the optimal path [9]; neural network approaches that use interconnected nodes or neurons to model the way the human brain processes data through machine learning [10]; the particle swarm optimization (PSO) algorithm, which iteratively improves candidate solutions [11]; and the GA, a metaheuristic inspired by natural selection for solving optimization problems [12]. Nevertheless, the current research has predominantly concentrated on path planning for single AGVs, with fewer studies focusing on dual-AGV-ganged path planning, which requires in-depth research.
In the path planning of dual-AGV-ganged systems, a critical issue is to ensure that the leader AGV can plan collision-free paths for both AGVs. This requires comprehensive consideration of the turning collisions and positional changes in the dual AGVs to avoid collisions during turning maneuvers. To address these challenges, Di Liang et al. [13] introduced the artificial potential field method to enhance the global optimization accuracy of ant colony algorithms, thereby identifying the optimal path for the leader AGV to guide the path planning of the follower AGV. Zhenhua Pan et al. [14] simulated the relationship between AGVs and obstacles, utilizing spring forces to adjust paths and achieve multi-AGV path planning. Wucheng Zhou et al. [15], based on the predicted distance between leader–follower AGVs and obstacles, planned paths for a leader AGV and adjusted formations to achieve obstacle avoidance. Yi Liu et al. [16] improved the evaluation function by obtaining the relative distances and angles between AGVs through mutual communication, resolving the multi-AGV path-planning problem. Alonso et al. [17] proposed a distributed rolling-time domain local-motion planner to avoid collisions with static and dynamic obstacles. Wang, Xu et al. [18] conducted online path planning for a leader AGV using the artificial potential field method and adjusted the linear and angular velocities of the follower AGV using sliding-mode control to meet obstacle avoidance requirements, offering diverse technical solutions for dual-AGV-ganged path planning. Kadir Aram et al. [19] utilized the A* algorithm to find the shortest path between the starting point and the destination. They used the instantaneous actual position of the leader AGV and the calculated coordinates of the target point as parameters to determine the optimal path. Gianni A. Di Caro et al. [20] combined Monte Carlo simulation and Bayesian optimization to guide the leader AGV in identifying sampling locations, integrating the ant colony algorithm to guide follower AGV path planning and to prevent collisions. Shiwei Lin et al. [21] employed the A* algorithm to plan paths for virtual leaders. They then utilized the Weight-Leader-Vicsek Model (WLVM) for multi-AGV path planning, guiding AGVs based on the current positions and angles of the virtual leaders. Jiawei Hu et al. [22] proposed a multi-AGV local path planner capable of traversing obstacles, suitable for scenarios where the relative distances and angles between AGVs can vary during path planning. Liwei Yang et al. [23] enhanced path search quality in ant colony algorithms by introducing pheromones for leader and follower ants, achieving collision-free path planning for multi-AGVs through formation transformations. Wenjie Lu et al. [24] effectively identified and defined unobstructed workspaces by constructing convex polygon trees (CPTs*) and incorporating a neural network-based rapid sampling method. This approach provided robust constraint conditions for path optimization and obstacle avoidance. Subsequently, they utilized these constraints, along with quadratic programming tools, to successfully solve the optimal path problem for multi-robot formations. This research not only demonstrates advanced path-planning techniques, but also provides significant theoretical guidance and practical application value for the path planning of dual AGVs. Sil Kwong Tse et al. [25] computed AGV paths and controls using consensus protocols, and these are suitable for dual-AGV system path planning with fewer obstacles.
However, most of the aforementioned studies do not sufficiently consider the poses of the starting and goal points. When encountering obstacles, they often use formation-changing methods to achieve safe and collision-free path planning. This approach is unsuitable for scenarios where the relative distance and angle between the dual AGVs need to remain constant. Considering that traditional path-planning algorithms cannot remain effective in complex environments [26], this study chose genetic algorithms, which offer high robustness and wide applicability among intelligent algorithms [27]. Firstly, the leader–follower AGV system was assumed to be rigid to maintain constant relative poses. Then, based on single-AGV path-planning strategies, longitudinal path planning for the leader AGV was conducted while taking into account the steering risks of the follower AGV to thoroughly study and optimize the dual-AGV-ganged paths. The main contributions are as follows:
(1) A safety steering radius for dual-AGV-ganged systems was designed by integrating the shapes of the leader and follower AGVs and the safety distance information into the global path-planning algorithm. This approach prevents steering collisions while effectively balancing path-planning effectiveness and cost map utilization.
(2) The pose information of the starting and goal points was introduced, and a dual-AGV-ganged steering cost function was established in the initialization stage of the GA path. This function predicts the steering conditions of the follower AGV and generates an initial path that is safe and collision-free.
(3) A dual-AGV-ganged fitness function was designed to comprehensively consider the steering conditions of both the leader and follower AGVs, guiding the algorithm to iteratively optimize toward achieving the smooth, efficient, and safe movement of the dual AGVs.
The rest of this paper is organized as follows: Section 2 introduces the establishment of the experimental environment and the setting of the dual-AGV-ganged safety steering radius based on the parameters of the leader–follower AGV. Section 3 introduces the main process of the proposed GA-based dual-AGV-ganged path-planning method. Section 4 details the simulation and real vehicle experiments that were conducted and presents the results analysis. Section 5 concludes this paper.

2. Establishment of Environmental Model

This study employs a two-dimensional grid map, one of the most commonly used map types in path planning [28]. As shown in Figure 1, each grid cell was quantified by an occupancy probability value, where a probability of 1 indicates occupancy, 0 indicates unoccupancy, and values between 0 and 1 indicate unknown states. The AGV can pass through a grid when it is unoccupied. Initial information is obtained through topic communication in the Robot Operating System (ROS). ROS, a middleware framework for robot software development, was created by Willow Garage in 2007 [29]. The coordinates retrieved from the subscribed topic information were then converted into decimal form using real-number encoding. In AGV navigation, an inflation radius was typically set in the cost map to account for the dimensions of the AGV, thereby reducing the risk of collisions [30]. However, this method has limitations when dealing with AGVs that have significantly different length and width dimensions as it requires a trade-off between safety and efficient map utilization [31].
To address potential collision issues during straight-line movement in a dual-AGV-ganged system, this study adjusted the inflation radius in the cost map. Additionally, a dual-AGV-ganged safety steering radius was introduced in the global path-planning algorithm to ensure collision-free turning, significantly enhancing the safety of the dual-AGV-ganged system during navigation.
As shown in Figure 2, the black dashed box outlines the overall profile of the dual-AGV-ganged system, while the blue rectangles represent the contours of the leader AGV and the follower AGV, maintaining a fixed safety distance between them. The green arrows on the leader AGV’s contours indicate the shared orientation of the two vehicles. The parameters for the dual-AGV-ganged system are based on the center-to-center distance c between the two AGVs, as well as the horizontal distance a and vertical distance b from the center of a single AGV to its contour. The specific settings are detailed below.
The inflation radius of the cost map was set based on the horizontal and vertical distances from the center of gravity to the outer contour of a single AGV, along with a buffer distance, as described by Equation (1):
R Map = a 2 + b 2 + d s ,
where R Map is the global cost map inflation radius; a and b are the horizontal and vertical distances from the center of gravity of a single AGV to the profile, respectively; and d s is the buffer distance.
This paper comprehensively considers factors such as the center of gravity distance of the leader–follower AGV and the resolution of the cost map to establish a safety steering radius for dual AGVs, as specified in Equation (2):
R Turn = a 2 + c 2 + d s r ,
where R Turn is the safety steering radius for dual AGVs, c is the distance between the centers of gravity of the leader and follower AGVs, and r is the resolution of the cost map.

3. Proposed Dual-AGV-Ganged Path-Planning Method

3.1. Introducing the Starting-Point and Goal-Point Pose for Path Initialization

The initialization process plays a crucial role in the convergence speed and final outcomes of the algorithm. This paper proposes dual-AGV-ganged safety-steering rules to guide the direction of path initialization. Additionally, the poses of the starting and goal points were incorporated to more comprehensively consider the possible steering collisions of dual AGVs. First, the angle of the starting point was calculated. Using the dual-AGV-ganged system’s safe turning radius, the vector angles between the starting point and pre-selected path points, as well as the turning cost of the dual-AGV system, were computed to select the suitable path points for generating a path that considers the starting-point’s pose. Next, based on this initial path, the angle of the goal point was calculated, and the vector angles and turning costs between the pre-selected path points and the goal point were determined in reverse. This ensures the selection of appropriate path points to generate a path that accounts for both the starting and goal points’ poses, thereby completing the population initialization. The specific steps are detailed below.
Part I: Initialization of the Path Starting-Point Poses
(1) Obtain the angle of the starting-point: By subscribing to the ROS topic published by AMCL, the pose information of the leader AGV’s starting point is obtained, including the orientation represented by the quaternion ( q = [ w , x , y , z ] ). In this context, a quaternion is a four-dimensional vector used to represent 3D rotations. The component www is related to the rotation angle, while x, y, and z represent the components of the rotation axis along the x, y, and z directions, respectively [32]. The quaternion is converted to Euler angles using Equations (3)–(5). The Euler angle along the z-axis of the AGV is mapped from ( π , π ) to ( 0 , 2 π ) , and, after a 180° clockwise rotation, the starting-point angle θ start is obtained. Finally, the starting point is set as the current node of the leader AGV, and θ start is set as the current angle of the follower AGV:
Roll ( ϕ ) = atan 2 ( 2 ( w x + y z ) , 1 2 ( x 2 + y 2 ) ) ,
Pitch ( θ ) = asin ( 2 ( w y z x ) ) ,
Yaw ( ψ ) = atan 2 ( 2 ( w z + x y ) , 1 2 ( y 2 + z 2 ) ) ,
where Roll ( ϕ ) is the roll angle, Pitch ( θ ) is the pitch angle, Yaw ( ψ ) is the yaw angle, atan2 is the arctangent function, and asin is the arcsine function.
(2) Conduct a search of the surrounding free nodes and sort: The free nodes around the current node of the leader AGV are identified, and the coordinates of the goal point with the current point are compared to determine the direction of the goal point relative to the current node. Next, the free nodes are sorted and then prioritized by selecting those located in or near this direction as candidate path points, setting the current node as P A and the candidate path points as P B ;
(3) Calculate the angle forming a vector: By subtracting the x and y coordinates of P A from the x and y coordinates of P B , respectively, d x and d y are obtained. Then, using Equation (6), the angle of vector is A B formed by P A and P B is calculated. This angle is then rotated 180° clockwise to set the target angle for the follower AGV:
θ point = 0 if d x = 0 and d y > 0 π if d x = 0 and d y < 0 π 2 if d x > 0 and d y = 0 3 π 2 if d x < 0 and d y = 0 atan 2 ( d y , d x ) if d x 0 and d y > 0 atan 2 ( d y , d x ) + 2 π if d x 0 and d y < 0 ,
where θ point is the angle of the vector A B .
(4) Calculate the cost value of the dual-AGV-ganged steering: The current angle of the follower AGV and the goal angle is set as θ A and θ B respectively, and the number of obstacle points between θ A and θ B is first calculated. Subsequently, the steering cost value between θ A and θ B is computed using the dual-AGV-ganged steering cost function. The steering process for the dual AGVs is illustrated in Figure 3, and the function is represented by Equation (7):
C Turn = 1 if N Obstacle = 0 N Obstacle × 100 if N Obstacle > 0 ,
where C Turn is the cost of turning, and N Obstacle is the number of obstacle points.
If θ A and θ B are equal, then N Obstacle is 0; if they are not equal, then, with the current node as the center and R Turn as the radius, adjust the x and y coordinates of the center by adding and subtracting the radius to form a range for intersection traversal. Within this range, find the coordinates where the distance from the center is less than or equal to the radius and falls within the specified angular region. Then, count the number of obstacles in this area to determine N Obstacle ;
(5) Generate a path considering the starting-point pose: Sequentially, the node with the minimum C Turn as the next node is selected, and then the current node for the leader AGV is designated. Then, this node is added to the path and the corresponding θ point is rotated clockwise by 180° to set the current angle for the follower AGV. Repeat these steps until an initial path to the goal point is generated;
Part II: Initialization of the Path Goal-Point Poses
(6) Obtain the angle of the goal-point: Subscribing to the ROS topics published by RVIZ, and in following Step (1), the angle θ goal of the goal point is obtained, the goal point is set as the current node for the leader AGV, and θ goal is set as the current angle for the follower AGV;
(7) Conduct a search of the surrounding free nodes and sort: In the initialized path obtained from Step (1), a path point is randomly selected and is designated as the goal point. Then, following Step (2), the free nodes around the current node of the leader AGV are retrieved and sorted;
(8) Working backwards to calculate the angle forming a vector: With the current node of the leader AGV as P B and the preselected path point as P A , and in following Step (3), the angle of the vector formed by the two nodes is reverse calculated to obtain θ point . This angle points from the preselected path point to the current node. After rotating it clockwise by 180°, it is set as the goal angle for the follower AGV;
(9) Reverse calculation of the dual-AGV-ganged steering cost value: In following Step (4), C Turn is calculated and selected with the node with the smallest C Turn as the next node. This is then set as the current node, which is then rotated θ point clockwise by 180° to determine the current angle for the follower AGV. The next node is then continually selected according to the aforementioned steps until the path to the random path point is found;
(10) Generate a path considering the goal-point pose: The path from the starting point to the random path point is combined with the path introducing the pose of the goal point in reverse order, generating a path that simultaneously considers the poses of both the starting point and the goal point;
Finally, determine whether the initial population requirements are met: if yes, output the initial population; if no, proceed to Step (6) and continue the initialization process. The algorithm initialization process is illustrated in Figure 4.

3.2. Dual-AGV-Ganged Fitness Function

The fitness function directly influences the selection and retention of paths, making it crucial for the algorithm’s outcomes. During the path initialization stage, this paper prioritized the shortest path points toward the goal direction, thus considering the shortest distance. In subsequent iterations, the goal was to achieve a collision-free operation for the dual-AGV-ganged system. Therefore, a dual-AGV-ganged fitness function was designed, as shown in Equation (8):
fitness = 1 C Start + C Middle + C Goal ,
where C Start is the starting-point steering cost value, C Middle is the middle point steering cost value, and C Goal is the goal-point steering cost value.
The calculation steps of C Start are as follows: Using the starting point as P A and the second point in the path as P B , calculate θ B using Equation (6) and then rotate it clockwise by 180°. θ start is taken as θ A . If θ A and θ B are equal, then N Sobstacle is 0. Otherwise, a detailed analysis needs to be conducted according to the following steps, as shown in Figure 5. The black rectangular box and arrow represent the dual-AGV system’s outline and orientation, the red line segment represents the planned path, the black circles represent path nodes, and the green circles represent obstacles. Begin using P A as the center, with R Turn as the radius. Calculate the number of grid cells occupied by obstacles within the sector formed by the two angles, resulting in N Sobstacle . Then, calculate C Start based on Equation (9).
C Start = 1 , N Sobstacle = 0 N Sobstacle × 100 , N Sobstacle > 0 ,
where C Start is the steering cost value at the starting point, and N Sobstacle is the number of obstacle points during the steering process at the starting location.
The calculation steps of C Middle are as follows: Starting from the path’s starting point, iterate through all path points. Compute the turning cost C Turn between three adjacent path points P i , P i + 1 , and P i + 2 . Specifically, take P i as P A , P i + 1 as P B , and calculate θ point using Equation (6). Rotate it clockwise by 180° to obtain θ A and θ B , respectively. If θ A and θ B are equal, then N Mobstacle i is 0. Otherwise, a detailed analysis needs to be conducted according to the following steps, as shown in Figure 6. Using P i + 1 as the center, with R Turn as the radius, calculate the number of grid cells occupied by obstacles within the sector formed by the two angles, resulting in N Mobstacle i . Then, calculate C Middle i based on Equation (10). Repeat the above steps until reaching the goal point and then sum up the C Middle i values to obtain C Middle , as shown in Equation (11).
C Middle i = 1 , N Mobstacle i = 0 N Mobstacle i × 100 , N Mobstacle i > 0 ,
where C Middle i is the steering cost value at the i intermediate node in the path, and N Mobstacle i is the number of obstacle points during the steering process at the i intermediate node location in the path.
C Middle = i = 1 n C Middle i ,
where C Middle is the steering cost value at the middle point, and n is the number of intermediate nodes in the path, excluding the starting and goal points.
The calculation steps of C Goal are as follows: Using the goal point as P B and the second-to-last point in the path as P A , calculate θ A using Equation (6) and then rotate it clockwise by 180°. θ goal is taken as θ B . If θ A and θ B are equal, then N Gobstacle is 0. Otherwise, a detailed analysis needs to be conducted according to the following steps, as shown in Figure 7. Begin using P A as the center, with R Turn as the radius, and then calculate the number of grid cells occupied by obstacles within the sector formed by the two angles, resulting in N Gobstacle . Then, calculate C Goal based on Equation (12).
C Goal = 1 , N Gobstacle = 0 N Gobstacle × 100 , N Gobstacle > 0 ,
where C Goal is the steering cost value at the starting point, and N Gobstacle is the number of obstacle points during the steering process at the goal location.

3.3. Genetic Operator

In a GA, the selection operation is a crucial step for choosing the best individuals to form the next generation by evaluating the results of the fitness function. This paper adopted an elitism strategy, preserving individuals with the highest fitness to ensure superior traits are carried forward, thereby aiding in achieving better convergence [33]. Simultaneously, the roulette wheel method was employed for selection to prevent premature convergence of the population [34].
In a GA, the crossover operation is also a crucial step in generating the next generation of individuals, but it can introduce issues at turning points. Therefore, this paper adopted a single-point random crossover method, which protects the path while maintaining the diversity of the population.
In a GA, the mutation operation enhanced the algorithm’s local search capability, preventing it from becoming trapped in local optima. This paper utilized a cell mutation operation, where two non-adjacent positions on the path are randomly selected as mutation points for local adjustment, thereby achieving the goal of forward path search.

3.4. Algorithm Termination Conditions

The iteration termination condition in this study is defined as either the best fitness value of the population remaining unchanged for five consecutive generations or reaching the maximum number of iterations. If the population evolution condition is met, the loop terminates, and the optimal path is decoded and output. If the maximum number of iterations is reached, the path with the minimum steering cost value is selected, decoded, and output.

3.5. Algorithm Process

The pseudocode for the GA-based dual-AGV-ganged path-planning method is presented as Algorithm 1.
Algorithm 1: Genetic Algorithm
Applsci 14 07482 i001

4. Experimental Results and Discussion

To validate the feasibility and effectiveness of the proposed algorithm, we conducted experiments in both simulated and real environments. The experiments evaluated the path-planning performance after incorporating the pose information of the starting and goal points. The results were then compared with those obtained using the GA, Astra algorithm, and Dijkstra algorithm.

4.1. Simulation Experiment of the Introduced Starting-Point and Goal-Point Poses

This study conducted simulation verification on the ROS Noetic platform using experimental equipment equipped with an i5-12400F processor, 16 GB RAM, and a 2.50 GHz main frequency.The processor was manufactured by Intel Corporation, Santa Clara, USA. The simulation involved two AGVs equipped with VLP-32C LiDAR, produced by Velodyne Lidar, Inc., San Jose, CA, USA, and RealSense D435i depth cameras, produced by Intel Corporation, Santa Clara, CA, USA, along with several static obstacles, modeled in Gazebo with the cost map resolution set to 0.05. The Gmapping simultaneous localization and mapping (SLAM) algorithm, version 1.4.2, was used to generate a detailed environment map, which was converted into a format suitable for path planning using the Map Server package, version 1.17.3. The map was visualized using the Rviz component, as shown in Map 1 in Figure 8. The black and blue rectangular boxes in the center correspond to the overall outline of the dual-AGV-ganged system, as well as the shapes, safety distance, and orientation of the leader AGV (AGV1) and follower AGV (AGV2), as depicted in Figure 2. The other black areas represent obstacles, the regions surrounding the black areas indicate inflated regions, and the gray areas denote navigable regions.
To better analyze the path-planning process with consideration of the initial pose, we selected a region from the map shown in Figure 8 with a higher density of obstacles and greater difficulty in path planning. As illustrated in Figure 9, this region was chosen to evaluate the dual-AGV system’s performance. The AGV outlines and obstacle information in Figure 9 are consistent with those depicted in Figure 8. The blue dashed rectangular box represents the approximate position of the dual-AGV system during operation.
In Figure 9a, the black arrows indicate the initial pose, while the black lines represent the planned path. When the initial pose is not considered, the planning primarily follows the shortest path. However, at the starting point, the AGV must rotate from its initial angle to the vector angle formed by the first two points on the path. During this rotation, the dual-AGV system is at risk of colliding with obstacles, as evidenced by the situation at Position A.
In contrast, Figure 9b demonstrates the path-planning process when the initial pose is considered. Here, the AGV maintains a straight trajectory aligned with the starting point’s angle, continuing in this direction until it reaches a safe position. Only then does it initiate a turn, as shown at Position B. This approach effectively avoids steering collisions that could occur when the initial pose is ignored.
To comprehensively demonstrate the effectiveness of the algorithm, we conducted an experiment that simultaneously introduced the poses of both the starting point and the goal point into the path-planning process, as shown in Figure 10a. The corresponding map information is similar to that shown in Figure 9, focusing on a region with a higher density of obstacles and greater path-planning challenges. The black arrow at the end of the path represents the goal point’s pose. Without accounting for the starting point’s pose, the AGV risks colliding with obstacles during the initial phase, as seen at Position C. Moreover, after reaching the goal point’s location, the AGV needs to rotate from the angle formed by the last two points on the path to align with the goal point’s pose. This turning process may lead to collisions with obstacles, as seen at Position D. Conversely, in Figure 10b, the algorithm takes into consideration both the starting-point and goal-point poses. The dual-AGV system effectively avoids collisions at the starting point by planning a path that accounts for the initial pose, as shown at Position E. Furthermore, it anticipates the goal-point’s pose, ensuring that no additional turns are required after reaching the goal point. This approach prevents the turning collisions observed when the goal point’s pose is neglected, as demonstrated at Position F.

4.2. Path-Length Comparison Simulation Experiment

Since the commonly used A* and Dijkstra algorithms in ROS are only suitable for single-AGV scenarios, they cannot be directly applied to the path planning of a dual-AGV system. To ensure safety, we treated the dual AGVs as a single unit for path planning and avoided collisions by increasing the global inflation radius. This approach expands the inflation radius in Map 1 to match the overall outline of the dual-AGV system. However, in many of the scenarios where the dual AGVs could previously navigate safely, this method failed to provide effective paths. Consequently, we adjusted the starting-point pose and conducted comparative experiments, as shown in Figure 11. In Map 2, the contour of the dual-AGV system is represented by a black rectangular box. Compared to Figure 8, the inflation regions surrounding the black areas representing obstacles were significantly larger, while the traversable gray areas were noticeably reduced. All other information remained the same as in Figure 8.
To facilitate a comparison of the path-planning effectiveness while ensuring safety, we conducted 100 experiments using the proposed algorithm and two other algorithms. We then performed a comparative analysis of the most frequently occurring paths, as shown in Figure 12. The red path represents the route planned by the Dijkstra algorithm, the blue path represents the Astra algorithm’s route, and the orange path represents the route planned by the algorithm proposed in this paper. The Astra and Dijkstra algorithms were constrained by the inflation radius, resulting in a decrease in map utilization. The paths planned by the Astra algorithm were convoluted, while those planned by the Dijkstra algorithm were lengthy. However, the algorithm proposed in this paper was not constrained by such limitations and could significantly shorten path lengths while enhancing path smoothness.
In Figure 12, the upper right corner displays the length information of the three paths. Compared to the Astra and Dijkstra algorithms, the path length achieved by our algorithm was reduced by 23.5% and 24.3%, respectively. The algorithm demonstrated outstanding performance and significantly enhanced the utilization rate of the global cost map. In summary, the proposed algorithm effectively mitigates the issue of steering collisions in a dual-AGV-ganged system while considering the pose information of starting and goal points, resulting in the successful planning of safe, collision-free, and efficient global paths.

4.3. Real Experiment Introducing Starting-Point and Goal-Point Poses

This study employed two identical Bulldog-star ROS AGVs for experimental validation. Both leader and follower AGVs were equipped with Intel i11-1165G7 processors, 64 GB RAM, 2.8 GHz clock speed, and an Ubuntu 20.04 ROS Noetic system.The processor was manufactured by Intel Corporation, Santa Clara, USA. As shown in Figure 13, these AGVs were equipped with four omni-directional McNamee wheels. Additionally, they were equipped with USB 3.0 interfaces, RealSense D435i depth cameras (with a measurement accuracy of 0.2–1%), IMU Brick 2.0 six-axis accelerometers (with a measurement accuracy of 0.01°), and VLP-32C LiDAR (with a maximum detection range of 200 m, measurement accuracy of 3 cm, and angular resolution of 0.33°) for environmental perception. The resolution of the cost map was set to 0.02, and the Gmapping SLAM algorithm was employed to meticulously model the environment, which was then converted into a map suitable for path planning using the Map server package.The manufacturer of the corresponding hardware and the software version are consistent with those in the simulation.
The dimensions of the Bulldog-star ROS AGV were approximately 85 cm in length, 60 cm in width, and 77 cm in height, with the laser radar positioned at a height of about 55 cm above the ground. Based on these dimensions, eight static obstacles were set up to create the experimental environment, as depicted in Figure 14. The global cost map constructed using the Gmapping algorithm, as visualized through Rviz, is shown in Figure 15. The information presented in this map aligns with the cost map constructed during simulation.
As shown in Figure 16, without introducing the pose information of the starting and goal points, all three algorithms neglected the starting-point pose during path planning. This may lead to the follower AGV colliding with surrounding obstacles when turning at the starting point, as indicated by the blue dashed box at the starting point in Figure 17a. Similarly, since these algorithms do not consider the goal-point pose, the follower AGV needs to adjust its posture after reaching the goal point, which may result in collisions with nearby boxes, as indicated by the blue dashed box at the goal point shown in Figure 17b. Additionally, the Astra and Dijkstra algorithms may cause collisions when planning the middle section of the path, as indicated by the green dashed box. This significantly increases the difficulty of local path planning and the risk of collisions.
As shown in Figure 18b, with the introduction of the starting-point pose, the path planning takes into account the collision risks during turning. If it is not possible to turn safely, the system proceeds straight to a safe location before turning, thereby avoiding the risk of collision during the initial turning. However, due to the lack of consideration for the goal-point pose, collision risks still exist near the goal point.
As shown in Figure 18c, with the simultaneous introduction of the starting- and goal-point poses, the algorithm comprehensively considers the safety issues of turning at each position and can plan the path in advance according to the target-point poses. This ensures that both leader and follower AGVs operate safely and are collision-free throughout the journey, aligning with the results of simulation experiments.
As shown in Figure 19, the global cost Map 4 closely resembles the results of the simulation experiments. Due to the lack of consideration for the poses of the starting and goal points in the global path planning of ROS, a larger global inflation radius needs to be set to avoid collisions between the dual AGVs.
Due to the limitations of the inflation radius settings and the inherent constraints of the algorithms, both the GA and the Astra algorithms failed to plan safe and effective paths. In contrast, while the Dijkstra algorithm successfully planned paths, they were relatively lengthy. The algorithm proposed in this paper demonstrated superior efficiency, reducing the path length by 2 m to just 76.8% of the Dijkstra algorithm’s path length. Additionally, it required fewer turns, as depicted in Figure 20.

4.4. Comparison of Real-World Experiments in Narrow Environments

In this study, more complex scenarios were set up to conduct comprehensive comparison experiments with the GA, Astra algorithm, and Dijkstra algorithm, and their performance in narrow spaces was tested. However, due to the limitations of the GA and Astra algorithm, they failed to successfully plan safe paths. They could only reduce the cost coefficient of the cost map, which increased the risk of collisions, resulting in paths that still collided with surrounding obstacles. Although the Dijkstra algorithm could generate safe paths, the large inflation radius significantly reduced map utilization, failed to plan a path through narrow areas, increased path length, and decreased path quality. In contrast, the proposed algorithm successfully navigated through narrow areas, as depicted in Figure 21. Meanwhile, it effectively balanced path length and cost map utilization, generating global paths that were both short and smooth, as shown in Figure 22.
As shown in Figure 22, the path length of the proposed algorithm in this paper was significantly superior to the other two algorithms. Compared to the Astra algorithm, which failed to successfully plan paths, the paths generated by our algorithm were more effective. Moreover, in comparison to the Dijkstra algorithm, the path length of our algorithm was shortened by 5.35 m, representing a reduction of 30.1%, thereby significantly enhancing the performance of the algorithm and the utilization rate of the global cost map.
The experimental results demonstrate that, both in simulation and real environments, the proposed algorithm effectively avoids steering collisions in a dual-AGV-ganged system while considering the poses of the starting and goal points, thus successfully planning safe and collision-free paths. Traditional algorithms require setting a larger inflation radius to ensure path safety, but this significantly reduces the utilization of the cost map. In complex real-world environments, the GA and Astra algorithm fail to plan paths successfully, and although the Dijkstra algorithm can plan paths, the resulting paths are longer. In contrast, our algorithm successfully generates safe, collision-free, and efficient global paths, significantly improving path length and smoothness. Moreover, this algorithm efficiently utilizes map resources, enabling smooth passage through narrow areas, providing safer and more efficient global guidance for local path planning.

5. Conclusions

To enhance the safety and efficiency of the dual-AGV-ganged system, this study proposes a GA-based method for dual-AGV-ganged path planning. This method incorporates the pose information of starting and goal points and designs a safe turning radius for dual-AGV-ganged systems, effectively preventing steering collisions during global path planning. This allows dual AGVs to complete tasks swiftly, smoothly, efficiently, and safely. Simulation and real-vehicle experiments demonstrate that, whether in simple or complex scenarios, the proposed algorithm successfully plans globally collision-free and efficient paths for both leader and follower AGVs. Compared to traditional genetic algorithms, the path-planning capability is significantly improved, and its performance surpasses the widely used Astra and Dijkstra algorithms in ROS. By ensuring the safety, success rates, and optimal utilization of the cost map, the algorithm can plan paths that are both short and smooth. This provides a novel solution for dual-AGV-ganged path planning, showcasing significant practical value and promising application prospects.
Compared to existing global path-planning algorithms for dual-AGV systems that mainly rely on setting a large inflation radius, the method proposed in this paper offers significant innovations. However, one of the potential challenges in future work is the introduction of dynamic obstacles into the path-planning process. The presence of dynamic obstacles could have a substantial impact on the proposed method, particularly in situations where the dual-AGV system needs to adapt to unforeseen changes in the environment. While our current approach effectively handles static obstacles, dynamic obstacles may increase the complexity of ensuring collision-free operation. A key challenge arises when the dual-AGV system is turning: if an obstacle appears on the side of the follower AGV, the leader AGV may successfully avoid it, but the follower AGV could still collide, leading to potential safety issues.
Therefore, future research will focus on refining the algorithm to accommodate dynamic obstacles, ensuring that the dual-AGV system can respond in real-time without compromising safety. Furthermore, it is essential to explore multi-AGV-ganged path planning to fully leverage the advantages of our algorithm in balancing safety and cost map utilization. Additionally, we will delve into multi-AGV-ganged global dynamic path planning to enhance the overall efficiency and practicality of multi-AGV-ganged systems.

Author Contributions

H.L. and Y.C. contributed to the original draft writing and conducted experiments. F.R. and M.L. contributed to optimizing the original draft writing. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the National Key Research and Development Program of China (2021YFB1716200) and the Research Funds for Leading Talents Program (048000514123686).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data are contained within the article.

Conflicts of Interest

The authors have no competing interests to declare that are relevant to the content of this article.

References

  1. Ji, W.; Wang, L. Industrial robotic machining: A review. Int. J. Adv. Manuf. Technol. 2019, 103, 1239–1255. [Google Scholar] [CrossRef]
  2. Li, D.; He, Y.; Zhao, X.; Su, Y.; Huang, J. Trajectory Tracking Control Design for Dual Unmanned Ground Vehicle Cooperative Handling System. In Proceedings of the 2022 International Conference on Advanced Robotics and Mechatronics (ICARM), Guilin, China, 9–11 July 2022; pp. 943–948. [Google Scholar]
  3. Liu, L.; Wang, X.; Yang, X.; Liu, H.; Li, J.; Wang, P. Path planning techniques for mobile robots: Review and prospect. Expert Syst. Appl. 2023, 227, 120254. [Google Scholar] [CrossRef]
  4. Akka, K.; Khaber, F. Mobile Robot Path Planning Using an Improved Ant Colony Optimization. Int. J. Adv. Robot. Syst. 2018, 15, 1729881418774673. [Google Scholar] [CrossRef]
  5. Zheng, T.; Xu, Y.; Zheng, D. AGV Path Planning based on Improved A-star Algorithm. In Proceedings of the 2024 IEEE 7th Advanced Information Management, Communicates, Electronic and Automation Control Conference (IMCEC), Chongqing, China, 15–17 March 2024. [Google Scholar]
  6. Chen, Z.; Xu, B. AGV path planning based on improved artificial potential field method. In Proceedings of the 2021 IEEE International Conference on Power Electronics, Computer Applications (ICPECA), Shenyang, China, 22–24 January 2021; pp. 32–37. [Google Scholar]
  7. LaValle, S. Rapidly-Exploring Random Trees: A New Tool for Path Planning; Research Report 9811; Department of Computer Science, Iowa State University: Ames, IA, USA, 1998. [Google Scholar]
  8. Sun, Y.; Fang, M.; Su, Y. AGV path planning based on improved Dijkstra algorithm. J. Phys. Conf. Ser. 2021, 1746, 012052. [Google Scholar] [CrossRef]
  9. He, C.; Mao, J. AGV optimal path planning based on improved ant colony algorithm. In Proceedings of the 2018 2nd International Conference on Electronic Information Technology and Computer Engineering (EITCE 2018), Shanghai, China, 12–14 October 2018; Volume 232, p. 03052. [Google Scholar]
  10. Luo, M.; Hou, X.; Yang, S.X. A multi-scale map method based on bioinspired neural network algorithm for robot path planning. IEEE Access 2019, 7, 142682–142691. [Google Scholar] [CrossRef]
  11. Zhang, Y.; Gong, D.-w.; Zhang, J.-h. Robot path planning in uncertain environment using multi-objective particle swarm optimization. Neurocomputing 2013, 103, 172–185. [Google Scholar] [CrossRef]
  12. Tan, X.; Lei, D.; Wu, D.; Li, Z. Robot path planning using an improved genetic algorithm with ordered feasible subpaths. In Proceedings of the 2018 Chinese Automation Congress (CAC), Xi’an, China, 30 November–2 December 2018; pp. 4293–4297. [Google Scholar]
  13. Liang, D.; Liu, Z.; Bhamra, R. Collaborative multi-robot formation control and global path optimization. Appl. Sci. 2022, 12, 7046. [Google Scholar] [CrossRef]
  14. Pan, Z.; Wang, D.; Deng, H.; Li, K. A virtual spring method for the multi-robot path planning and formation control. Int. J. Control Autom. Syst. 2019, 17, 1272–1282. [Google Scholar] [CrossRef]
  15. Zhou, W.; Li, S.; Chen, Y. Research on Multi-Robot Cooperative Handling and Obstacle Avoidance Algorithm. In Proceedings of the 2022 International Conference on Cyber-Physical Social Intelligence (ICCSI), Nanjing, China, 18–21 November 2022; pp. 648–652. [Google Scholar]
  16. LIUa, Y. A Local Path Planning Method of Multi-AGV Systems. In Proceedings of the Mechatronics and Automation Technology: 2nd International Conference (ICMAT 2023), Wuhan, China, 28–29 October 2023; IOS Press: Amsterdam, The Netherlands, 2024; Volume 46, p. 380. [Google Scholar]
  17. Alonso-Mora, J.; Knepper, R.; Siegwart, R.; Rus, D. Local motion planning for collaborative multi-robot manipulation of deformable objects. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 5495–5502. [Google Scholar]
  18. Wang, X.; Yang, H.; Chen, H.; Wang, J.; Bai, L.; Zan, W. Leader-Follower Formation Control Based on Artificial Potential Field and Sliding Mode Control. In Proceedings of the Intelligent Robotics and Applications: 10th International Conference, ICIRA 2017, Wuhan, China, 16–18 August 2017; Proceedings, Part III; Springer: Berlin/Heidelberg, Germany, 2017; pp. 203–214. [Google Scholar]
  19. Aram, K.; Erdemir, G.; Can, B. Formation Control of Multiple Autonomous Mobile Robots Using Turkish Natural Language Processing. Appl. Sci. 2024, 14, 3722. [Google Scholar] [CrossRef]
  20. Di Caro, G.A.; Yousaf, A.W.Z. Multi-robot informative path planning using a leader-follower architecture. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021; pp. 10045–10051. [Google Scholar]
  21. Lin, S.; Liu, A.; Wang, J. A Dual-Layer Weight-Leader-Vicsek Model for Multi-AGV Path Planning in Warehouse. Biomimetics 2023, 8, 549. [Google Scholar] [CrossRef] [PubMed]
  22. Hu, J.; Liu, W.; Zhang, H.; Xiong, Z. Obstacle Crossing by Multi-mobile Robots in Object Transportation with Deformable Sheet. arXiv 2021, arXiv:2111.09046v1. [Google Scholar]
  23. Yang, L.; Fu, L.; Li, P.; Mao, J.; Guo, N.; Du, L. LF-ACO: An effective formation path planning for multi-mobile robot. Math. Biosci. Eng. 2022, 19, 225–252. [Google Scholar] [CrossRef] [PubMed]
  24. Lu, W.; Xiong, H.; Zhang, Z.; Hu, Z.; Wang, T. Scalable Optimal Formation Path Planning for Multiple Interconnected Robots via Convex Polygon Trees. J. Intell. Robot. Syst. 2023, 109, 63. [Google Scholar] [CrossRef]
  25. Tse, S.K.; Wong, Y.B.; Tang, J.; Duan, P.; Leung, S.W.W.; Shi, L. Relative state formation-based warehouse multi-robot collaborative parcel moving. In Proceedings of the 2021 4th IEEE International Conference on Industrial Cyber-Physical Systems (ICPS), Victoria, BC, Canada, 10–12 May 2021; pp. 375–380. [Google Scholar]
  26. Cui, Y.; Hu, W.; Rahmani, A. Multi-robot path planning using learning-based artificial bee colony algorithm. Eng. Appl. Artif. Intell. 2024, 129, 107579. [Google Scholar] [CrossRef]
  27. Huang, F.; Guo, W.; Zhao, H. AGV Path Planning Based on Improved Genetic Algorithm. In Proceedings of the 2023 2nd International Symposium on Control Engineering and Robotics (ISCER), Hangzhou, China, 17–19 February 2023; pp. 3323–3327. [Google Scholar]
  28. Li, Z.; Li, Y.; Rong, X.; Zhang, H. Grid map construction and terrain prediction for quadruped robot based on c-terrain path. IEEE Access 2020, 8, 56572–56580. [Google Scholar] [CrossRef]
  29. Quigley, M.; Conley, K.; Gerkey, B.; Faust, J.; Foote, T.; Leibs, J.; Wheeler, R.; Ng, A.Y. ROS: An open-source Robot Operating System. In Proceedings of the ICRA workshop on open source software, Kobe, Japan, 12–17 May 2009; Volume 3, p. 5. [Google Scholar]
  30. King, J.; Likhachev, M. Efficient Cost Computation in Cost Map Planning for Non-Circular Robots. In Proceedings of the 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems, St. Louis, MO, USA, 10–15 October 2009; pp. 3924–3930. [Google Scholar] [CrossRef]
  31. Oajsalee, S.; Tantrairatn, S.; Khaengkarn, S. Study of ROS Based Localization and Mapping for Closed Area Survey. In Proceedings of the 2019 IEEE 5th International Conference on Mechatronics Systems and Robots (ICMSR), Singapore, 24–28 July 2019; pp. 24–28. [Google Scholar] [CrossRef]
  32. Kong, M.; Ji, C.; Chen, Z.; Li, R. Application of Orientation Interpolation of Robot Using Unit Quaternion. In Proceedings of the 2013 IEEE International Conference on Information and Automation (ICIA), Yinchuan, China, 26–28 August 2013; IEEE: New York, NY, USA, 2013; pp. 384–389. [Google Scholar] [CrossRef]
  33. Liu, C.; Liu, A.; Wang, R.; Zhao, H.; Lu, Z. Path Planning Algorithm for Multi-Locomotion Robot Based on Multi-Objective Genetic Algorithm with Elitist Strategy. Micromachines 2022, 13, 616. [Google Scholar] [CrossRef]
  34. Xia, G.M.; Zeng, J.C. A stochastic particle swarm optimization algorithm based on the genetic algorithm of roulette wheel selection. Comput. Eng. Sci. 2007, 29, 6–11. [Google Scholar]
Figure 1. Two-dimensional grid map.
Figure 1. Two-dimensional grid map.
Applsci 14 07482 g001
Figure 2. Parameters of the dual-AGV-ganged system.
Figure 2. Parameters of the dual-AGV-ganged system.
Applsci 14 07482 g002
Figure 3. Schematic diagram of the dual-AGV-ganged steering.
Figure 3. Schematic diagram of the dual-AGV-ganged steering.
Applsci 14 07482 g003
Figure 4. Population initialization flowchart.
Figure 4. Population initialization flowchart.
Applsci 14 07482 g004
Figure 5. Starting-point turning diagram.
Figure 5. Starting-point turning diagram.
Applsci 14 07482 g005
Figure 6. Middle-point turning diagram.
Figure 6. Middle-point turning diagram.
Applsci 14 07482 g006
Figure 7. Goal-point turning diagram.
Figure 7. Goal-point turning diagram.
Applsci 14 07482 g007
Figure 8. Global cost Map 1.
Figure 8. Global cost Map 1.
Applsci 14 07482 g008
Figure 9. Comparison of the path-planning effects of the algorithm with the introduction of the pose of starting point: (a) Path without the introduction of starting-point pose planning. (b) Path with the introduction of starting-point pose planning.
Figure 9. Comparison of the path-planning effects of the algorithm with the introduction of the pose of starting point: (a) Path without the introduction of starting-point pose planning. (b) Path with the introduction of starting-point pose planning.
Applsci 14 07482 g009
Figure 10. Comparison of the path-planning effects of the algorithm with the introduction of the goal-point pose: (a) Path without the introduction of goal-point pose planning. (b) Path with the introduction of goal-point pose planning.
Figure 10. Comparison of the path-planning effects of the algorithm with the introduction of the goal-point pose: (a) Path without the introduction of goal-point pose planning. (b) Path with the introduction of goal-point pose planning.
Applsci 14 07482 g010
Figure 11. Global cost Map 2.
Figure 11. Global cost Map 2.
Applsci 14 07482 g011
Figure 12. Comparison of the path-planning results using the three algorithms in simulated environments.
Figure 12. Comparison of the path-planning results using the three algorithms in simulated environments.
Applsci 14 07482 g012
Figure 13. Leader–follower Bulldog-star ROS AGV.
Figure 13. Leader–follower Bulldog-star ROS AGV.
Applsci 14 07482 g013
Figure 14. Experimental setup with real vehicles.
Figure 14. Experimental setup with real vehicles.
Applsci 14 07482 g014
Figure 15. Global cost Map 3.
Figure 15. Global cost Map 3.
Applsci 14 07482 g015
Figure 16. Comparison of the path-planning results of the three algorithms: (a) Path planned using the genetic algorithm. (b) Path planned using the Astra algorithm. (c) Path planned using the Dijkstra algorithm.
Figure 16. Comparison of the path-planning results of the three algorithms: (a) Path planned using the genetic algorithm. (b) Path planned using the Astra algorithm. (c) Path planned using the Dijkstra algorithm.
Applsci 14 07482 g016
Figure 17. In real-world environment key-point steering scenarios: (a) Initial-point steering scenario. (b) Goal-point steering scenario.
Figure 17. In real-world environment key-point steering scenarios: (a) Initial-point steering scenario. (b) Goal-point steering scenario.
Applsci 14 07482 g017
Figure 18. Comparison of the path-planning effects of the algorithm with the introduction of the pose of starting point: (a) Path without the introduction of starting-point pose planning. (b) Path with the introduction of starting-point pose planning. (c) Path planned with the introduction of both starting- and goal-point pose planning.
Figure 18. Comparison of the path-planning effects of the algorithm with the introduction of the pose of starting point: (a) Path without the introduction of starting-point pose planning. (b) Path with the introduction of starting-point pose planning. (c) Path planned with the introduction of both starting- and goal-point pose planning.
Applsci 14 07482 g018
Figure 19. Global cost Map 4.
Figure 19. Global cost Map 4.
Applsci 14 07482 g019
Figure 20. Comparison of the path-planning results using two algorithms in real environments.
Figure 20. Comparison of the path-planning results using two algorithms in real environments.
Applsci 14 07482 g020
Figure 21. A narrow area in a real environment.
Figure 21. A narrow area in a real environment.
Applsci 14 07482 g021
Figure 22. Comparison of the path-planning results using two of the algorithms in real narrow environments.
Figure 22. Comparison of the path-planning results using two of the algorithms in real narrow environments.
Applsci 14 07482 g022
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

Cai, Y.; Liu, H.; Li, M.; Ren, F. A Method of Dual-AGV-Ganged Path Planning Based on the Genetic Algorithm. Appl. Sci. 2024, 14, 7482. https://doi.org/10.3390/app14177482

AMA Style

Cai Y, Liu H, Li M, Ren F. A Method of Dual-AGV-Ganged Path Planning Based on the Genetic Algorithm. Applied Sciences. 2024; 14(17):7482. https://doi.org/10.3390/app14177482

Chicago/Turabian Style

Cai, Yongrong, Haibin Liu, Mingfei Li, and Fujie Ren. 2024. "A Method of Dual-AGV-Ganged Path Planning Based on the Genetic Algorithm" Applied Sciences 14, no. 17: 7482. https://doi.org/10.3390/app14177482

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