Robotics and Computer Integrated Manufacturing 63 (2020) 101915
Contents lists available at ScienceDirect
Robotics and Computer Integrated Manufacturing journal homepage: www.elsevier.com/locate/rcim
Highly-scalable traffic management of autonomous industrial transportation systems
T
Ivica Draganjac , Tamara Petrović, Damjan Miklić, Zdenko Kovačić, Juraj Oršulić ⁎
LARICS Laboratory, Faculty of Electrical Engineering and Computing, University of Zagreb, Croatia
ARTICLE INFO
ABSTRACT
Keywords: Multi-robot systems Decentralized control Motion coordination Path planning Autonomous warehousing Automated guided vehicles
In this paper, we present a novel method for highly-scalable coordination of free-ranging automated guided vehicles in industrial logistics and manufacturing scenarios. The primary aim of this method is to enhance the current industrial state-of-the-art multi-vehicle transportation systems, which, despite their long presence on the factory floor and significant advances over the last decades, still rely on a centralized controller and predetermined network of paths. In order to eliminate the major drawbacks of such systems, including poor scalability, low flexibility, and the presence of a single point of failure, in the proposed control approach vehicles autonomously execute their assigned pick-up and delivery operations by running a fully decentralized control algorithm. The algorithm integrates path planning and motion coordination capabilities and relies on a two-layer control architecture with topological workspace representation on the top layer and state-lattice representation on the bottom layer. Each vehicle plans its own shortest feasible path toward the assigned goal location and resolves conflict situations with other vehicles as they arise along the way. The motion coordination strategy relies on the privatezone mechanism ensuring reliable collision avoidance, and local negotiations within the limited communication radius ensuring high scalability as the number of vehicles in the fleet increases. We present experimental validation results obtained on a system comprising six Pioneer 3DX robots in four different scenarios and simulation results with up to fifty vehicles. We also analyze the overall quality of the proposed traffic management method and compare its performance to other state-of-the-art multi-vehicle coordination approaches.
1. Introduction Factory logistics play an important role in any production process, affecting production efficiency and energy consumption. As raw materials and final products need to constantly flow between the factory warehouse and the production shop floor, any bottleneck and inefficiency in logistics decreases the productivity level of the whole factory. A key technology that has long been recognized as a practical and reliable solution for improving the efficiency of material handling operations in industrial environments are systems with multiple automated guided vehicles or multiAGV systems. Characterized by their capability to continuously, safely, and efficiently transport different kinds of load without human intervention, multi-AGV systems have become an essential part of many automated manufacturing and warehousing facilities. Notwithstanding the recent very successful examples of large-scale use of autonomous mobile delivery vehicles such as Kiva Systems [1], many of today’s manufacturing and logistics processes are still largely dependent on manually operated vehicles [2]. As the Kiva example
⁎
shows, using autonomous vehicles to automate segments of the logistics chain can bring significant gains in production efficiency [3]. Furthermore, as manually operated vehicles are still responsible for a large fraction of product damages and work-related injuries, full automation of some logistics operations is highly desirable, as it increases both product quality and worker safety. However, there are many open challenges that need to be addressed in order to pave the way for a wider adoption of AGVs in factory logistics. Many key parts of the real-world deployment phase are currently ad-hoc and manual, such as the design of AGV paths, which is a time consuming and error prone activity. Scalability, automatic resolution of conflicts, deadlock and livelock situations are additional key issues still requiring more robust and efficient algorithms. Finally, safety measures preventing collisions between AGVs and other moving objects [4], as well as cooperation with human workers in shared workspaces [5], are issues of paramount importance for enabling the adoption of multi-AGV systems in a wider range of application areas. For in-depth analysis of open issues and development directions in the field, the reader is referred to [6] and [2].
Corresponding author. E-mail address:
[email protected] (I. Draganjac). URL: http://larics.fer.hr/ (I. Draganjac).
https://doi.org/10.1016/j.rcim.2019.101915 Received 27 July 2018; Received in revised form 23 November 2019; Accepted 24 November 2019 Available online 13 December 2019 0736-5845/ © 2019 Elsevier Ltd. All rights reserved.
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Taking all of the above into account, it is no surprise that there has been a lot of recent research activity in the field of autonomous logistics. An early report proposing the use of free-range routing, as opposed to manual path design that is still prevalent in the industry, is [7]. Motivated by the problem of AGVs transporting containers in Rotterdam harbour, the authors implemented an optimization method based on dynamic programming, which has been validated in simulations with up to 14 vehicles. The Safe AUtonomous NAvigation (SAUNA) framework [6] aims to be a complete and efficient system for automated management of fleets of autonomous ground vehicles in industrial sites. It employs constraint-based paradigm to provide a modular approach to multi-vehicle coordination based on least commitment. Another approach based on Temporal Logic Constrains [8] has been shown to provide formal correctness guarantee. Authors in [9] describe the technological developments within the Pan Robots project, aimed at increasing the autonomy and efficiency of AGVs used for industrial logistics in environments shared with human operators. The aforementioned approaches use a centralized architecture in order to facilitate analytical tractability and provide optimality guarantees. However, the biggest drawback of centralized approaches is the lack of scalability, as computational complexity tends to grow exponentially with the number of vehicles and size of the environment. Therefore, these methods are currently not applicable to systems exceeding tens of vehicles. To overcome the limitations of the centralized approaches, several authors have proposed methods with varying degrees of decentralization. A distributed protocol for motion coordination in free-range vehicular systems, based on Resource Allocation Systems (RAS) theory is described in [10]. It assumes limited communication range and formally guarantees collision-free mission execution and liveliness, i.e., that all missions will be completed in finite time. The approach is theoretically very well developed, but its practicality has not been validated by simulations or experimentally. The authors in [11] propose a hierarchical traffic control method for partially decentralized coordination of multi-AGV systems in industrial environments. It features a two layer architecture, with topological relationships between areas encoded in the top layer. The bottom layer provides decentralized coordination by local negotiation on top of centralized information encoded in the fixed routes. For validation, simulations have been performed in Matlab with up to 20 vehicles. In [12], a decentralized task assignment and path coordination method is described, capable of avoiding deadlocks and collisions. It uses a partitioning of the environment into zones and uses decentralized consensus for coordination. Simulation results with nine vehicles are presented. Despite significant advances in the field of autonomous and intelligent road vehicles [13], industrial AGVs still rely on centralized controllers and predefined paths, which we see as the two main causes of low scalability and low flexibility to changes in the layout. Although centralized control approaches facilitate maximization of system throughput by ensuring optimal solutions, as presented in [14,15], their computational complexity is a huge limitation when it comes to increasing the number of vehicles in the fleet. Consequently, today’s practical multi-AGV control systems are rarely capable of controlling more than 10–15 vehicles moving on a carefully designed network of paths. Furthermore, forcing the vehicles to move along predetermined paths drastically restricts their mobility and autonomy, and increases deployment and maintenance costs since a path network must be designed and maintained in case of any change in the layout. On the other hand, the growing needs of today’s global market constantly impose new challenges on the manufacturing and warehousing aspects of the supply chain, requiring more and more AGVs on the rapidly-changing factory floor, which can only be fulfilled by highly-scalable and flexible control approaches. Our solution to this problem is based on hypothesis that making vehicles fully autonomous, i.e. providing them with capabilities for planning their own paths within the entire obstacle-free space, and negotiating conflict situations only with the neighboring
vehicles in their local area, would significantly reduce computational complexity and consequently increase the overall system scalability and flexibility. Based on the above considerations, in this paper we present a method that combines algorithms for decentralized motion coordination and lattice-based path planning into a standalone control stack enabling fully autonomous vehicle operation. The decentralized nature and low computational complexity of the coordination algorithm ensures high scalability as the number of vehicles in the fleet increases. On the other hand, the lattice-based path planning ensures lower energy consumption due to optimal vehicle paths, as well as lower deployment costs and higher flexibility to changes in the environment, since no a priori path design is needed. Similarly to some other approaches, the control algorithm is based on a two-layer architecture, with the top layer operating only on topological primitives identified in the environment, and the bottom layer operating on the vehicle configuration space. Any conflicts that may occur during mission execution are solved by direct negotiation between the involved vehicles, in a way which guarantees deadlock-free system behavior. Conflict resolution is based on a vehicle priority scheme and results in temporary stopping or retreating of the lower-priority vehicles taking part in the conflict. Safe avoidance maneuvers during conflict resolution are ensured by the private-zone mechanism, which is thoroughly described and analyzed in our previous work [16]. In this paper, we provide a high-level description of the proposed traffic management method and present extensive simulation and experimental validation results confirming its correctness and high scalability properties. We focus only on the traffic management aspect of multi-AGV systems, involving the problems of planning and coordinating vehicle motions, while all other problems, including navigation, localization, workspace mapping, etc., are beyond the scope of this paper. The paper is organized as follows. In Section 2 we introduce the notation and formalize the multi-AGV control problem. Section 3 describes the architecture of the decentralized control algorithm. In Section 4 we analyze the high-level stability of the control algorithm. The relevant details of our ROS-based implementation are presented in Section 5. Validation results and performance metrics analyzing system throughput, efficiency and scalability are presented and discussed in Section 6. Concluding remarks are given in Section 7. 2. Problem statement We consider the problem of coordinating a fleet of N AGVs { 1, …, N } operating in a bounded 2-D workspace SE (2) with obstacle region . Our primary objective is to design a traffic management algorithm that enhances the current state-of-the-art multiAGV systems, based on centralized controllers and fixed paths, by ensuring high scalability and eliminating both the single point of failure and the need for a priori path design. In order to fulfill the given objective we focus on the design of a i, decentralized control algorithm executing on each vehicle i {1, …, N }, and providing the vehicles with capabilities for autonomous execution of received missions {m1i , …, mki } . We assume that each vehicle i dynamically receives one mission at a time from a high-level task dispatcher, the design of which is outside the scope of this work. The mission mij contains information about the goal configuration T
qiG, j = xGi , j , yGi , j ,
i G, j
that has to be reached by the vehicle
i
in order
to perform its j th pick-up/delivery operation. If a new mission is received during the execution of a previously received mission, it is buffered on the vehicle for the future execution based on the first-in first-out principle. The set of all possible configurations of vehicle i with respect to the fixed coordinate system constitutes the configuration space i . The current pose of vehicle i in its configuration space i is denoted by the vector qi = [x i , y i , i]T . The ordered set of all 2
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 1. A sketch of the multi-AGV traffic management problem. Each vehicle i should be able to autonomously determine its shortest feasible path toward the given goal location qiG and reliably resolve different conflict situations with other vehicles as they arise along the way.
individual vehicle configurations C = [q1, …, qN ] denotes the current state of the fleet. By autonomous mission execution we assume that vehicle i , upon executing its mission mij , starts executing its next mission mij + 1 in two sequential steps: (i) by obtaining an optimal obstacle-free path π, i.e. i( ) = , toward the next goal location qiG, j + 1; (ii) by coordinating its motion with other vehicles along the path in a collisionfree, deadlock-free, and livelock-free manner. A sketch depicting the traffic management problem in a fleet of AGVs autonomously moving with obstacle region toward their goal configurations in workspace = k k , is shown in Fig. 1 The list of relevant symbols is given in Table 1. We assume that each vehicle is provided with a map of the workspace and a localization system providing an accurate estimate of the vehicle’s current pose within the map. Measurement disturbances and environment uncertainties are not explicitly considered in this work, i.e., there is an implicit safety margin by which we increase the vehicle footprint when planning collision-free paths. As long as the measurement error does not exceed this safety margin, it does not have any adverse effect on the coordination algorithm. We provide an in-depth analysis of measurement accuracy in our previous work [17]. We also assume that each vehicle is equipped with an on-board computer executing the control algorithm and with a communication device enabling data exchange with other vehicles within the required communication radius.
3. Decentralized traffic management In this section we provide a conceptual description of the designed traffic management algorithm. Our main objective is to make the vehicles fully autonomous, i.e. each vehicle must be able to autonomously determine its own path toward the current mission’s goal location and to coordinate its motions with other vehicles operating in the shared workspace in order to avoid collisions and deadlocks. Accordingly, our control algorithm is running on each vehicle in the system and it integrates modules for autonomous path planning and motion coordination. Both modules are based on a two-layer architecture, with the top layer operating on the topological primitives and the bottom layer operating on the underlying state lattice space. The path planning module provides a solution to the path planning problem in two steps. In the first step the top-layer algorithm calculates a vehicle route based on the topological representation of the workspace, while in the second step the bottom-layer algorithm determines the shortest feasible path along the topological route. In order to ensure safe motions along the calculated paths, the motion coordination module performs distributed allocation of the required spatial resources on both topological and state-lattice layers and resolves conflict situations as they occur, as further explained in Section 3.4. 3.1. Topological environment representation The vast majority of manufacturing and warehousing facilities in which multi-AGV systems are deployed contain well structured layouts with easily identifiable areas reserved for static infrastructure, such as conveyors, workstations, palletizers and shelves. Moreover, in most cases it is easy to detect and differentiate larger open spaces, which may also contain static obstacles, from the narrow spaces such as corridors connecting different rooms or neighboring open spaces within the same facility. Considering these observations, it becomes clear that such environments can be easily represented in a topological way, with topological elements representing different bounded areas in the working layout. The topological representation of the working environment in this work is based on the following topological primitives, which we refer to as sectors:
Table 1 List of symbols. Symbol
Definition the ith vehicle
i
N
total number of AGVs in the system bounded 2-D workspace obstacle region in the workspace the configuration space of vehicle
i
i
mij
the jth mission of vehicle
qi
the current configuration of vehicle
qiG,j
the goal configuration of vehicle
i(
)
i
the space occupied by vehicle
i i
i
in the configuration space
while executing the mission
i
mij
while moving along the path π
3
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 2. Decomposing the workspace into sectors and representing the sector inter-connectivity information by a directed graph.
• Terminals - open spaces that may also contain obstacles. • Corridors - narrow passages between two terminals. • Docking stations - parts of the workspace where vehicles perform loading and unloading operations. • Parking stations - parts of the workspace reserved for parking and
A1) A connection may exist only between different types of sectors. A2) Each parking station, docking station or corridor may be accessed only from a terminal. A3) Any two terminals may be connected exclusively via corridors. A4) There is a route from each sector to any other sector in the layout, i.e. the graph representing workspace sectors is a strongly connected directed graph. A5) The total number of parking stations in the layout is greater than or equal to the total number of vehicles in the system.
charging of vehicles.
Fig. 2a depicts an example of the workspace with highlighted sector boundaries. Once the sector boundaries have been identified, a directed graph indicating connections between adjacent sectors is constructed (Fig. 2b). The nodes of this graph correspond to sectors, while its edges represent allowed vehicle transitions between adjacent sectors. As can be noted in Fig. 2b, only one-way corridors are considered in this work. This restriction has been introduced with the aim of minimizing the required vehicle communication radius, as further explained in Section 3.5. It should be emphasized that this topological restriction does not necessarily imply a practical constraint, since each corridor having at least double vehicle width can be topologically represented by two one-way corridors with opposite traffic directions. Additionally, we make the following assumptions on the sectoral representation of the working layout:
3.2. Top-layer route determination By encoding the sector inter-connectivity information, the topological graph of the environment allows for the determination of a route comprising a sequence of sectors the vehicle should pass through while moving from its initial sector to the current mission’s destination sector. The determination of a topological route relies on Dijkstra’s graph search algorithm. In the context of Fig. 2, the topological routes for the vehicle initially located at the parking station P2, upon assignment of the following missions: m1: pick-up the load at the docking station D2; m2: deliver the load at the docking station D5; m3: return to parking station P2, would be {P2 → T1 → D2}, {D2 → T1 → C1 → T2 → D5} and 4
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
{D5 → T2 → C2 → T1 → P2}, respectively. When dealing with more complex layouts in which more than one route between a particular pair of initial and destination sectors exist, a weighted topological graph encoding sector lengths is used to allow for the determination of the shortest route. Once the topological route has been obtained by the top-layer algorithm, it is passed down to the bottom-layer algorithm, which then obtains the shortest feasible obstacle-free path on the calculated route using the state-lattice planning approach.
For the purpose of motion primitive calculation, we consider the model of a vehicle actuated in curvature in the distance domain while moving in the plane, described by the following system of nonlinear equations:
d x (s ) = cos (s ) ds d y (s ) = sin (s ) ds d ( s ) = (s ) ds
3.3. Bottom-layer path planning Path planning methods implemented in most practical multi-AGV systems calculate the path as a sequence of simple segments, i.e. virtual straight lines or arcs connecting two neighboring discrete states in the predetermined path network (guidepath). In order to avoid the restrictions imposed by predetermined paths and to additionally increase overall system autonomy and flexibility, in this work we consider a freeranging motion scheme in which vehicles exploit the entire obstacle-free workspace. Besides free-ranging properties and obstacle avoidance, another important requirement is related to path feasibility. More specifically, the path planning algorithm should ensure that AGVs, which fall into the group of non-holonomic vehicles [18], are able to accurately follow the calculated paths due to their differential constraints. Different approaches to path planning under differential constraints have been proposed in literature, including sampling-based methods such as Rapidly Exploring Random Trees (RRT) [19,20] and Probabilistic Roadmaps (PRM) [21], symbolic methods [22], and methods based on the use of state lattices [23,24]. Due to its practicality, in this work we consider the lattice-based path planning approach. The state lattice, introduced in [23], represents a sampled vehicle state space that encodes feasible motions by design. Path planning based on the use of a state lattice can be divided into state lattice construction and searching for a path in the constructed lattice using efficient graph search algorithms.
(1)
In order to generate a motion primitive between two different sampled states a cubic polynomial of the distance variable (polynomial spiral) is used as the curvature function: (2)
(s ) = a + bs + cs 2 + ds3
Let (x0, y0, θ0, κ0) and (x1, y1, θ1, κ1) be the initial and the goal vehicle states. The generation of motion primitives then involves solving the BVP given by the following system of equations: 0 1
= (0) = (s1)
x1 = x (s1) = x 0 + y1 = y (s1) = y0 + 1
= (s1) =
0
s1 0 0
s1
cos (s ) ds sin (s ) ds
+ as1 +
bs12 cs 3 ds 4 + 1 + 1 2 3 4
(3)
where s1 is a motion primitive length. This problem is solved by using numerical methods [25], and only motion primitives satisfying vehicle steering limitations are considered. The set of motion primitives that has been generated for the path planning purpose in this work is shown in Fig. 3a. Since state sampling is done uniformly over x and y, the calculated motion primitives are position invariant and can easily be translated to any other discrete state in the lattice space. Accordingly, the generated motion primitives repeat at regular intervals, i.e. they connect each discrete state in the vehicle state space to its neighboring states, forming a lattice. The number of neighboring states that each state is connected to, as well as the state sampling density is usually chosen based on the size of the vehicle, the size of workspace, and vehicle steering limitations [26]. In this work, a state lattice with a total of 336 motion primitives connecting each discrete location to 48 neighboring discrete locations within the square-bounded neighborhood ρ has been generated. In order to ensure the proper functioning of the coordination algorithm described in Section 3.4, we put additional constraints on the state lattice generation process. More specifically, the generated state lattice possesses the collision-avoidability property, introduced in [16].
3.3.1. State lattice construction The goal of state lattice construction is to sample the vehicle state space in a way that captures the mobility of the vehicle while intrinsically taking into account its kinematic constraints. It is an offline process that is conducted only once for a particular type of vehicle, usually in the predeployment phase. In this process the vehicle coordinates (x, y) and heading θ are uniformly sampled over the bounded area ρ in free space and the interval [0, 2π], respectively. The resulting set of all sampled vehicle orientations is denoted by Θ. In the second step, the boundary value problem (BVP) is solved in order to generate a set of feasible motion T
, to its primitives, connecting each sampled state q = [0, 0, ] , reachable neighboring states in a discrete, bounded neighborhood ρ. This is done in a way that ensures continuity of vehicle state variables, steering angle and path curvature across the sampled states.
Fig. 3. The constructed state lattice. 5
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Basically, the resolution of a state lattice satisfying this property guarantees that any conflict situation between two vehicles, moving in free space, can be resolved by one vehicle retreating to one of its adjacent states via only one motion primitive.
opt
= arg min i
g (pj ) pj
i
(4)
In this work, the cost function g(p), associated with each motion primitive p, is calculated by multiplying the total length of p by an empirically adjusted cost factor penalizing backwards motions, i.e. g (p) = k·|pj |, where |pj| denotes the arc lenght of pj, while k = 1 for forward motion and k = 2 for backward motion. Clearly, such a cost function enables the determination of the shortest path with minimum backward motions, which is a common requirement in industrial applications, primarily due to safety reasons. Besides its cost, the consideration of a certain motion primitive as a candidate for the path segment in the resulting path is a subject to the following constraints:
3.3.2. Private zones on the state lattice Having constructed the state lattice, an additional offline step is conducted to enable the implementation of the motion coordination strategy described in Section 3.4. In this step, the vehicle workspace is represented by cells, which in our case have dimensions 5 cm × 5 cm, and then the so-called private zones, introduced and thoroughly described in our previous work [16], are constructed. A private zone (q) is a subregion of the discretized obstacle-free space, containing all cells being occupied by the vehicle footprint while moving along the motion primitives connecting the discrete state q to all neighboring discrete states in lattice space satisfying the collision-avoidability property. Since for each discrete orientation a different set of motion primitives connecting each state (x, y, θ′) to other states on the lattice exists, a distinct private zone for each orientation is constructed. In this work, a state lattice with π/8 orientation resolution is used, which, due to the state lattice symmetry, yields four differently shaped private zones, shown in Fig. 4. In our implementation, each private zone is represented by indices of its cells, assuming the center of the zone is positioned at state (0,0). Such representation allows for easy identification of the private zone regions around any discrete state in the workspace, which is an important prerequisite for the implementation of our motion coordination strategy, as further explained in Section 3.4. The fundamental property of each private zone is that it guarantees the necessary physical space to which a vehicle, being positioned at the center of the private zone, can retreat via only one motion primitive in order to avoid collision with another vehicle moving along an arbitrary shortest path passing through the zone. For more information on the collision-avoidability property and the private zone construction process, the reader is referred to [16].
(pj )
=
(5)
(qj)
=
(6)
(qj + 1)
=
(7)
The constraint given by Eq. (5) requires that the candidate path segment pj provides an obstacle-free motion for a particular type of vehicle. This constraint is evaluated by checking the availability of all cells (pj ) that become occupied by the vehicle while moving along the path segment pj. The other two constraints (Eqs. (6) and (7)) require that obstacle-free private zones can be constructed at both discrete states connected by the candidate path segment, which is a necessary precondition for the implementation of the private-zone-based coordination mechanism described in Section 3.4.2. These constraints are evaluated by checking the availability of cells within the assumed private zone regions around the states qj and qj + 1. In case a collision with an obstacle has been detected during the evaluation of constraints (Eqs. (5)–(7)), the evaluated motion primitive is excluded from the set of candidate path segments. In order to determine an optimal sequence of motion primitives, i.e. path πopt, the constructed state lattice is represented as a directed graph = , . Each node v represents a valid vehicle pose, while each edge e represents a feasible motion. In this way, the path planning problem is reduced to a graph search problem, and thus, any graph search algorithm can be used to find a path between two arbitrary sampled states. In this work, we have implemented an A* search algorithm that uses Euclidean distance as the heuristic function. Accordingly, calculation of the candidate path segment costs and evaluation of introduced constraints are performed inside the A* algorithm. This procedure yields an obstacle-free feasible path, which is optimal with respect to the given cost function and constraints. An example of the resulting vehicle paths obtained by the described latticebased path planning procedure is shown in Fig. 5. As can be noticed, the paths are slightly distorted in the vicinity of the static obstacles, which is the consequence of the imposed constraints related to private zones, enabling the implementation of the motion coordination strategy described in the next section.
3.3.3. Path planning on the state lattice Since the obtained motion primitives are feasible by design and repeated at every discrete state on the lattice, they are used in the path planning process in order to find an optimal feasible path connecting the initial vehicle state qI and the desired goal state qG in the lattice space. Therefore, the goal of the path planning process is to find the appropriate sequence of motion primitives = (p0 , …, pj , …, pn ), connecting states qI and qG via a series of other discrete states (q 0 = qI , …, qj, qj + 1, …qn+ 1 = qG), so that pj, j {0, …, n}, connects two consecutive states qj and qj + 1. The motion primitives (p0 , …, pn ) can thus be treated as the path segments constituting the resulting path π. Since there are many possible ways to reach the given goal state from an initial state on the lattice, it is necessary to ensure the determination of an optimal path, i.e. the one with minimum cost. Given the cost function g, which returns the cost of a given path segment, the path planning problem is then the problem of minimizing the objective function f ( i ) = p i g (pj ), where πi is an arbitrary path connecting the initial
3.4. Motion coordination
j
and goal states, composed of a sequence of path segments pj with their respective costs g(pj). Hence, assuming the set Π contains all valid solutions to a planning problem, our goal is to find an optimal solution:
Once the path has been obtained by the described two-layer path planning approach, safe vehicle motion along that path must be Fig. 4. Four different shapes of constructed private zones.
6
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 5. Example of the planned vehicle paths consisting of a sequence of motion primitives.
algorithm running on the vehicle first checks if any other vehicle has already occupied or is currently in the process of allocating the same cell (s). For this purpose, the vehicle performing allocation acquires information on the current plans of all other vehicles within the communication radius by reading their sign-board data. In order to reduce the amount of data that is exchanged among the vehicles during each allocation process, the sign-board does not contain information on all desired cells, but only information on the current vehicle location and the next desired state (target node) around which the next private zone is to be allocated. By combining this information with the known path information (which is broadcast by each vehicle upon having obtained the path) as well as known size and shape of the vehicle footprint and its affiliated private zones, a vehicle performing allocation is able to obtain the desired cells of all other neighboring vehicles. In case there is another vehicle trying to allocate the same cell(s), a competition process is started and only one vehicle gets access to a particular part of the workspace. In our current implementation, it is implied that all vehicles, and consequently their footprints and affiliated private zones, are identical, which means that by knowing only its own footprint and private zone information each vehicle is able to detect the desired cells of all other vehicles in the communication radius. However, it can be easily extended to the situation where the vehicles are different but know each otherś kinematic information in advance, which is a reasonable assumption in an industrial environment. More specifically, in order to handle a fleet of different-sized vehicles, besides information on its own footprint and private zones, each vehicle should also be provided with information on the footprint and private zones of all other types of vehicles in the fleet. In that case, a different set of footprint and private zone data would be used for detecting the desired cells of each particular type of vehicle. Accordingly, considering that the vehicles know each other’s size, shape, and kinematics encoded in the footprints and private zones, each vehicle would be able to obtain the desired cells of any other vehicle, which is a necessary prerequisite for ensuring mutually-exclusive access to any part of the workspace. While performing resource allocation, the coordination algorithm also detects potential conflicts with other vehicles and resolves them in case of successful allocation. The conflict resolution relies on the designed conflict negotiation protocol, which takes into account vehicle (i.e. mission) priorities. The following two subsections provide a brief description of the private-zone coordination mechanism and the corresponding conflict negotiation protocol. An in-depth description and analysis of the private-zone coordination approach can be found in [16].
ensured. Considering the fact that the vehicles autonomously calculate their paths, i.e. without taking into account the plans of other vehicles, many unpredictable conflict situations in the shared environment may occur. Therefore, the primary objective of the motion coordination part of our traffic management algorithm is to ensure coordinated vehicle motions in order to prevent inter-vehicle collisions, as well as deadlock and livelock situations. The coordination strategy pursued in this work consists of the following three steps: (i) allocating the necessary spatial resources on the path; (ii) negotiating possible conflicts with other vehicles; (iii) moving toward the allocated part of the workspace. The three basic types of spatial resources considered in the allocation process are parking stations and docking stations on the topological layer, and workspace cells at the state lattice layer. Each parking station, docking station, and cell inside a corridor or a terminal is considered as a resource of capacity one that can be allocated by only one vehicle at a time. Accordingly, the vehicle is allowed to enter a parking station or a docking station only after it has successfully been allocated. Furthermore, vehicles move along their path segments inside corridors by first allocating all the cells that become occupied by the vehicle while moving along each individual path segment. Therefore, the maximum allowed number of vehicles in a corridor depends on its length. On the other hand, the coordination inside the terminals is based on the allocation of cells in the form of private zones, introduced in Section 3.3.2. The primary reason for using private zones is to ensure the necessary physical space for performing avoidance maneuvers in conflict situations, as further described in Section 3.4.2. 3.4.1. Resource allocation Taking into account the fact that there is no centralized controller or any kind of global information in our system, the mutually-exclusive allocation of the shared spatial resources is ensured by the “One out of N” algorithm, introduced in [27] and customized in [16]. This algorithm guarantees that in situations when there are N vehicles competing for a resource of capacity one, only one vehicle eventually gets access. By executing this algorithm, the motion coordination module dynamically allocates the required spatial resources on the vehicle path. The allocation is based on the exchange of information with other vehicles within the local communication radius through the sign-board mechanism [28]. When allocating the desired cells inside terminals (cells being occupied by the vehicle footprint while moving from its current location to its next private zone, including the cells within the zone), the allocation 7
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
3.4.2. The private-zone coordination mechanism Vehicle coordination inside the terminals is carried out in the following way. The coordination algorithm, running on each vehicle, allocates the next private zone around one of the remaining discrete states (nodes) connecting two adjacent path segments. Upon successful allocation, the algorithm guides the vehicle toward the center of that zone, or, in case there are other lower-priority vehicles on the path, initiates a conflict negotiation process. In case of successful conflict negotiation, the blocking vehicles yield or retreat to safe locations within their private zones in order to ensure collision-free motion of the higher-priority vehicle that initiated the negotiation process. Otherwise, the allocated private zone is released and the allocation process is repeated in the next round of the coordination loop. Snapshots from the coordination scenario with private zones, which also demonstrate the resolution of conflicts, are shown in Fig. 6.
algorithm is summarized by Algorithm 1. Due to the implementation of the distributed resource allocation algorithm that ensures mutual exclusion even in the presence of communication delays [27], and the request/response model that requires an adequate response to each request during the conflict negotiation, it is ensured that the packet delays have no adverse effect on reliability and safety of our coordination algorithm. 3.5. Communication radius As stated in Section 2, one of our primary objectives is to design a scalable traffic management algorithm, which can properly handle an arbitrary increase in the number of vehicles in the system. The two crucial properties of the designed control algorithm, which ensure high scalability, are low computational complexity and limited communication requirements. In [16], we have shown that the complexity of the control algorithm is linear in the number of vehicles. The second property, related to limited communication requirements, is fulfilled by requiring inter-vehicle communication only within the limited topological area surrounding the vehicle. The minimal required communication radius encompasses only those vehicles that could potentially compete for the same resource. Regardless of the current vehicle sector, the farthest node that can be chosen as the next target node in the allocation process is the first of the remaining nodes that is not located in the terminal. Accordingly, the required communication radius for different vehicle locations within the layout can be visualized by the diagram in Fig. 8. As can be seen, all the vehicles located inside the terminal area and its neighboring docking and parking stations must be able to communicate. Additionally, those vehicles should also be able to communicate to the vehicles entering the terminal from the inbound corridors and leaving the terminal through the outbound corridors, as long as they
3.4.3. Conflict negotiation protocol In the case a conflict situation with lower-priority vehicles has been detected, the coordination algorithm initiates its resolution by executing the conflict negotiation protocol based on the exchange of special messages. Fig. 7 illustrates the negotiation message exchange flow during conflict resolution between the higher-priority vehicle 1 and lower-priority vehicles 2 and 3 . Negotiation is initiated by vehicle 1, which sends removal_reqested messages to vehicles 2 and 3 . After receiving removal_acknowledged from 2 and 3, 1 confirms successful negotiation by sending removal_confirmed to both vehicles, 3, triggering their removal actions. Upon retreating to safe 2 and locations inside their private zones, 2 and 3 respond with passing_permitted, enabling 1 to pass through their private zones. As 1 leaves the private zones of 2 and 3, it sends passing_done message to each of those vehicles, permitting them to return to their original locations. The pseudocode of the main procedure of the two-layer control
Fig. 6. Conflict resolution based on removal actions. Lower-priority vehicles deflect to safe locations inside their private zones in order to free the path for passing higher-priority vehicles. 8
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 7. Message exchange flow during the conflict negotiation between the higher-priority vehicle 2 and 3 perform removal actions.
1
and the lower-priority vehicles
2
and
3
in case when both
the given goal locations, circular waits can occur. In this situation each vehicle is waiting for the spatial resource held by another vehicle from the same set. Clearly, unless properly handled, this situation could result in system deadlock. An illustration of a circular wait formed by the vehicles located in different sectors is shown in Fig. 9. In this example each vehicle is assigned a goal location that can only be reached by passing through at least one corridor. Since the corridors are already occupied and removal actions are allowed only inside the terminals, regardless of their priorities none of the vehicles is capable of proceeding to its desired docking station. In order to deal with this type of situation, the coordination algorithm implements a circular wait detection and resolution mechanism (lines 18–22 in Algorithm 1).
occupy path segments lying in both the corridor and the terminal. On the other hand, vehicles moving through the inner part of the corridors should be able to communicate only to their preceding and succeeding vehicles, since they only move forward by allocating the workspace cells lying on the next path segment. The limited communication radius strongly contributes to system scalability, especially in large-scale environments with layouts divided into many sectors. In such cases, adding new vehicles at one side of the environment does not affect the execution of the motion coordination algorithm on vehicles located at the other side of the environment. 4. Stability analysis
4.1. Detecting the circular waits
In this section we analyze the stability of the presented coordination method in order to show that no deadlock or livelock situations can prevent the execution of assigned vehicle missions. The stability analysis is of paramount importance, since deadlocks and livelocks are highly undesirable in industrial environments. A thorough analysis of the private-zone coordination mechanism on the state-lattice layer, confirming its deadlock-free and livelock-free properties while coordinating vehicles inside each individual terminal, is given in [16]. In this work, we extend this analysis to the topological layer by considering the interdependence of vehicle motions within the entire working layout. The first objective is to show that no livelock situations can occur. Livelock refers to a situation in which vehicles cyclically repeat their motion sequences, but none of the vehicles can reach its goal location in finite time. Considering the fact that no path replanning is allowed, vehicles constantly progress toward their goal locations while moving along their shortest paths. Although the motion of one or more vehicles can be temporarily interrupted by the higher priority vehicle requesting the right of way, this situation necessarily results with the higher priority vehicle proceeding with its motion. Therefore, each set of motion sequences includes at least one vehicle progressing toward its goal location, meaning that the given motion sequence can not be repeated. Accordingly, the implemented coordination strategy is free of livelocks by design. As opposed to livelocks, additional control actions are required in order to ensure deadlock-free system properties. Due to the independence of the task assignment and motion coordination modules, and the fact that vehicles move only along their shortest paths toward
This first step in handling circular waits is their reliable detection. Since the vehicles have no global knowledge about all system states, this task must be performed in a distributed way. Many approaches for solving this kind of problem have been proposed in literature. They can be generally divided into the following four categories: path pushing, edge chasing, diffusion computation and global state detection [29,30]. However, in order to detect a circular wait in this work, there is no need for implementing a dedicated algorithm due to the following reason. While performing the distributed allocation of its next spatial resource, each vehicle communicates to all other vehicles within the local communication radius in order to ensure mutually exclusive access to the required spatial resources. The inter-vehicle communication during the resource allocation process is based on reading other vehicles’ signboard data. Besides the data required for the allocation process, the sign board of each vehicle also contains information on the detected vehicles that are blocking its motion. Therefore, by reading other vehicles’ signboard data, each vehicle is capable of automatically detecting its blocking vehicle, i.e. a vehicle occupying the required spatial resources, and also the vehicles by which the blocking vehicle is blocked. Having acquired this information, the blocked vehicle publishes the list of all detected vehicles blocking its way on its own sign board. Accordingly, the information on blocking vehicles is automatically propagated to other vehicles becoming blocked by them. Taking into account the fact that the resource allocation algorithm is repeatedly executed in a looping procedure (see Algorithm 1), the list of blocking vehicles on the sign board of each blocked vehicle is being 9
10
24
23
22
21
20
19
18
17
16
15
14
13
12
11
10
9
8
7
6
5
4
3
2
1
/* Set of missions of vehicle Ai */
Algorithm 1. Main procedure of the decentralized control algorithm.
i until qicurr , qG, j; Remove the executed mission from the set M i ;
Navigate toward the next target node(qtg , blocking_veh); else resolve_circular_wait = Check circular wait conditions(); if resolve_circular_wait then mij−1 = Obtain the temporary goal location; M i ← mij−1 ; Continue by executing mission mij−1 ;
if NOT resolved then Release allocated resources; continue;
Input : M i = {mi1 , . . ., mik }; blocking_veh ← ∅; while vehicle in IDLE state do Removal requests processing(); foreach mij ∈ M i , j ∈ {1, . . ., k} do i route = Top-layer planning(qiI , qG, j , map, sectors, topol._graph); j i π = Lattice-based path planning(qiI , qG, j , lattice, map, route); repeat Removal requests processing(); allocated = Detect and allocate the required spatial resource(s); if allocated then if blocking_veh , ∅ then resolved = Conflict negotiation(blocking_veh);
I. Draganjac, et al.
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 8. Minimal required communication radius in dependence on the vehicle location.
constantly updated in each round of the procedure. Eventually, every blocked vehicle will end up with a list of all vehicles blocking its path. In the case of a circular wait, the acquired list of blocking vehicles on each blocked vehicle will also contain the blocked vehicle itself, indicating that a circular wait situation occurred. Obviously, since each vehicle executes the same control algorithm, all the vehicles taking part in a circular wait will eventually detect the same circular wait situation. Therefore, a proper strategy must be defined in order to reliably resolve the detected circular wait and prevent system deadlock.
4.2. Resolving the circular waits Strategies for resolving circular waits generally rely on the abortion of one of the processes involved in the circular wait. Similarly, the resolution strategy implemented in this work is based on temporary sending the lowest priority vehicle involved in the circular wait toward the closest location that is not affected by the circular wait. Accordingly, upon detecting the circular-wait situation, the lowest priority vehicle exiting a corridor or a docking station starts a
Fig. 9. A circular wait formed by vehicles located in different sectors. 11
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
replanning procedure in order to obtain a new path toward the closest vacant parking location or outbound corridor. In order to ensure successful allocation of the required spatial resources, this vehicle is temporarily considered as the highest priority vehicle during the resource allocation and conflict resolution processes. The resolution of the circular wait in the context of Fig. 9 is performed by the lowest priority vehicle 4 that allocates a vacant parking location 4 leaves the x and starts moving toward that location. As soon as corridor, the circular wait is broken. It should be noted that potential conflicts with other vehicles operating inside the terminal area can be easily resolved, since those vehicles reside inside their private zones providing necessary free space for avoiding collisions. In case when there are no vacant parking locations or alternative outbound corridors in the terminal that the vehicle resolving a circular wait is entering, it announces the unsuccessful resolution trial on its sign board and the next vehicle in reverse priority order, entering another terminal, starts the same resolution procedure. This process is repeated as many times as necessary until reaching successful resolution of the circular wait, after which the temporarily removed vehicle replans its path toward its original destination and resumes with the execution of the interrupted mission. In order to prove the correctness of the described circular wait resolution strategy we provide the following two theorems.
5. ROS implementation In this section we briefly describe the implementation of the control algorithm within the robot operating system (ROS) framework [31]. All the necessary modules for controlling vehicles have been implemented within a standalone ROS package using the C++ programming language. The modular implementation of the control package is depicted in Fig. 10, which also shows connections between the nodes and information they exchange over underlying topics and services through the TCP/IP network protocol ensuring reliable delivery of packets among different modules by detecting and retransmitting every lost packet. The path planning, path following and motion coordination functionalities are implemented within separate ROS nodes named path planner, path follower and agv controller, respectively. The path following functionality is based on the well known pure pursuit path tracking algorithm [32], enabling vehicles to navigate along the calculated lattice-based paths. Furthermore, the task assignment functionality is implemented within a simple mission publisher node. It reads predefined missions from a dedicated file and assigns each mission to the designated vehicle. The localization node provides pose estimates based on the use of on-board localization sensors when controlling real vehicles, and by simulating the vehicle kinematics while performing simulations. More specifically, the localization of the Pioneer 3DX robots used in experiments (Section 6.2) is based on the amcl ROS package, implementing the adaptive (or KLD-sampling) Monte Carlo localization approach. This approach uses a particle filter [33] to track the pose of a robot against a known map, based on the real-time data collected from the on-board SICK LMS-100 laser scanner mounted on top of the robot. On the other hand, the simulations are conducted by running a custom localization node estimating the current poses of virtual vehicles based on the known vehicle kinematics and velocity information received from the path follower module. This simplified localization technique eliminates the burden of real localization algorithms in simulations and provides a clearer insight into the implemented coordination logic. Besides the above-mentioned nodes, a standard map_server node is used to provide vehicles with the map of the environment, while the RViz tool is used to visualize the operation of the entire multi-AGV system. Accordingly, the modular architecture of the control package makes it suitable for use in a hardware-in-the-loop configuration when controlling real vehicles, as well as for conducting simulations in virtual scenarios. The described ROS package has been used for validating the correctness and performance of the control algorithm in simulation scenarios and experimentally, as further presented in Section 6.
Theorem 1. Every circular wait formed in the layout represented by the introduced sectors includes a cycle of sectors with every other sector being a terminal. Proof. This statement follows directly from the assumptions A1–A3 (Section 3.1), which imply that every transition from one sector to another necessarily implies passing through a terminal. □ Theorem 2. Regardless of the exact locations of the parking stations in the layout represented by the introduced sectors, every circular wait can be resolved by temporarily removing one of the vehicles affected by the circular wait that is entering a terminal sector to a vacant parking station directly accessible from that terminal or to an alternative outbound corridor that is not affected by the circular wait. Proof. We prove this statement by contradiction. Let’s suppose the opposite, i.e. none of the vehicles in a circular wait entering a terminal sector can be temporarily removed to a parking station in that terminal or to another outbound corridor that is not affected by the deadlock situation. This proposition can only be true if both of the following two conditions are satisfied. a) There are no parking stations that can be accessed from the terminals affected by the circular wait or every parking station in those terminals is occupied. b) None of the terminals affected by the circular wait contains an outbound corridor that is not affected by the analyzed circular wait.
6. Performance validation In this section we present simulations and experimental results that validate the decentralized control method described in previous sections.
Suppose that the condition a) is satisfied, which may be true in large environments with many terminals. Furthermore, suppose that the condition b) is also satisfied, meaning that none of the terminals affected by the circular wait contains neither a vacant parking station nor an outbound corridor that is not affected by the analyzed circular wait. However, considering the assumption A5 (Section 3.1), there should always exist at least one unoccupied parking station for each vehicle in the system, which according to the assumption A4 must be accessible from any terminal in the layout, i.e. including the terminals affected by the deadlock situation as well. Accordingly, assuming that the condition a) is satisfied, at least one terminal in a circular wait should provide a connection toward other parts of the workspace containing unoccupied parking stations via at least one outbound corridor that is not affected by the analyzed circular wait. Therefore, our starting proposition that both conditions (a) and (b) can be true at the same time is in contradiction to the assumptions A4 and A5, which define the topological representation of the layout. This concludes the proof. □
6.1. Simulation scenario In order to validate traffic management performance and verify system scalability in virtual environments, we conducted simulations with 10, 20, 30, 40, and 50 virtual forklifts with footprint dimensions 2.8 m × 1.1 m on a map with dimensions 108 m × 152 m. The map is divided into four terminals, each comprising twelve docking stations and two corridors providing connections with neighboring terminals. A simulated working environment with fifty virtual AGVs, visualized by the RViz tool, is shown Fig. 11.1 During simulations, vehicle speed was limited to 1.2 m/s, and the 1 An annotated video of simulation with fifty vehicles is available at https:// tinyurl.com/simulation-with-50-vehicles.
12
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Fig. 10. Modular implementation of the designed decentralized control algorithm within the ROS framework. Separate instances of the agv_controller, path_planner and path_follower nodes are executed on-board each vehicle in the system. The red and green arrows denote communication between the nodes over ROS topics and services, respectively. (For interpretation of the references to color in this figure legend, the reader is referred to the web version of this article.)
vehicles were assigned random missions with a constant rate of one mission per minute. Each mission consisted in picking-up the load at the given pick-up location and transferring it to the drop-off location. The conducted simulations confirm the correctness of the proposed approach, i.e. regardless of the number of vehicles in simulation, the vehicles were able to execute their missions without collisions, deadlocks or livelocks. The simulations are conducted by executing the control package described in Section 5 on three computers connected through the ROS multimaster network. Each simulation was running over a longer period of time, while the performance metrics data has been collected during a period of 30 min. The obtained simulation results are presented in Section 6.4.
6.2. Experimental validation on P3DX robots Experiments were conducted on a laboratory setup comprising six Pioneer 3DX robots. Pioneer robots are differential-drive vehicles equipped with an on-board computer running ROS on Linux OS, laser scanner and odometry sensors for localization purposes, and a Wi-Fi module enabling wireless communication with other robots in the fleet. Prior to experiments, the ROS package implementing the control algorithm was installed on each Pioneer robot. The experimental validation was performed inside a testing arena with dimensions 10 m × 6 m in four different scenarios: in an open space, and in the layouts containing static obstacles, corridors, and
Fig. 11. Snapshot from a simulation of a multi-AGV system comprising fifty vehicles. 13
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
private zones on the map of the arena on the right. The conducted experiments confirm that the control algorithm is capable of coordinating vehicles not only in open spaces, but also in environments with static obstacles, corridors and shelves. It is also confirmed that the coordination method is computationally inexpensive and enables the vehicles to autonomously resolve different unpredictable conflict situations that arise along the way. 6.3. Performance metrics This subsection describes the performance metrics that are used to analyze the quality of the presented method. To the best of our knowledge, a benchmark set and the corresponding performance metrics that would allow comparison of different coordination methods does not exist in literature. This could be due to the fact that system performance depends on many factors, such as the map of the environment, path determination approach, limitations of AGVs, task allocation methods, etc., making it difficult to directly compare only one aspect of control, such as motion coordination. Different performance metrics approaches are considered in literature. In [34], the authors analyze the number of accomplished missions per hour as a measure of system performance. Assuming that AGVs are always assigned with missions, this parameter shows the bottleneck capacity of the system. Furthermore, decomposition and analysis of mission execution times is used, for example, in [35–37], while an analysis of traveled distances is used in [38]. Total computation time as a measure for analyzing system scalability is used in [39]. The performance metrics used in this work combine all of these approaches. To analyze the performance effectiveness and scalability of the control algorithm, for each simulation scenario we determine the overall system throughput as the number of completed missions per hour (TH). In addition, we analyze time and energy costs for each simulation run. By time cost we consider the total average time needed to execute a single mission. The total time is decomposed into useful time that the vehicle spends advancing to its goal, and waiting time that the vehicle spends either allocating the next resource, or giving the right of way to higherpriority vehicles. By energy cost we consider total path length traveled per mission, which is further decomposed into useful path (advancing to goal) and evasion path (removing from paths of other vehicles). In [16] we have shown that the computational complexity of the control approach based on resource allocation and conflict negotiation is O(N). In order to verify this result, we also present the average resource allocation times and conflict negotiation times for different fleet sizes. 6.4. Performance analysis The results of the overall system throughput analysis are given in Table 2, while a graph depicting the interpolated dependence of system throughput on the number of vehicles in the fleet is shown in Fig. 13. As expected, system throughput increases as the number of vehicles in the fleet increases, until a critical bottleneck point when, due to high traffic congestion, system throughput starts decreasing. According to Table 2, optimal system throughput in the simulated environment can be achieved with approximately 33 vehicles. Moreover, it can be seen that any further increase in the number of vehicles has a negative impact on system throughput since more vehicles take part in conflicts and the total number of moving vehicles starts dropping. The time cost and energy cost results are given in Tables 3 and 4, respectively. The results show that the average mission time increases with the number of vehicles because of the conflict situations that arise more frequently with the higher number of vehicles in the shared workspace. In order to demonstrate the conflict statistics as a function of the number of vehicles in the system, we present the total number of vehicle removal and yield actions on the basis of 100 missions in Table 5. Comparing the time cost and the energy cost results, it can be
Fig. 12. Snapshots from experimental validation of the decentralized traffic management algorithm on a system comprising six Pioneer 3DX robots in four different layouts.
shelves. The aim of the conducted experiments is to demonstrate the usability of the presented traffic management concept in different types of working environments. In each of the four scenarios the vehicles are receiving random missions consisting of docking maneuvers at one of six predefined docking areas. Fig. 12 depicts one scene from each of the four validated scenarios.2 Each scene shows, side by side, vehicles in the testing arena on the left, and their corresponding paths, self-localized poses, and allocated 2 An annotated video of conducted experiments is available at https://tinyurl. com/experiments-with-p3-dx-robots.
14
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
Table 2 System throughput TH with respect to number of vehicles.
Table 4 Energy cost with respect to number of vehicles.
Number of vehicles
TH [h 1]
Number of vehicles
10
20
30
40
50
528
880
953
918
836
total path [m] useful path [m] evasion path [m]
10
20
30
40
50
64 63.48 0.52
60.84 59.92 0.92
61.04 59.4 1.64
61.6 59.6 2
64.6 62.04 2.56
Table 5 Conflict statistics on basis of 100 missions. Number of vehicles
nbr. of yields nbr. of removals
20
30
40
50
20 7.5
8.7 16
13.3 30
24.1 32
19.5 45
described in [40]. According to the presented scheduling times in [40], the centralized control algorithm requires 107 ms to calculate only one set of safe trajectories for ten vehicles on a map with dimensions 95 m × 10 m. Accordingly, due to its high scalability, the algorithm proposed in this work eliminates the computational limitations present in the state-of-the-art centralized approaches, such as [40], and allows for real-time control of systems with a large number of vehicles. Since the vehicle coordination in this work relies on allocation of the spatial resources and negotiation of the detected conflict situations, Tables 6 and 7 summarize the average allocation times and conflict negotiation times for different numbers of vehicles in the fleet. Both variables increase slightly with the number of vehicles, which confirms the linear complexity of the motion coordination algorithm. This result also confirms the high scalability of the decentralized control approach, since the computational time does not increase significantly as the number of vehicles in the system increases. Moreover, it should be emphasized that allocation and conflict negotiation times increase more rapidly in simulations than in real systems, since simulations are conducted by executing controllers of all vehicles on only three networked computers. It is also worth mentioning that these times have no impact on smooth vehicle motions, since vehicles start allocating their next resources and negotiating the detected conflicts one step ahead, i.e. while moving toward their currently allocated resources.
Fig. 13. Interpolated dependence of system throughput on the number of vehicles.
noticed that although the total mission time significantly increases as a consequence of larger waiting times, energy consumption is not that much affected by the increase in the number of vehicles. This is a consequence of the control strategy that forces vehicles to follow shortest paths toward the goals at all times, and to select the shortest possible evasion paths in conflict situations. The presented coordination approach is compared to [39], where the authors give detailed specifications of the conducted experiments, enabling comparisons with other approaches. The experiments in [39] are conducted on a map with dimensions 260 m × 45 m, using 7 AGVs with speed limitation of 1.5 m/s. The authors analyze time to drop (TTD) - time between pick-up and delivery and obtain average TTD of 87.6 s. If we scale this result to vehicle speed of 1.2 m/s, used in this work, we obtain TTD value of 109.5 s. The map size used in this work is larger than the one in [39], however we do not scale the results due to different layouts. TTD as a measure can be compared with total travel time given in Table 3. Although the total travel time should be greater than TTD since it includes both traveling toward the pick-up station and delivery location, the values obtained for 10 vehicles in our experiment (travel time of 58.05 s) show better performance compared to the mentioned approach. This comparison provides a rough estimate of the algorithm performance. However, to make a direct and complete comparison, the experiments should be performed on the same map, using the same set of missions. In terms of scalability, the proposed control algorithm is compared to centralized lattice-based multi-vehicle coordination approach
7. Conclusion In this paper, we have described a decentralized traffic management method, which provides vehicles with capabilities for fully autonomous mission execution. The experimental results have confirmed that the developed method is capable of coordinating vehicles in different types of environments represented by the introduced topological sectors. Furthermore, the simulation and experimental validation results have confirmed that the method is highly scalable and suitable for coordination of small, medium and large-scale multi-AGV systems. Another benefit of the presented coordination method is high flexibility to changes in the environment, which is ensured by the free-ranging motion concept in which vehicles autonomously plan their paths within the entire obstacle-free space. The only action that needs to be taken in
Table 3 Time cost with respect to number of vehicles.
Table 6 Average conflict negotiation time.
Number of vehicles
total time [s] useful time [s] waiting time [s]
10
10
20
30
40
50
Number of vehicles
58.05 52.90 5.15
62.04 49.94 12.10
70.36 49.49 20.87
90.14 49.67 40.46
159.95 51.71 108.24
10
20
30
40
50
3.12
3.43
3.82
3.96
5.37
conflict negotiation time [s]
15
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al.
References
Table 7 Average resource allocation time.
[1] P.R. Wurman, R. D’Andrea, M. Mountz, Coordinating hundreds of cooperative, autonomous vehicles in warehouses, AI Mag. 29 (1) (2008) 9. [2] L. Sabattini, V. Digani, C. Secchi, G. Cotena, D. Ronzoni, M. Foppoli, F. Oleari, Technological roadmap to boost the introduction of AGVs in industrial applications, IEEE International Conference on Intelligent Computer Communication and Processing (ICCP), (2013). [3] R. D’Andrea, A revolution in the warehouse: a retrospective on kiva systems and the grand challenges ahead (guest editorial), Autom. Sci. Eng. IEEE Trans. 9 (4) (2012) 638–639. [4] M. Raineri, S. Perri, C.G.L. Bianco, Safety and efficiency management in LGV operated warehouses, Robot. Comput. Integr. Manuf. 57 (2019) 73–85, https://doi. org/10.1016/j.rcim.2018.11.003. [5] T. Petković, D. Puljiz, I. Marković, B. Hein, Human intention estimation based on hidden Markov model motion validation for safe flexible robotized warehouses, Robot. Comput. Integr. Manuf. 57 (2019) 182–196, https://doi.org/10.1016/j.rcim. 2018.11.004. [6] H. Andreasson, A. Bouguerra, M. Cirillo, D.N. Dimitrov, D. Driankov, L. Karlsson, A.J. Lilienthal, F. Pecora, J.P. Saarinen, A. Sherikov, et al., Autonomous transport vehicles: where we are and what is missing, Robot. Autom. Mag. IEEE 22 (1) (2015) 64–75. [7] M.B. Duinkerken, M. van der Zee, G. Lodewijks, Dynamic free range routing for automated guided vehicles, 2006 IEEE International Conference on Networking, Sensing and Control, IEEE, 2006, pp. 312–317. [8] A. Ulusoy, S.L. Smith, X.C. Ding, C. Belta, D. Rus, Optimality and robustness in multi-robot path planning with temporal logic constraints, Int. J. Robot. Res. 32 (8) (2013) 889–911. [9] L. Sabattini, M. Aikio, P. Beinschob, M. Boehning, E. Cardarelli, V. Digani, A. Krengel, M. Magnani, S. Mandici, F. Oleari, C. Reinke, D. Ronzoni, C. Stimming, R. Varga, A. Vatavu, S.C. Lopez, C. Fantuzzi, A. Mayra, S. Nedevschi, C. Secchi, K. Fuerstenberg, The pan-robots project: advanced automated guided vehicle systems for industrial logistics, IEEE Robot. Autom. Mag. 25 (1) (2018) 55–64, https:// doi.org/10.1109/MRA.2017.2700325. [10] E. Roszkowska, S. Reveliotis, A distributed protocol for motion coordination in freerange vehicular systems, Automatica 49 (6) (2013) 1639–1653. [11] V. Digani, L. Sabattini, C. Secchi, C. Fantuzzi, Hierarchical traffic control for partially decentralized coordination of multi AGV systems in industrial environments, 2014 IEEE International Conference on Robotics and Automation (ICRA), IEEE, 2014, pp. 6144–6149. [12] M.P. Fanti, A.M. Mangini, G. Pedroncelli, W. Ukovich, A decentralized control strategy for the coordination of agv systems, Control Eng. Pract. 70 (2018) 86–97, https://doi.org/10.1016/j.conengprac.2017.10.001. [13] W. Schwarting, J. Alonso-Mora, D. Rus, Planning and decision-making for autonomous vehicles, Ann. Rev. Control Robot. Auton. Syst. 1 (1) (2018) 187–210, https://doi.org/10.1146/annurev-control-060117-105157. [14] V. Digani, M.A. Hsieh, L. Sabattini, C. Secchi, Coordination of multiple AGVs: a quadratic optimization method, Auton. Robots 43 (3) (2019) 539–555, https://doi. org/10.1007/s10514-018-9730-9. [15] B. Li, H. Liu, D. Xiao, G. Yu, Y. Zhang, Centralized and optimal motion planning for large-scale AGV systems: a generic approach, Adv. Eng. Softw. 106 (2017) 33–46, https://doi.org/10.1016/j.advengsoft.2017.01.002. [16] I. Draganjac, D. Miklić, Z. Kovačić, G. Vasiljević, S. Bogdan, Decentralized control of multi-AGV systems in autonomous warehousing applications, IEEE Trans. Autom. Sci. Eng. 13 (4) (2016) 1433–1447. [17] G. Vasiljević, D. Miklić, I. Draganjac, Z. Kovačić, P. Lista, High-accuracy vehicle localization for autonomous warehousing, Robot. Comput. Integr. Manuf. (42) (2016) 1–16, https://doi.org/10.1016/j.rcim.2016.05.001. [18] J. Barraquand, J.-C. Latombe, On nonholonomic mobile robots and optimal maneuvering, Proceedings of the IEEE International Symposium on Intelligent Control, IEEE, 1989, pp. 340–347. [19] R. Kala, K. Warwick, Planning of multiple autonomous vehicles using RRT, Proceedings of the IEEE International Conference on Cybernetic Intelligent Systems (CIS), (2011), pp. 20–25, https://doi.org/10.1109/CIS.2011.6169129. [20] S. Karaman, E. Frazzoli, Sampling-based optimal motion planning for non-holonomic dynamical systems, Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), IEEE, 2013, pp. 5041–5047. [21] P. Švestka, M.H. Overmars, Motion planning for carlike robots using a probabilistic learning approach, Int. J. Robot. Res. 16 (2) (1997) 119–143. [22] C. Belta, A. Bicchi, M. Egerstedt, E. Frazzoli, E. Klavins, G.J. Pappas, Symbolic planning and control of robot motion [grand challenges of robotics], IEEE Robot. Autom. Mag. 14 (1) (2007) 61–70, https://doi.org/10.1109/MRA.2007.339624. [23] M. Pivtoraiko, R.A. Knepper, A. Kelly, Differentially constrained mobile robot motion planning in state lattices, J. Field Robot. 26 (3) (2009) 308–333. [24] M. Cirillo, T. Uras, S. Koenig, A lattice-based approach to multi-robot motion planning for non-holonomic vehicles, 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2014), IEEE, 2014, pp. 232–239. [25] A. Kelly, B. Nagy, Reactive nonholonomic trajectory generation via parametric optimal control, Int. J. Robot. Res. 22 (7 - 8) (2003) 583–601. [26] M. Pivtoraiko, A. Kelly, Efficient constrained path planning via search in state lattices, Proceedings of the 8th International Symposium on Artificial Intelligence, Robotics and Automation in Space, (2005). [27] J. Wang, DRS operating primitives based on distributed mutual exclusion, Proceedings of the 1993 IEEE/RSJ International Conference on Intelligent Robots and Systems, IROS ’93, 2 (1993), pp. 1085–1090 vol.2, https://doi.org/10.1109/
Number of vehicles
allocation time [s]
10
20
30
40
50
0.23
0.76
0.95
1.65
3.16
order to adapt to changes in the environment is to provide the vehicles with an updated map of the environment, which ensures significant reduction of deployment and maintenance costs since there is no need for designing and maintaining a layout-dependent network of paths. In addition, new vehicles can be easily added into the system, without the need for making any additional adjustments in the control system. In order to quantitatively analyze the system behavior, performance metrics have been defined and obtained by extensive simulations. The performance of the presented control approach was compared to other state-of-the-art multi-AGV control methods. Our future work will include experimental validation of this method in realistic industrial environments on real AGVs, as well as further optimizations of the coordination algorithm in order to additionally improve system throughput and ensure more balanced vehicle utilization. We are planning to achieve these improvements by implementing a dynamic path planning method that takes into account the current locations and plans of other vehicles in order to avoid congested areas and consequently reduce the number of conflicts resulting in undesired vehicle stops. The avoidance of congested areas is to be achieved by imposing an additional constraint on the objective function used in the path planning process, forcing the calculation of less congested vehicle paths. As the paper is dealing with an industrially applicable topic, we would also like to point out some managerial implications of our research. The supply chain industry is growing at unprecedented rates, and so are the intralogistics operations of manufacturers, distributors and retailers. Companies are resorting to ever larger fleets of AGVs to handle the increasing flow of goods and materials. Fully centralized systems that are ubiquitous today have inherent limits in terms of scalability and flexibility. To future-proof their operations, warehouse managers should look towards new system architectures, which are more scalable and flexible. Scalability refers to the ability of the coordination algorithm to handle larger fleets comprising tens or even hundreds of vehicles. Flexibility refers to the ability to quickly adapt to changes in the environment and to add and remove vehicles from the fleet, without disrupting warehouse operations. We view the results described in this paper as one step toward the application of highlyscalable and flexible decentralized AGV fleets in real-life industrial applications. CRediT authorship contribution statement Ivica Draganjac: Conceptualization, Methodology, Software, Formal analysis, Investigation, Data curation, Writing - original draft, Writing - review & editing, Visualization. Tamara Petrović: Validation, Formal analysis, Writing - original draft, Writing - review & editing. Damjan Miklić: Writing - original draft, Writing - review & editing. Zdenko Kovačić: Supervision, Project administration, Resources, Funding acquisition, Writing - review & editing. Juraj Oršulić: Investigation. Declaration of Competing Interest We wish to confirm that there are no known conflicts of interest associated with this publication and there has been no significant financial support for this work that could have influenced its outcome. 16
Robotics and Computer Integrated Manufacturing 63 (2020) 101915
I. Draganjac, et al. IROS.1993.583316. [28] J. Wang., On sign-board based inter-robot communication in distributed robotic systems, Proceedings of the 1994 IEEE International Conference on Robotics and Automation, 2 (1994), pp. 1045–1050, https://doi.org/10.1109/ROBOT.1994. 351219. [29] E. Knapp, Deadlock detection in distributed databases, ACM Comput. Surv. 19 (4) (1987) 303–328, https://doi.org/10.1145/45075.46163. [30] M. Singhal, Deadlock detection in distributed systems, Computer 22 (11) (1989) 37–48, https://doi.org/10.1109/2.43525. [31] M. Quigley, K. Conley, B.P. Gerkey, J. Faust, T. Foote, J. Leibs, R. Wheeler, A.Y. Ng, ROS: an open-source robot operating system, ICRA Workshop on Open Source Software, (2009). [32] R.C. Coulter, Implementation of the Pure Pursuit Path Tracking Algorithm, Technical Report, Robotics Institute, Carnegie Mellon University, Pittsburgh, PA, 1992. [33] D. Fox, Kld-sampling: Adaptive particle filters, Advances in Neural Information Processing Systems, (2002), pp. 713–720. [34] L. Sabattini, V. Digani, M. Lucchi, C. Secchi, C. Fantuzzi, Mission assignment for multi-vehicle systems in industrial environments, IFAC-PapersOnLine 48 (19) (2015) 268–273.
[35] V. Digani, L. Sabattini, C. Secchi, A probabilistic eulerian traffic model for the coordination of multiple AGVs in automatic warehouses, IEEE Robot. Autom. Lett. 1 (1) (2016) 26–32. [36] K. Zheng, D. Tang, W. Gu, M. Dai, Distributed control of multi-AGV system based on regional control model, Prod. Eng. 7 (4) (2013) 433–441. [37] J. Santos, P. Costa, L.F. Rocha, A.P. Moreira, G. Veiga, Time enhanced a: towards the development of a new approach for multi-robot coordination, Industrial Technology (ICIT), 2015 IEEE International Conference on, IEEE, 2015, pp. 3314–3319. [38] C. Wei, K.V. Hindriks, C.M. Jonker, Altruistic coordination for multi-robot cooperative pathfinding, Appl. Intell. 44 (2) (2016) 269–281. [39] R. Olmi, C. Secchi, C. Fantuzzi, An efficient control strategy for the traffic coordination of AGVs, 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems, (2011), pp. 4615–4620, https://doi.org/10.1109/IROS.2011. 6094474. [40] M. Cirillo, F. Pecora, H. Andreasson, T. Uras, S. Koenig, Integrated motion planning and coordination for industrial vehicles, Proceedings of the 24th International Conference on Automated Planning and Scheduling, Portsmouth, NH, USA, 2126 (2014).
17