Next Article in Journal
A Three-Stage Nonparametric Kernel-Based Time Series Model Based on Fuzzy Data
Previous Article in Journal
NFT-Vehicle: A Blockchain-Based Tokenization Architecture to Register Transactions over a Vehicle’s Life Cycle
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Grid-Map-Based Path Planning and Task Assignment for Multi-Type AGVs in a Distribution Warehouse

Department of Logistics Engineering, School of Traffic and Transportation, Beijing Jiaotong University, Shangyuan Cun, Haidian District, Beijing 100044, China
*
Author to whom correspondence should be addressed.
Mathematics 2023, 11(13), 2802; https://doi.org/10.3390/math11132802
Submission received: 11 May 2023 / Revised: 17 June 2023 / Accepted: 20 June 2023 / Published: 21 June 2023

Abstract

:
In an intelligent distribution warehouse, latent AGVs are used for horizontal handling, and forklift AGVs are used for horizontal or vertical handling. Studying the path planning and task assignment problem when the two types of AGVs are mixed can help improve the warehouse operation efficiency and reduce the warehouse operation cost. This paper proposes a two-stage optimization method to solve this problem. In the first stage, the warehouse plan layout is transformed into a raster map, and the shortest path between any two points of the warehouse without conflict with fixed obstacles is planned and stored using the A* algorithm combined with circular rules, and the planned shortest path is called directly in the subsequent stages. In the second stage, to minimize the task completion time and AGV energy consumption, a genetic algorithm combining penalty functions is used to assign horizontal handling tasks to submerged AGVs or forklift AGVs and vertical handling tasks to forklift AGVs. The experimental results show that the method can meet the 24 h operation requirements of an intelligent distribution warehouse and realize the path planning and task assignment of forklift AGVs and latent AGVs. And furthermore, the number of AGVs arranged in the warehouse can be further reduced.

1. Introduction

With the opening of the Industry 4.0 era, AGV, IoT, cloud computing, AR, and other technologies continue to be put into practical application. In 2012, the application of Amazon Kiva was a successful example of the Industry 4.0 era. In the Kiva system, many AGVs carried shelves to pick-up stations, replacing the traditional manual pick-up using trolleys. This led to the massive use of AGVs in the warehousing sector. Multi-AGV systems in warehousing have been widely recognized as a practical means of improving productivity while significantly reducing operating costs [1]. The AGV operation optimization problem has also gradually become a research hotspot, mainly including task assignment, path planning, and joint optimization [2,3], which will be categorized and reviewed below.
AGV task assignment problem refers to assigning multiple tasks to multiple AGVs and determining the order in which each AGV performs the tasks. As shown in Table 1, most of the existing studies focus on multiple numbers and single types of AGVs, mainly using completion time, number of AGVs, and AGV utilization as the optimization objectives of task assignment and solving them with the targeted improvement of genetic algorithms and ant colony algorithms. A small portion of the literature also combines problems such as charging and picking station layout with AGV task assignments. With the increasing complexity of AGV application scenarios, a small portion of the literature has begun to research multiple types of AGVs. Zhou et al. [4] divided the parts needed by automobile production lines into light materials and heavy materials and proposed and solved the material handling problem with a time window for two types of AGV; light materials were transported via multi-load AGV, and heavy materials were transported via single-load AGV. There are also a few studies on the joint optimization of AGVs and associated equipment. Aziez et al. [5] modeled the dual optimization of AGVs and trolleys for the actual situation of using trolleys to move materials and AGVs to move trolleys in hospitals and proposed an adaptive large domain search algorithm for fast response to dynamic demands. Hu et al. [6] studied the problem of task assignment for AGVs and automated crane trucks in automated container terminals.
AGV path planning is finding a path that allows AGV to reach the destination quickly without interference. The existing research can be divided into traditional and bionic intelligent path planning. Traditional path planning includes the artificial potential field method, Dijkstra’s algorithm, and the A-star algorithm. Khatib [14] first proposed a real-time obstacle avoidance method for robotic arms based on the concept of artificial potential field, assuming that the robotic arms are in a virtual force field, in the attraction generated via the target point and the repulsion generated via the obstacle. However, the traditional artificial potential field method is easily limited to local information, resulting in congestion, locking, and so on. However, the traditional, artificial, potential field method is easily limited by the localization of information, which leads to congestion and lock up, etc. The subsequent studies focus on achieving conflict-free path planning for robots by improving the local minimum problem [15,16,17]. Dijkstra algorithm is a classical path search algorithm for global path search in a static environment, which is fast and accurate in the case of a few nodes and is mainly used in topological maps. Kim et al. [18] combine the Dijkstra algorithm and time window to realize the conflict-free shortest path of AGV in a bidirectional flow network. The A-star algorithm is a heuristic search algorithm that combines the advantages of the Dijkstra algorithm and Breadth First Search. Due to its high efficiency, the A-star algorithm is widely used in real-time systems, artificial intelligence, and other fields, mainly in grid-based maps. Chiddarwar et al. [19] use the A-star algorithm to obtain the path without conflict between the robot and static obstacles, then dynamically adjust the robot sequence to resolve the conflict between multiple robots. Tang et al. [20] propose an improved geometric A-star algorithm for path planning to form smoother paths. Fransen et al. [21] improve the A-star algorithm to find the least-cost path with turn cost. The intelligent bionic algorithm mainly includes the genetic algorithm, ant colony algorithm, particle swarm algorithm, whale algorithm, and so on. Intelligent bionic algorithms are often appropriate for path planning when the operating environment is complex. Faridi et al. [22] propose to combine improved artificial swarm neighborhood search planning with evolutionary planning to solve multi-robot, multi-objective navigation problems in unknown dynamic environments. There are also studies using the ant colony algorithm [23] and the sheep flock heredity algorithm [24] for multi-robot path planning. With the complexity of the operating environment, path planning is often combined with dynamic obstacle avoidance problems. Zhong et al. [25] add time conflict-free constraints to the path planning model to obtain conflict-free scheduling of AGVs. In the field of intelligent vehicles, Gao et al. [26,27] predict the trajectories of potentially conflicting objects or intelligent vehicles, which also has some reference value for AGV dynamic obstacle avoidance.
Due to the importance and urgency of task assignment and path planning of AGVs, the joint optimization problem of the two is also a hot research topic. Most of the early research focused on exact algorithms. Krishnamurthy et al. [28] construct a mixed integer programming model to describe the DCFRP (dispatching and conflict-free route problem) and solve it using a column generation algorithm. Desaulniers et al. [29] developed exact methods combining column generation, greedy search heuristics, and branch-and-cut algorithms. As the solution size becomes larger, solution methods such as space–time networks, double-layer programming, and phased methods have been proposed one after another. Murakami [30] and Nishida et al. [31] solved the AGV path planning and task assignment problem by constructing space–time network models. Nishi et al. [32], Yang et al. [33], and Ji et al. [34] solved the problem using a two-layer planning approach, with the upper layer solving for AGV task assignment and the lower layer solving for AGV path planning. Hu et al. [35] and Liang et al. [36] proposed three-staged methods of solving path planning, task assignment, and conflict resolution sequentially.
Existing literature shows fruitful research results on AGV task assignment, path planning, and joint optimization. However, they mainly focus on operation workshops or automated terminals. Scenarios are mostly abstracted as topological maps, often ignore fixed obstacles in operation scenarios, and need to consider AGV simulation paths, which are less applicable in warehouse environments with a high density of facilities and equipment. Most of the existing research focuses on single-type AGVs. With the strengthening of intelligent requirements of warehousing, the demand for mixed operations of multiple types of AGVs, such as latent AGVs and forklift AGVs, becomes more significant. It is necessary to combine the scenario characteristics of intelligent distribution warehouses, to make targeted expansion of the research on AGV path planning and task assignment, and to realize the integration and optimization of multiple types of AGVs.
To solve the path planning and task assignment problem of latent AGVs and forklift AGVs in an actual intelligent distribution warehouse to achieve warehouse operation efficiency improvement and warehouse operation cost reduction, a two-stage optimization method combining offline planning and online planning is proposed. The first stage is offline shortest path planning, constructing the determined warehouse layout as a grid map, using the A-star algorithm for shortest path planning, and storing the shortest path and distance between any two grids as offline data, which can directly call the offline data to determine the travel path when the tasks in different planning cycles change, which can greatly reduce the repeated planning in practical application. The second stage is online multi-type task assignment, obtaining real-time updated task data, using the genetic algorithm to solve the problem with the goal of minimum task completion time and energy consumption of AGVs, and assigning two types of handling tasks to corresponding types of AGVs.
The rest of this paper is organized as follows: Section 2 performs the problem description; Section 3 constructs the mathematical model; Section 4 presents the proposed solution method; Section 5 conducts a case study; Finally, Section 6 concludes the paper.

2. Problem Description

A distribution warehouse is important for consolidating and distributing goods, mainly for short-term storage and rapid transit. Therefore, it is often necessary to put both latent AGVs and forklift AGVs in the warehouse. Latent AGVs can only realize the horizontal handling of palletized goods, while forklift AGVs can realize vertical or horizontal handling of palletized goods. The research problem is shown in Figure 1. It can be formulated as follows: in a certain planning cycle, there are multiple pallets to be handled in the distribution warehouse generated at different times, divided into horizontal handling tasks and vertical handling tasks according to whether they need to go up and down the shelves. The AGV parking area houses many latent AGVs and forklift AGVs. The scheduling system needs to arrange for the AGVs to visit all tasks’ pickup and delivery points along the shortest path at a limited time and finally return to the AGV parking area. AGV movement process has no conflict with the fixed facilities in the warehouse. Latent AGVs or forklift AGVs can perform horizontal handling tasks, while vertical handling tasks can only be performed using forklift AGVs. This study needs to abstract the warehouse as a grid map, and the fixed facilities are represented as inaccessible grids. The following two core problems are solved: multi-type task assignment based on assignment principle and shortest path planning based on static obstacle avoidance.
In addition to the above description, the following assumptions are considered in this paper:
  • AGV runs at a constant speed without considering the influence of full load/no-load and turning;
  • No additional loss time for AGV operation regardless of AGV starting, braking, forking, and so on;
  • Regardless of the size difference of AGV, the two types of AGV all occupy one grid;
  • AGV charging is not considered;
  • The operating environment is a static network, dynamic situations such as conflicts between AGVs and sudden obstacles are not considered.

3. Mathematical Modeling

Two models are involved in this study. Model 1 is the path planning model, the input is the raster map, and the outputs are the shortest path and distance between any two grids. Model 2 is the task assignment model, the shortest path distance derived from Model 1, the set of AGVs and the set of tasks are the input data, and the output is the schedule of tasks and AGVs.

3.1. Path Planning Model

The solution goal of this stage is to obtain the shortest path and path distance between any two passable grids. The parameters of the path planning model are defined as shown in Table 2.
In order to reduce the computational effort, the definition can be given directly for the particular case where path planning is not required, as shown in Equation (1). When the starting and ending grids are the same, the shortest path is empty, and the path distance is 0. When there is an obstacle grid in the starting or ending point, and the starting and ending points are different, the shortest path is empty, and the path distance is infinite.
D i j = 0 i W , j W , i = j i O   o r   j O , i j
When the start and end points are located in different passable grids, the shortest path is solved by constructing the path planning model.
D i j = m i n g G g G R g g i j × x g x g 2 + y g y g 2 , i , j G , i j
R g g i j × x g x g 1 , i , j , g , g G , i j
R g g i j × y g y g 1 , i , j , g , g G , i j
g G R i g i j = 1 , i , j , g G , i j
g G R g j i j = 1 , i , j , g G , i j
g G R g g i j = g G R g g i j , i , j , g , g G , i j , g i , g j
R g g i j = 0,1 , i , j , g , g G , i j
The Objective Function (2) represents the minimized path distance Dij. Constraints (3) and (4) represent movement constraints, which restrict the AGV to move only in 8 adjacent grids in the grid map and gradually approach the ending point. Constraint (5) indicates that the AGV must start from the starting grid. Constraint (6) indicates that the AGV must reach the ending grid. Constraint (7) indicates the other grids except the starting and ending grids to keep the inflow and outflow equal. Constraint (8) represents variable value constraint.

3.2. Task Assignment Model

The task assignment model has to consider both the efficiency and cost of AGV operation, so the optimization objectives are chosen to minimize task completion time and AGV energy consumption. The parameters of the task assignment model are defined as shown in Table 3.
Optimization Objective 1 is the minimum task completion time, as shown in Equation (9), in which its calculation is related to the AGV moving distance, AGV running speed, and task generation time. Equation (10) represents the time when AGV k starts to perform task m. It is necessary to consider whether the task is generated when AGV reaches the task pickup grid, which can be discussed in two cases: if task m is the first task performed via AGV k, compare the time when AGV reaches the pickup grid of task m along the shortest path from the starting point and the generation time of task m, and take the larger of the two; if task m is the task after the first task executed using AGV k, compare the time of the shortest path from the front task delivery grid to the pickup grid of task m and the generation time of task m, and take the larger of the two. Equation (11) indicates the time for AGV k to end the execution of task m. The value is taken as the time for AGV k to start execution of task m plus the time to reach the task delivery grid along the shortest path from the task m pickup grid. Equation (12) indicates that the task completion time of AGV k is the time to return to the starting point along the shortest path after AGV k has completed the last task assigned.
f 1 = min m a x T k , k K
T k m s = m a x D f k i m V k , t m 1 , k K , m M , Y k m = 1 , m M X m m k = 0 m a x ( T k m e + D j m i m V k ) , t m 1 , k K , m M , m M X m m k = 1
T k m e = T k m s + D i m j m V k , k K , m M , Y k m = 1
T k = T k m e + D j m f k V k , k K , m M , Y k m = 1 , m M X m m k = 0
Optimization Objective 2 is the minimum total energy consumption of the AGVs, as shown in Equation (9). The existing literature has modeled AGV power consumption, and Zhou et al. [4] proposed that AGV power consumption is proportional to AGV weight and travel distance. In this paper, we optimize the existing model by considering the weight difference between the two states of AGV handling pallets and no load. Equation (14) represents the travel distance of AGV k, consisting of three parts. Equation (15) represents the travel distance of AGV k when performing the first task, taking the value of the shortest path distance of “AGV starting point → task pickup point → task delivery point”. Equation (16) represents the travel distance of AGV k when performing intermediate tasks, taking the value of the sum of the shortest path distance of “before the task delivery point → task pickup point → task delivery point”. Equation (17) represents the travel distance of AGV k after performing the last task to return to the starting point, taking the value of the shortest path distance of “task delivery point → AGV starting point”.
f 2 = min k K e k W k + w m M Y k m D i m j m + e k W k D k m M Y k m D i m j m = min k K e k W k D k + e k w m M Y k m D i m j m
D k = D 1 k + D 2 k + D 3 k , k K
D 1 k = D f k i m + D i m j m , k K , m M , Y k m = 1 , m M X m m k = 0
D 2 k = m M m M X m m k D j m i m + D i m j m , k K
D 3 k = D j m f k , k K , m M , Y k m = 1 , m M X m m k = 0
Equation (18) indicates the service relationship constraint, the constraint that each task must be served via an AGV. Equation (19) indicates that the equipment selection constraint that constrains the vertical handling task cannot be completed using latent AGV. Equation (20) indicates that the time window constraint, to avoid congestion in the warehouse, constrains the start time of AGV k execution task m between the generation time and deadline of task m. Equation (21) indicates that the time order constraint, to avoid long waiting times for tasks, constrains the AGV in the execution of multiple tasks, the task with the earlier generation time is executed first. Equations (22) and (23) represent variable value constraints.
k K Y k m = 1 , m M
k K m M Y k m u k p m = 0
t m 1 T k m s t m 2 , k K , m M , Y k m = 1
T k m s T k m s , k K , Y k m = Y k m = 1 , t m 1 t m 1
Y k m , X m m k = 0,1 , k K , m M , m M
Y k m X m m k , k K , m M , m M

4. Solution Algorithms

The grid-map-based multi-type AGV path planning and task assignment are essentially two problems, and we design two algorithms to solve them separately. In the first stage, we use the A-star algorithm combined with the cyclic rule to solve the path planning model to obtain the shortest path planning scheme for AGVs. In the second stage, we use the genetic algorithm to solve the task assignment model with the shortest path of the first stage as known information.

4.1. A-Star Algorithm for Path Planning Model

The A-star algorithm is the most effective heuristic search algorithm to solve the shortest path search problem. The basic idea is to use the evaluation function to determine the search direction. Starting from the starting point and expanding to the surrounding nodes, the cost value of each surrounding node is calculated using the evaluation function, and the least costly node is selected as the next expansion node. This process is repeated until the target point is reached and the final path is generated.
The A-star algorithm’s evaluation function f(n) is calculated, as shown in Equation (24). g(n) indicates the actual distance moved from the starting point to node n, and h(n) indicates the estimated distance from node n to the target point. Since the avoidance between AGV and fixed obstacles must be considered, AGV cannot travel along a straight line, the Manhattan distance is chosen as the heuristic function., as shown in Equation (25).
f n = g n + h n
h n = x 1 x 2 + y 1 y 2
The existing A-star algorithm mainly solves the shortest path between known points A and B. In this paper, we improve the A-star algorithm by setting the cyclic rules to continuously solve the shortest path between any two points in the warehouse. Assuming that there are m elements in the set G of passable grids, the logic of the loop calls the A-star algorithm in this paper is shown in Algorithm 1.
Algorithm 1. Framework for recurring A-star algorithm
 1:
Initialize: Set of passable grids G, position of the starting grid in the set G o, position of the ending grid in the set G d, starting grid number G(o), ending grid number G(o)
 2:
for o = 1:(m−1) do
 3:
while dm do
 4:
 Shortest path search from G(o) to G(d) using A-star algorithm
 5:
d = d + 1
 6:
end while
 7:
end for
 8:
for o = 2:m do
 9:
while d > 0 do
 10:
  Shortest path search from G(o) to G(d) using A-star algorithm
 11:
  d = d − 1
 12:
  end while
 13:
  end for
The steps for solving the shortest path with known starting and ending points using the A-star algorithm are:
Step 1: Add the starting point to the Open list (list of nodes to be examined).
Step 2: Check if the Open list is empty. If empty, the retrieval fails, and the input solution is not feasible; otherwise, execute Step 3.
Step 3: Examine the Open list, find the node n with the smallest value of f(n), and move it to the Close list (list of nodes that have been inspected).
Step 4: Determine whether node n is the target point. If yes, complete the shortest path search and execute Step 7; otherwise, execute Step 5
Step 5: Check the eight squares around node n. If it is not passable or already in the Close list, ignore it and return to Step 2; otherwise, execute Step 6.
Step 6: Determine if the eight squares around node n are in the Open list.
If not, add the surrounding squares to the Open list and set the current node as the parent node, record the values of f(n), g(n), and h(n) of the surrounding squares, and return Step 2.
If in, determine whether the path from the current node to the surrounding nodes already in the Open list is closer (judged via g(n), the smaller, the closer). If closer, set the current node as the parent node and recalculate the values of f(n) and g(n) of the surrounding squares and return Step 2; if not closer, return Step 2 directly.
Step 7: Complete the shortest path search, backtrack the Close list, and record the shortest path and distance of AGV from the starting point to the ending point.
Since the two-stage scheduling method proposed in this paper requires solving the shortest path between any two points in the warehouse first, the computational complexity of the path planning process is related to the number of grids. The number of times the A-star algorithm needs to be called during path planning for a map with n grids is n(n−1)/2; the time complexity of the A-star algorithm is O(nlog(n)) [37]. Therefore, the time complexity of the path planning algorithm proposed in this paper is O(n3log(n)). The time complexity of the path planning algorithm is verified using Matlab2021 on a laptop computer equipped with an AMD R5 5600H processor and 16 GB of RAM. The path planning time was 2.6 s and 70238.9 s for a grid size of 100 and 2500, respectively. As the map size (number of grids) increases, the path planning time increases rapidly. The A-star algorithm can be optimized in the future, thus further improving the path planning efficiency.

4.2. Genetic Algorithm for Task Assignment Model

4.2.1. Encoding Operation

We use the real number coding method to represent the chromosomes. The number position indicates the task number, and the number indicates the AGV number to which the task matches. To meet the time sequence constraint, the tasks are numbered according to the task generation time (the task number generated first is smaller), and the AGV executes the task with the smaller number first. The chromosome shown in Figure 2 represents the AGV task assignment scheme as follows: AGV1 executes tasks 6 and 10 in order, AGV2 executes Task 7, AGV3 executes Tasks 1, 2, 4, and 9 in order, and AGV4 executes Tasks 3, 5 and 8 in order.

4.2.2. Population Initialization

The goal of population initialization is to generate a population number of individuals, and the feasible initial solution in this paper is affected by service relationship constraints, equipment selection constraints, and time window constraints. To generate a better initial population, the initial population is constructed in this paper by the following three steps:
Step 1: Generate the initial solution that satisfies the service relationship constraint and the equipment selection constraint. Firstly, form an all-zero array of task numbers. Secondly, assign vertical handling tasks to forklift AGVs. Thirdly, assign horizontal handling tasks to latent AGVs or forklift AGVs. As shown in Figure 3, suppose there are four tasks in the warehouse, Tasks 1 and 3 are vertical handling tasks, Tasks 2 and 4 are horizontal handling tasks; there are 3 AGVs, in which AGV1 is a latent AGV, AGV2 and 3 are forklift AGVs.
Step 2: Generate the initial solution that satisfies the time window constraint. Determine whether the solution formed in the first step satisfies the time window constraint. If it satisfies, the solution is feasible; if not, it is discarded.
Step 3: Repeat Steps 1 and 2 until the initial solution for the number of populations is generated.

4.2.3. Fitness Function

Fitness is used to judge the quality of individuals in the population. The higher the fitness value, the better the corresponding optimization result. In this paper, to solve the minimum value problem, the inverse of the objective function can be used as the fitness function. The coding method used in this paper cannot ensure that the newly generated individuals meet the time window constraints after crossover and mutation. To solve the problem of violation of constraints simply, this paper uses the penalty function to improve the genetic algorithm.
f i t n e s s = 1 f 1 f 2 + f
f = α , The   time   window   constraint   is   not   satisfied 0 , The   time   window   constraint   is   satisfied
Equation (26) is the formula for calculating the fitness function. Equation (27) indicates that the penalty function f takes a larger positive integer when the task assignment scheme exceeds the time limit, eliminating the scheme.

4.2.4. Selection Operation

The selection operation is selecting good individuals as parents to enter the next generation for genetic operation. In this paper, we choose the binary tournament method. Compare the parent population two by two, select the individuals with more excellent fitness, and put them into the offspring population. Assuming that the population size is N, N comparisons are required, and two individuals are randomly selected for comparison in each cycle. The one with more excellent fitness is selected. There may be duplicates among the newly selected individuals, and only one is retained.

4.2.5. Crossover Operation

In this paper, we use the two-point crossover. Choose the same two positions X1 and X2 of two individuals (A and B) at random, and exchange the parts of X1 and X2 of two individuals, as shown in Figure 4.

4.2.6. Mutation Operation

The second step of changing individual genes is to perform a mutation operation. In this paper, we use positional mutation, that is, we randomly select one gene position X1, and then randomly select one gene position X2 (X1 is not equal to X2) from other genes corresponding to the same task type as X1 to avoid getting individuals that do not satisfy the equipment selection constraint, and exchange the X1 and X2, as shown in Figure 5.

4.2.7. Recombination Operation

The number of offspring individuals obtained after the above selection, crossover, and mutation may be less than the population number, and a certain number of offspring individuals need to be supplemented to complete the update of the parent population. In this paper, we adopt the idea of an elite retention strategy to rank the parent population according to fitness. If there are n individuals in the offspring, and the population number is N, then we select the top (Nn) individuals in the parent population and add them to the offspring population. A new parent population is formed using the above steps as the population for the next selection operation.

5. Analysis of Case Study

To verify the model’s and algorithm’s performance, the A-star algorithm and genetic algorithm are implemented using MATLAB programming to solve the multi-type AGVs path planning and task assignment problems. We construct a real intelligent distribution warehouse operation scenario as a grid map of 50 m in length and 50 m in width, as shown in Figure 6, with the grid codes increasing from left to right and from bottom to top, numbered from 1 to 2500, respectively. White grids are passable passages, and black grids are impassable barriers. The analysis of experimental results, such as path planning, task assignment, and marginal cost, are completed sequentially based on the grid map.

5.1. Parameter Setting

The population size of the genetic algorithm is 100, the number of iterations is 5000, the crossover probability and variation probability are 0.9 and 0.1, respectively, and the penalty function coefficient is 1000. We collected 900 pieces of data on 24 h operation of the above intelligent distribution warehouse, and some of the data are shown in Table 4. The weight of the goods handled in this warehouse is 1 ton. Currently, two latent AGVs and three forklift AGVs are put in to complete the handling tasks, and the AGV parameters are shown in Table 5.

5.2. Analysis of Results

(1)
Path planning results
The calculations are performed in Matlab 2021a. We use the A-star algorithm to solve the path planning model to plan the shortest path between any two grids in the grid map, which finally forms a distance matrix with a scale of 2500 × 2500. Some data are shown in Table 6. There are three cases of the shortest path in the grid map. In the first case, when i and j represent the same grid, the shortest path is empty, and the distance is 0, such as the diagonal elements in the distance matrix. In the second case, when there are impassable grids in i and j, the shortest path is empty, and the distance is infinite, such as the elements in rows and columns 5, 6, 9, and 10 in the distance matrix. In the third case, when both i and j are passable grids, the shortest paths are obtained using the A-star algorithm, and the distances are the length of the shortest path. As shown in Figure 7, the shortest path between grid 1 and grid 7 is {1,2,3,4,55,56,7}, and the distance is 6.8 m.
(2)
Results of task assignment
To verify the effectiveness of the multi-type AGV task assignment model constructed in this paper, we first conduct ablation experiments on the assignment relationship constraint. We select the first ten tasks in Table 4 (Tasks 3 and 5 are vertical handling tasks, and the rest are horizontal handling tasks) and the five AGVs shown in Table 5 (AGV 1, 2, and3 are forklift AGVs, and AGV2 and 4 are latent AGVs), and assign them using the multi-type AGV task assignment model and the multi-AGV task assignment model that without considering Equation (18), respectively. The experimental results are shown in the following Table 7, from which it can be seen that the multi-type AGV task assignment model assigns vertical handling Tasks 3 and 5 to forklift AGV3, and the multi-AGV task assignment model without considering Equation (18), assigns vertical handling Tasks 3 and 5 to latent AGV4 because latent type AGVs consume less energy, and the objective function2 of assigning vertical handling tasks to latent AGVs can achieve better results. However, this aligns differently from the actual situation because the latent AGVs cannot perform the up-and-down motion required for vertical handling tasks. This proves the validity and necessity of the task assignment constraint proposed in this paper, which can make the multi-type AGV task assignment model more compatible with the simultaneous operation of latent AGVs and forklift AGVs.
The genetic algorithm is used to solve the task allocation model with the scale of two latent AGVs, three forklift AGVs, and 900 tasks, and the iteration curves are shown in Figure 8. Both objective functions are constantly decreasing, proving the method’s effectiveness. In addition, planning the 24 h AGV task assignment scheme took about 178.7 s, which proved the practicality and efficiency of the algorithm.
The maximum task completion time (objective 1) is optimized from 23.4510 h to 23.4475 h, and a part of the task assignment scheme is shown in Table 8. It can be found that AGVs usually have arrived at the task pickup point for waiting before task generation, so the time to start performing tasks is limited by the task generation time, and there is little room for optimization of the maximum task completion time. At the same time, this reflects that the AGV waiting time is too long, and the utilization rate is not high, indicating that the number of AGVs put into operation in this warehouse is on the high side, and there may be room for optimization of quantity and type.
The energy consumption of AGVs (Objective 2) decreases from 10.9044 kWh to 6.7981 kWh, which shows a better optimization effect, indicating that the proposed method can greatly reduce the energy consumption of AGVs and the operating cost of the warehouse. To further analyze the effect of AGV type on energy consumption, we obtain the optimal scheduling scheme when the number of iterations is 500, 1000, 2000, 3000, 4000, and 5000. The results are shown in Figure 9 and Figure 10, the total energy consumption of AGVs is gradually optimized as the number of iterations increases, but the energy consumption of latent AGV4 and latent AGV5 gradually expands, indicating that more horizontal handling tasks are assigned to latent AGVs. The reason is that latent AGVs have a lower self-weight and energy consumption factor, and the energy consumption when moving goods across the same distance is lower than that of forklift AGVs. Therefore, it is recommended to use a latent AGV instead of a forklift AGV whenever possible when performing horizontal handling in actual operation.
To confirm the superiority of the multi-type AGV task assignment model in practical applications, we compare it with a common strategy in intelligent distribution warehouses, which is to assign idle AGVs to complete handling randomly, and the results are shown in the figure below. Figure 11 shows that the proposed multi-type AGV task assignment model can reduce the task completion time and total energy consumption by 0.04% and 40.41%, respectively, indicating that the method can optimize both efficiency and cost in practical application. The late generation of the final task mainly limits the low task completion time optimization level. The high optimization level of total energy consumption indicates that the proposed method can significantly reduce the energy loss of AGVs, which aligns with the future development trend of low carbonization.
(3)
Marginal cost analysis
Using the method proposed in this paper to optimize the AGV path and task assignment in the warehouse, AGVs spend much time waiting for task generation, indicating that putting in two latent AGVs and three forklift-type AGVs is too redundant. To improve the utilization rate of AGVs and reduce the cost of purchasing equipment for enterprises, we configured different numbers and types of AGVs located at the same starting point based on the same task conditions and conducted a comparative analysis of the maximum task completion time and AGV energy consumption.
Figure 12 shows the effect of the type and number of AGVs on the task completion time. It can be found that when one forklift AGV is put in, all the tasks in the warehouse can be completed under the condition that the time windows are satisfied. Moreover, when one latent AGV is added, the maximum task completion time can be optimized to a small extent (about the 80 s). The reason is that the latent AGVs run faster, and assigning the latest generated tasks to the latent AGVs can reduce the maximum task completion time.
Figure 13 shows the impact of the type and number of AGVs on the total energy consumption. It can be found that the scheme of “forklift AGV + 1 latent AGV” can significantly reduce the total energy consumption, and the continued investment in latent AGVs has little effect on the optimization of total energy consumption but will lead to a rapid increase in equipment acquisition costs. Therefore, it is recommended that the warehouse reduce the original two latent AGVs to one. When the number of latent AGVs is one, putting in one forklift AGV can already meet the demand of vertical handling tasks, and increasing the number of forklift AGVs has little impact on the total energy consumption, which also leads to a significant increase in cost. Therefore, it is recommended that the warehouse reduce the original three forklift AGVs to one.
According to this study, the AGV configuration of the warehouse can be optimized from the original “2 latent AGVs + 3 forklift AGVs” to “1 latent AGV + 1 forklift AGV”, and the equipment acquisition cost will be significantly reduced. This shows that this study can not only realize the path planning and task assignment of multi-type AGVs, improve operation efficiency, and save equipment energy consumption but also provide a more suitable AGV configuration solution for the warehouse and reduce operation cost.

6. Conclusions

This paper conducts an optimization study on the task assignment and path planning problem for the hybrid operation of latent AGVs and forklift AGVs in intelligent distribution warehouses, proposes a two-stage optimization model containing path planning and task assignment, and proposes the A-star algorithm combining cyclic rules and the genetic algorithm using penalty function. The effectiveness of the proposed method is verified using the 24 h operation data of an intelligent distribution warehouse. Firstly, the task assignment of multiple types of AGVs is realized, and the shortest path without conflict with fixed obstacles is planned for each AGV. Secondly, the original AGV configuration scheme of the warehouse is optimized, further reducing the warehouse’s cost. The limitations of this paper are as follows: (1) this paper’s path planning only considers static obstacle avoidance, temporarily ignoring the dynamic conflicts existing in the warehouse, such as conflicts between AGVs, sudden obstacles, etc.; (2) to simplify the model, temporarily ignoring the impact of AGV charging on AGV driving. Therefore, future research can try to add the AGV charging problem to improve the task assignment model while adding the third stage of optimization, calculating the time window of each AGV passing through each grid when completing the assigned task along the shortest path, and achieving dynamic conflict resolution via speed regulation.

Author Contributions

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

Funding

This research was funded by the National Key R&D Program of China, grant number 2021YFB1407003.

Data Availability Statement

The program code and data that support the plots discussed within this paper are available from the corresponding author upon request.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Lu, W.; Guo, S.; Song, T.; Li, Y. Analysis of Multi-AGVs Management System and Key Issues: A Review. Comput. Model. Eng. Sci. 2022, 131, 1197–1227. [Google Scholar] [CrossRef]
  2. Klei, C.M.; Kim, J. AGV dispatching. Int. J. Prod. Res. 1996, 34, 95–110. [Google Scholar] [CrossRef]
  3. Co, C.G.; Tanchoco, J.M.A. A Review of Research on AGVS Vehicle Management. Eng. Costs Prod. Econ. 1991, 21, 35–42. [Google Scholar] [CrossRef]
  4. Zhou, B.; He, Z. A novel hybrid-load AGV for JIT-based sustainable material handling scheduling with time window in mixed-model assembly line. Int. J. Prod. Res. 2023, 61, 796–817. [Google Scholar] [CrossRef]
  5. Aziez, I.; Côté, J.-F.; Coelho, L.C. Fleet sizing and routing of healthcare automated guided vehicles. Transp. Res. Part E Logist. Transp. Rev. 2022, 161, 19. [Google Scholar] [CrossRef]
  6. Hu, H.; Chen, X.; Wang, T.; Zhang, Y. A three-stage decomposition method for the joint vehicle dispatching and storage allocation problem in automated container terminals. Comput. Ind. Eng. 2019, 129, 90–101. [Google Scholar] [CrossRef]
  7. Tang, H.; Cheng, X.; Jiang, W.; Chen, S. Research on Equipment Configuration Optimization of AGV Unmanned Warehouse. IEEE Access 2021, 9, 47946–47959. [Google Scholar] [CrossRef]
  8. Xu, W.; Guo, S.; Li, X.; Guo, C.; Wu, R.; Peng, Z. A Dynamic Scheduling Method for Logistics Tasks Oriented to Intelligent Manufacturing Workshop. Math. Probl. Eng. 2019, 2019, 7237459. [Google Scholar] [CrossRef]
  9. Udhayakumar, P.; Kumanan, S. Task Scheduling of AGV in FMS Using Non-Traditional Optimization Techniques. Int. J. Simul. Model. 2010, 9, 28–39. [Google Scholar] [CrossRef]
  10. Liu, Y.; Ji, S.; Su, Z.; Guo, D. Multi-objective AGV scheduling in an automatic sorting system of an unmanned (intelligent) warehouse by using two adaptive genetic algorithms and a multi-adaptive genetic algorithm. PLoS ONE 2019, 14, e0226161. [Google Scholar] [CrossRef] [PubMed]
  11. Mousavi, M.; Yap, H.J.; Musa, S.N.; Tahriri, F.; Dawal, S.Z.M. Multi-objective AGV scheduling in an FMS using a hybrid of genetic algorithm and particle swarm optimization. PLoS ONE 2017, 12, e0169817. [Google Scholar] [CrossRef]
  12. Li, J.; Cheng, W.; Lai, K.K.; Ram, B. Multi-AGV Flexible Manufacturing Cell Scheduling Considering Charging. Mathematics 2022, 10, 3417. [Google Scholar] [CrossRef]
  13. Liang, K.; Zhou, L.; Yang, J.; Liu, H.; Li, Y.; Jing, F.; Shan, M.; Yang, J. Research on a Dynamic Task Update Assignment Strategy Based on a “Parts to Picker” Picking System. Mathematics 2023, 11, 1684. [Google Scholar] [CrossRef]
  14. Khatib, O. Real-Time Obstacle Avoidance for Manipulators and Mobile Robots. Int. J. Robot. Res. 1986, 5, 90–98. [Google Scholar] [CrossRef]
  15. Rostami, S.M.H.; Sangaiah, A.K.; Wang, J.; Liu, X. Obstacle avoidance of mobile robots using modified artificial potential field algorithm. Eurasip J. Wirel. Commun. Netw. 2019, 2019, 70. [Google Scholar] [CrossRef]
  16. Szczepanski, R.; Bereit, A.; Tarczewski, T. Efficient Local Path Planning Algorithm Using Artificial Potential Field Supported by Augmented Reality. Energies 2021, 14, 6642. [Google Scholar] [CrossRef]
  17. Matoui, F.; Boussaid, B.; Metoui, B.; Abdelkrim, M.N. Contribution to the path planning of a multi-robot system: Centralized architecture. Intell. Serv. Robot. 2020, 13, 147–158. [Google Scholar] [CrossRef]
  18. Kim, C.W.; Tanchoco, J.M.A. Conflict-Free Shortest-Time Bidirectional AGV Routeing. Int. J. Prod. Res. 1991, 29, 2377–2391. [Google Scholar] [CrossRef]
  19. Chiddarwar, S.S.; Babu, N.R. Conflict free coordinated path planning for multiple robots using a dynamic path modification sequence. Robot. Auton. Syst. 2011, 59, 508–518. [Google Scholar] [CrossRef]
  20. Tang, G.; Tang, C.; Claramunt, C.; Hu, X.; Zhou, P. Geometric A-Star Algorithm: An Improved A-Star Algorithm for AGV Path Planning in a Port Environment. IEEE Access 2021, 9, 59196–59210. [Google Scholar] [CrossRef]
  21. Fransen, K.; van Eekelen, J. Efficient path planning for automated guided vehicles using A* (Astar) algorithm incorporating turning costs in search heuristic. Int. J. Prod. Res. 2021, 61, 707–725. [Google Scholar] [CrossRef]
  22. Faridi, A.Q.; Sharma, S.; Shukla, A.; Tiwari, R.; Dhar, J. Multi-robot multi-target dynamic path planning using artificial bee colony and evolutionary programming in unknown environment. Intell. Serv. Robot. 2018, 11, 171–186. [Google Scholar] [CrossRef]
  23. Zhang, Y.; Wang, F.; Fu, F.; Su, Z. Multi-AGV Path Planning for Indoor Factory by Using Prioritized Planning and Improved Ant Algorithm. J. Eng. Technol. Sci. 2018, 50, 534–547. [Google Scholar] [CrossRef]
  24. Subbaiah, K.V.; Rao, M.N.; Rao, K.N. Scheduling of AGVs and machines in FMS with makespan criteria using sheep flock heredity algorithm. Int. J. Phys. Sci. 2009, 4, 139–148. [Google Scholar]
  25. Zhong, M.; Yang, Y.; Dessouky, Y.; Postolache, O. Multi-AGV scheduling for conflict-free path planning in automated container terminals. Comput. Ind. Eng. 2020, 142, 11. [Google Scholar] [CrossRef]
  26. Gao, H.; Su, H.; Cai, Y.; Wu, R.; Hao, Z.; Xu, Y.; Wu, W.; Wang, J.; Li, Z.; Kan, Z. Trajectory prediction of cyclist based on dynamic Bayesian network and long short-term memory model at unsignalized intersections. Sci. China Inf. Sci. 2021, 64, 172207. [Google Scholar] [CrossRef]
  27. Gao, H.; Qin, Y.; Hu, C.; Liu, Y.; Li, K. An Interacting Multiple Model for Trajectory Prediction of Intelligent Vehicles in Typical Road Traffic Scenario. IEEE Trans. Neural Netw. Learn. Syst. 2021, 1–12. [Google Scholar] [CrossRef] [PubMed]
  28. Krishnamurthy, N.N.; Batta, R.; Karwan, M.H. Developing Conflict-Free Routes for Automated Guided Vehicles. Oper. Res. 1993, 41, 1077–1090. [Google Scholar] [CrossRef]
  29. Desaulniers, G.; Langevin, A.; Riopel, D.; Villeneuve, B. Dispatching and conflict-free routing of automated guided vehicles: An exact approach. Int. J. Flex. Manuf. Syst. 2003, 15, 309–331. [Google Scholar] [CrossRef]
  30. Murakami, K. Time-space network model and MILP formulation of the conflict-free routing problem of a capacitated AGV system. Comput. Ind. Eng. 2020, 141, 106270. [Google Scholar] [CrossRef]
  31. Nishida, K.; Nishi, T. Dynamic Optimization of Conflict-Free Routing of Automated Guided Vehicles for Just-in-Time Delivery. IEEE Trans. Autom. Sci. Eng. 2022, 1–16. [Google Scholar] [CrossRef]
  32. Nishi, T.; Hiranaka, Y.; Grossmann, I.E. A bilevel decomposition algorithm for simultaneous production scheduling and conflict-free routing for automated guided vehicles. Comput. Oper. Res. 2011, 38, 876–888. [Google Scholar] [CrossRef]
  33. Yang, Y.; Zhong, M.; Dessouky, Y.; Postolache, O. An integrated scheduling method for AGV routing in automated container terminals. Comput. Ind. Eng. 2018, 126, 482–493. [Google Scholar] [CrossRef]
  34. Ji, S.; Luan, D.; Chen, Z.; Guo, D. Integrated scheduling in automated container terminals considering AGV conflict-free routing. Transp. Lett. Int. J. Transp. Res. 2021, 13, 501–513. [Google Scholar] [CrossRef]
  35. Hu, Y.; Dong, L.; Xu, L. Multi-AGV dispatching and routing problem based on a three-stage decomposition method. Math. Biosci. Eng. 2020, 17, 5150–5172. [Google Scholar] [CrossRef]
  36. Liang, C.; Zhang, Y.; Dong, L. A Three Stage Optimal Scheduling Algorithm for AGV Route Planning Considering Collision Avoidance under Speed Control Strategy. Mathematics 2023, 11, 138. [Google Scholar] [CrossRef]
  37. Chiang, C.H.; Chiang, P.J.; Fei, J.C.-C.; Liu, J.S. A comparative study of implementing fast marching method and A* search for mobile robot path planning in grid environment: Effect of map resolution. In Proceedings of the 2007 IEEE Workshop on Advanced Robotics and Its Social Impacts, Hsinchu, Taiwan, 9–11 December 2007; pp. 1–6. [Google Scholar] [CrossRef]
Figure 1. Problem description.
Figure 1. Problem description.
Mathematics 11 02802 g001
Figure 2. Chromosome diagram of AGV task assignment.
Figure 2. Chromosome diagram of AGV task assignment.
Mathematics 11 02802 g002
Figure 3. Initial solution generation process to satisfy service relationship constraints and equipment selection constraints.
Figure 3. Initial solution generation process to satisfy service relationship constraints and equipment selection constraints.
Mathematics 11 02802 g003
Figure 4. Crossover operation.
Figure 4. Crossover operation.
Mathematics 11 02802 g004
Figure 5. Mutation operation.
Figure 5. Mutation operation.
Mathematics 11 02802 g005
Figure 6. Grid map of the warehouse.
Figure 6. Grid map of the warehouse.
Mathematics 11 02802 g006
Figure 7. The shortest path from Grid 1 to Grid 7.
Figure 7. The shortest path from Grid 1 to Grid 7.
Mathematics 11 02802 g007
Figure 8. (a) Iterative curve of the product of Objective 1 and Objective 2; (b) Iteration curves of Objective 1 and Objective 2, respectively.
Figure 8. (a) Iterative curve of the product of Objective 1 and Objective 2; (b) Iteration curves of Objective 1 and Objective 2, respectively.
Mathematics 11 02802 g008
Figure 9. Change in total energy consumption of AGVs.
Figure 9. Change in total energy consumption of AGVs.
Mathematics 11 02802 g009
Figure 10. Change in the energy consumption ratio of each AGV.
Figure 10. Change in the energy consumption ratio of each AGV.
Mathematics 11 02802 g010
Figure 11. Multi-type AGV task assignment model versus random assignment.
Figure 11. Multi-type AGV task assignment model versus random assignment.
Mathematics 11 02802 g011
Figure 12. Impact of AGV type and number on task completion time.
Figure 12. Impact of AGV type and number on task completion time.
Mathematics 11 02802 g012
Figure 13. Impact of AGV type and number on total energy consumption.
Figure 13. Impact of AGV type and number on total energy consumption.
Mathematics 11 02802 g013
Table 1. Studies related to AGV task assignment.
Table 1. Studies related to AGV task assignment.
Optimization ObjectiveSolution AlgorithmsOther Factors
Minimum Completion timeMinimum Number of AGVsMaximum AGV
Utilization
Genetic AlgorithmAnt Colony AlgorithmParticle Swarm OptimizationChargingLayout
Tang et al. [7]——————————
Xu et al. [8]——————
Udhayakumar et al. [9]————————
Liu et al. [10]————————
Mousavi et al. [11]——————
Li et al. [12]——————————
Liang et al. [13]———— ——————
Table 2. The parameters of the path planning model.
Table 2. The parameters of the path planning model.
SymbolDescription
Set
W Set   of   all   grids ,   W = G O
G Set of passable grids
O Set of obstacle grids
Parameter
x g , y g X - coordinate   value   and   Y - coordinate   value   of   grid   g
D i j The   distance   of   the   path   of   the   AGV   from   the   starting   grid   i   to   the   ending   grid   j
Variable
R g g i j Decision   variables .   Takes   1   if   the   path   of   AGV   from   the   starting   grid   i   to   the   ending   grid   j   passes   through   two   different   grids   g   and   g consecutively and 0 otherwise.
Table 3. The parameters of the task assignment model.
Table 3. The parameters of the task assignment model.
SymbolDescription
Set
M Set of tasks
K Set of AGVs
Parameter
i m Pickup grid number of task m
j m Delivery grid number of task m
p m Type   of   task   m .   If   p m = 1 ,   it   means   vertical   handling   task .   If   p m = 0 , it means the horizontal handling task
t m 1 Generation time of task m
t m 2 Deadline of task m
u k Type   of   AGV   k .   If   u k = 1 ,   it   means   latent   AGV .   If   u k = 0 , it means forklift AGV
f k Starting grid number of AGV k
V k Running speed of AGV k, related to the type of AGV, m/s
D i m j m Path   distance   from   pickup   grid   i m   to   delivery   grid   j m , obtained from the path planning model, m
e k Power consumption factor of AGV k, related to the type of AGV, kWh/(s·tons)
W k Weight of AGV, related to AGV type, tons
w Weight of goods, tons
D k Path distance of AGV k completing all assigned tasks, m
T k Time for AGV k to complete the assigned task, s
T k m s The   time   when   AGV   k   starts   task   m ,   i . e . ,   the   time   when   it   is   ready   to   leave   the   pickup   grid   i m
T k m e The   time   when   AGV   k   finishes   task   m ,   i . e . ,   the   time   when   it   is   ready   to   leave   delivery   grid   j m
Variable
X m m k Decision variables. Takes 1 if AGV k performs task m and task m’ consecutively and 0 otherwise
Y k m Decision variables. Takes 1 if task m is executed using AGV k and 0 otherwise.
Table 4. Task parameters of the intelligent distribution warehouse.
Table 4. Task parameters of the intelligent distribution warehouse.
Task NumberTask TypePickup GridDelivery GridTask Generation timeTask Deadline
1Horizontal handling task15100:06:140:08:14
2Horizontal handling task78250:06:140:08:14
3Vertical handling task139630:08:060:10:06
4Horizontal handling task193710:08:590:10:59
5Vertical handling task259790:08:590:10:59
898Horizontal handling task32158023:23:4723:27:47
899Vertical handling task25232523:23:4723:27:47
900Horizontal handling task49144823:25:4723:29:47
Table 5. AGV parameters of the intelligent distribution warehouse.
Table 5. AGV parameters of the intelligent distribution warehouse.
AGV NumberAGV TypeStarting GridRunning Speed
(m/s)
Weight
(t)
Power Consumption Factor (Wh/m·t)
1forklift AGV21031.20.7550.102
2forklift AGV17031.20.7550.102
3forklift AGV12531.20.7550.102
4latent AGV8531.50.1650.043
5latent AGV4531.50.1650.043
Table 6. Distance matrix (partial).
Table 6. Distance matrix (partial).
DistanceGrid1Grid2Grid3Grid4Grid5Grid6Grid7Grid8Grid9Grid10Grid2500
Grid10123InfInf6.87.8InfInf86
Grid21012InfInf5.86.8InfInf83.2
Grid32101InfInf4.85.8InfInf82.2
Grid43210InfInf3.84.8InfInf81.2
Grid5InfInfInfInf0InfInfInfInfInfInf
Grid6InfInfInfInfInf0InfInfInfInfInf
Grid76.85.84.83.8InfInf01InfInf78.2
Grid87.86.85.84.8InfInf10InfInf77.2
Grid9InfInfInfInfInfInfInfInf0InfInf
Grid10InfInfInfInfInfInfInfInfInf0Inf
Grid25008683.282.281.2InfInf78.277.2InfInf0
Table 7. The results of ablation experiments on the assignment relationship constraint.
Table 7. The results of ablation experiments on the assignment relationship constraint.
TaskMulti-Type AGV Task Assignment ModelMulti-AGV Task Assignment Model without Considering Equation (18)
Task 1AGV5AGV4
Task 2AGV5AGV5
Task 3AGV3AGV4
Task 4AGV5AGV4
Task 5AGV3AGV4
Task 6AGV5AGV4
Task 7AGV5AGV4
Task 8AGV4AGV4
Task 9AGV5AGV5
Task 10AGV4AGV4
Task Completion Time (h)0.58390.5839
Total Energy Consumption (KW·h)0.05220.0372
Table 8. Task assignment scheme (partial).
Table 8. Task assignment scheme (partial).
Task NumberAssigned AGVTask Generation TimeTask DeadlineAGV Arrival TimeTask Start TimeTask End Time
150.10390.13720.00200.10390.1066
240.10390.13720.00340.10390.1094
330.13500.16830.00700.13500.1394
430.14970.18310.14460.14970.1515
530.14970.18310.15370.15370.1584
898523.396423.463123.321723.396423.4023
899223.396423.463122.839123.396423.4135
900523.429723.496423.410323.429723.4475
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

Jiang, Z.; Zhang, X.; Wang, P. Grid-Map-Based Path Planning and Task Assignment for Multi-Type AGVs in a Distribution Warehouse. Mathematics 2023, 11, 2802. https://doi.org/10.3390/math11132802

AMA Style

Jiang Z, Zhang X, Wang P. Grid-Map-Based Path Planning and Task Assignment for Multi-Type AGVs in a Distribution Warehouse. Mathematics. 2023; 11(13):2802. https://doi.org/10.3390/math11132802

Chicago/Turabian Style

Jiang, Zhuoling, Xiaodong Zhang, and Pei Wang. 2023. "Grid-Map-Based Path Planning and Task Assignment for Multi-Type AGVs in a Distribution Warehouse" Mathematics 11, no. 13: 2802. https://doi.org/10.3390/math11132802

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