Routing, Path Planning, and Auto-localization - IEEE Xplore

27 downloads 38842 Views 1MB Size Report
global economy, social needs, and logistics focusing on sustainable development ... Everyday new robotic applications can be found in literature and media.
Robotic Forklifts for Intelligent Warehouses: Routing, Path Planning, and Auto-localization Kelen C. T. Vivaldini, Jorge P. M. Galdames, Thales S. Bueno, Roberto C. Araújo, Rafael M. Sobral, Marcelo Becker, and Glauco A. P. Caurin USP – EESC - Mechatronics Lab – Mobile Robotics Group, São Carlos – SP, Brazil. {kteixeira}{galdames}@sc.usp.br; {thales.bueno}{roberto.carlos.araujo}{rafael.sobral}@usp.br; {becker}{gcaurin}@sc.usp.br

Abstract - Today, robotic systems are bridging the gaps between global economy, social needs, and logistics focusing on sustainable development solutions. Everyday new robotic applications can be found in literature and media. Some of them are basically entertainment toys. Nevertheless, the great majority of them is used inside industries, performing several tasks (painting, welding, moving materials, etc.). In a scenario of global economy growth, any sustainable solution that can reduce the product final cost is welcome. This article presents researches on robotic forklifts for intelligent warehouses developed at the Mechatronics Lab at USP–EESC in Brazil. We show three keyroutines that determine the Automated Guided Vehicle (AGV) behavior: the routing algorithm (that computes the overall task execution time and the minimum global path of each AGV using a topological map of the warehouse), the local path planning algorithm (based on A* it searches for the local minimum path between two nodes of the warehouse topological map), and an auto-localization algorithm (that applies an Extended Kalman Filter – EKF – to estimate the AGVs actual positions). In order to validate the algorithms developed, several tests were carried out using the simulation software Player/Stage. The results obtained were encouraging and the router developed was able to solve traffic jams and collisions, before sending the final paths to the robots. In a near future all algorithms will be implemented using mini- robotic forklifts and a scaled environment built in our lab.

I.

INTRODUCTION

The world globalization is considered an on-going process that started centuries ago. Since the end of World War II, the so called modern globalization produced several effects that affect us today in different ways (financial, industrial, economic, political, cultural, etc). Nowadays, thanks to the great development in several areas of knowledge, this process can have benefit from various new technologies in telecommunication, computer, robotics, etc. Logistics Corporations are trying to achieve better results, increasing their productivity and reducing their costs, by looking for the use of new reliable technologies (including the use of robotic systems). Only now automated logistics systems are reaching their full capabilities. Frequently, automated logistics systems, like warehouses, industries, seaports, and container terminals are adopting AGVs - Automated Guide Vehicles (Fig. 1) as a flexible and scalable alternative to optimize transport tasks, and other hazardous tasks in inhospitable environments (e.g.: nuclear power plants, mines, industrial freezers, etc). More recently, a new generation of AGVs has provided better

978-1-4244-5697-0/10/$25.00 ©2010 IEEE

reliability, availability robustness, and productivity for the logistics sector, offering significant advantages when compared to conventional material manipulation equipment [1]. Therefore, one of the main purposes of AGVs routing systems is to minimize the time spent in cargo transportation. Since then, many authors have focused their efforts on this issue Ravizza [2], Broadbent [3], Kim and Tanchoco [4] Möhring [5], Liu [6] and Vis [7] present a literature review on routing problems and methods of resolution.

Fig. 1. AGV – Automated Guided Vehicle working in an Intelligent Warehouse in Germany [2].

Based on this scenario, our paper describes the work in progress at the Mechatronics Lab at USP-EESC, Brazil. In Section II we shortly present the methodology developed. We briefly describe three key-routines that determine the AGVs behavior in the warehouse: routing, path planner, and autolocalization algorithms. In Section III, the simulation environment is presented. Section IV focuses on the simulation results and in Section V we summarized the conclusions. II. METHODOLOGY In this work we used system architecture (Fig. 2) that allows robotic forklifts to execute transportation tasks in an intelligent warehouse-like environment. The system is composed of 3 interdependent sub-systems: global path planner (routing system), auto-localization, and local path planner (navigation and obstacle avoidance). It is important to highlight that each robotic forklift has its own sensor, autolocalization, and local navigation systems running independently and informing regularly the routing system all local decisions taken. Thanks to this, the routing system can verify globally the overall system safety.

1463

The routing system receives information about the transportation tasks needed (pallet quantity, priorities, etc.). Based on this information, it selects the minimum quantity of robotic forklifts necessary to execute the tasks. Then, based on a topologic map of the environment, it calculates the routes for the necessary forklifts, checking possible collisions, traffic jams, etc. After that, it sends the routes to each robotic forklift and regularly verifies the progress of all tasks. Taking into account the global route, each forklift calculates its own local path necessary to reach its goal and monitors its surrounds looking for dynamic or unexpected obstacles during the execution of planned path.

Fig. 3. The Routing System Algorithm.

The warehouse model adopted in the simulation purposes has a fleet of six forklifts that move in a bi-directional circuit composed of 360 nodes interconnected by 652 arcs, as shown in Fig. 4.

Fig. 2. Overall System Architecture proposed.

At a certain frequency, based on sensor data and environment map (a two-layer map: metric and topological) each robotic forklift auto-localization system updates its position estimates and informs these data to the global and local navigation systems. Its local navigation system compares actual position with the desired one. If the robot is away of the route, the local navigation system sends commands to correct its positioning. The methodology implemented is described in the following sections. A. Routing System The routing task may be understood as the process of selecting appropriate paths simultaneously for the AGVs among different possible solutions using cost functions in order to increase the system productivity [8]. In the proposed model, our routing algorithm performs the selection of optimized routes for the robotic forklifts along the network nodes, and it sends information from the origin to the destination positions for all AGVs. Each AGV executes the task starting in an initial position and orientation and moving to a pre-established position and orientation, generating a minimum path. This path is a continuous sequence of positions and orientations of the AGVs. The algorithm is based on Dijkstra's shortest-path method [5] and was implemented in C/C++ (Fig. 3).

Fig. 4. Mapping model considered in the simulations: (a) the warehouse 2D model ; (b) the topologic map with the nodes, and (c) final graph used in the simulations.

There are special nodes that we called stations. In these positions the robotic forklifts are able to release and receive new load (4 Production - A, B, C, and D, 11 Shelves and 6 Charging Platform), charge batteries (6 Depot). We considered that the Central Control Unit (CCU) calculates the routes using the routing algorithm and sends them to the robotic forklifts. They navigate through the warehouse connected by a communication system (wireless). It is necessary to highlight that the proposed algorithm calculates the route, represented by check-points (nodes in a topological map). In order to apply Dijkstra’s algorithm [5], it is necessary to have the environment mapped previously (Fig.

1464

4a) and an estimation of the robotic forklifts position (provided by the localization system). Then, the environment topological map is used (Fig. 4b). On this map, the relevant environment features are modeled as check-points (nodes). We assumed that the stations (Shelves, Platform Charging, and Production) are placed in nodes belonging to our warehouse topological map. This is to certify that each robotic forklift in the warehouse is on a node. Based on these assumptions, each node of the graph used in the simulations (Fig. 4c) has its address represented by coordinates (x, y), where x and y represent in the map, respectively, the row and column of address in meters. This map is modeled for graph G(N,E), where N is the set of nodes and E the set of edges. The NxN nodes of the graph represent the connection of nodes, edges represent two paths between two adjacent intersection nodes. The length of each edge is a constant value in meters. The attribution of loading and unloading tasks will be omitted in this work. We assume that the time can be divided into discreet units and that each forklift always arrives at the intersection node at some discreet time. Based on the forklift routing model of the map, we have formally define that: a Storage task is identified by an ordered pair of initial and final nodes ((Ix,Iy),(Fx,Fy)), where (Ix,Iy ) represents the origin address, (Fx,Fy) represents the destination address, and (Ix,Iy )≠(Fx,Fy). Assuming that a task has a distinct origin and also a distinct (but different) destination and each task has only one handled forklift, each forklift begins its activities. The Dijkstra’s shortest path is used in this work to calculate the routes of the forklifts considering the cost. Basically, the method of routing time window [10] consists in verifying traffic jams and deadlocks in order to improve the route. Next, we verify the route optimization reducing the quantity of curves using again Dijkstra’s algorithm with time-window [11]. The routing system interacts with the other systems as presented in Fig. 5.

minimum path between these positions, we applied the A* algorithm [12]. The A* algorithm is based on a graph that has nonnegative arcs and it considers two variables while searching the minimum path: the travelled distance and an estimative of the distance to reach the goal position. Due to this, the algorithm can direct its search to obtain the minimum path spending a minimum computer cost. After that, the navigation controller executes the actions necessary to move the robot according to the desired path. The robotic forklift kinematic model is essential to control its own movements (wheel angular speeds). As we are using differential driven robots to simulate the robotic forklifts, we decided to develop a parameterized model using the relevant constructive parameters necessary to control wheel speeds. To model a differential mobile robot, we consider that the wheel-soil contact points are placed in xy plane. The global coordinate system {M} is located in the environment at O and oriented by the orthogonal versors I 1 and J 1 :

M = {O, I 1 , J 1 }

(1)

A mobile coordinate system is fixed at the midpoint between the driven wheels axis (P), and will be guided by the orthogonal versors J2 and I2, which is parallel to the axis of the wheel:

N = {P, I 2 , J 2 }

(2)

Therefore, representation of points A, B and C can be written in a simpler manner using the system N:

A = {0,−c}N B = {− l ,0}N

(3) (4)

C = {l ,0}N

(5)

Finally, the point coordinates may be expressed in any coordinate system through equations 6 and 7:

AN = RMN (θ) . ( AM − {x, y,0}T )

(6)

+ {x, y,0} )

(7)

AM =

−1 RMN (θ) . ( AN

T

Fig. 5. Interaction of the routing system with navigation, control, and localizations systems.

B. Local Path Planning System The robotic forklift local path is based on the global path data provided by the routing algorithm. These data are basically a sequence of nodes of a topological map that is used to model the environment. The local planner converts these nodes into a sequence of initial and final positions that must be reached to complete the task. In order to find the

Fig.6. Global and mobile coordinates system and the position robot components

1465

It must be highlighted that the robot modeling will be used in real robot control applications. Due to the use of Player/Stage simulator, that already has a model for control system implemented, the first developed model was not used for simulations. C. Auto-Localization Localization is the problem of finding out robot’s coordinates relative to its environment, assuming that one is provided with map of the environment [13]. Localization is also a key component of the project. It provides the estimated position of the robot using a localization algorithm. The algorithm is based on the model that describes robot motion as a function of the odometry, where the robot motion is approximated by a rotation δROT1, followed by a translation δTRANS and a second rotation δROT2. There are several techniques and algorithms in literature used to localize mobile robots. In this work the Extended Kalman Filter (EKF) was adopted to obtain an estimate of the localization of the robot during the simulation. The EKF is a non-linear version of the Kalman Filter that basically substitutes linear predictions by non-linear generalizations. The EKF is divided into two main parts: prediction and correction. In the prediction stage an estimation of the position using the information odometry is made. Then, in the correction stage, characteristics extracted from the environment are compared with estimate measurements. They are calculated according to the map and estimated position. In the sequence, the estimate of robot’s position is updated. The EKF follows General Diagram to Location of Mobile Robots (Fig. 7) proposed by [14].

µ t = µ t + K t ( z t − h( µ t ))

(11)

Σ t = ( I − K t H t )Σ t

(12)

Return µt, ∑t Where: µ t state vector mean ( x t , y t , θ t )

g (u t , µ t −1 ) state transition function u t control vector (δROT1, δTRANS, δROT2) Σ t state vector covariance G t Jacobian of g (u t , µ t −1 ) Rt noise model K t Kalman gain H t Jacobian of h ( µ t ) Qt measurement noise i i i z t measurement vector ( rt t , φ t , s t )

h ( µ t ) measurement prediction function ( rˆtit , φˆti , sˆti ) Ht =

∂h( µ t ) ∂xt

Gt =

∂g (u t , µ t −1 ) ∂xt −1

Functions g (u t , µ t −1 ) and h ( µ t ) details: g (u t , xt −1 ) = xt −1 + δ TRANS ⋅ cos(θ t −1 + δ ROT 1 )

g (u t , y t −1 ) = y t −1 + δ TRANS ⋅ sin (θ t −1 + δ ROT 1 ) g (u t , θ t −1 ) = θ t −1 + δ ROT 1 + δ ROT 2

(m j , x − µ t , x )2 + (m j , y − µ t , y )2 φˆti = a tan 2(m j , y − µ t , y , m j , x − µ t , x ) − µ t ,θ rˆti =

sˆti = m j , s

III. SIMULATION ENVIRONMENT

Fig. 7. General Diagram to Location of Mobile Robots. Adapted from Siegwart and Nourbakhsh [14]

In order to simulate the EKF, landmarks were included in the simulated environment in a structured way and assuming previously known location. The landmarks are detected by the robotic forklift during the simulation. The positioning information of the landmarks (mj,x, mj,y, mj,s) regarding the robot are processed during the execution of the EKF’s algorithm. The Algorithm 1(adapted from Thrun et al. [15]) shows in details the equations of the Extended Kalman Filter. Prediction:

µ t = g (ut , µ t −1 )

(8)

Σ t = Gt Σ t −1GtT

(9)

+ Rt

Correction: K t = Σ t H tT ( H t Σ t H tT + Qt ) −1

(10)

The simulated environment is an intelligent warehouse. The simulation of this environment aims to find the best solution for this context. In other words, a viable, reliable, and robust solution. The simulations were implemented in Linux Operating System using the Player/Stage simulation software [16]. The development of simulation environment was divided into two stages: 1). implementation of warehouse’s virtual model and its limits based on its draft (CAD file); 2). virtual modeling of robotic forklifts (physical characteristics, controllers, etc.). The first stage is basically the generation of an image file from a warehouse draft. The 2D Stage simulator recognizes this file and creates a virtual map similar to the real one. This virtual map has information concerning the warehouse frontiers and inaccessible areas to the robot. In the second stage the robotic forklift and environment virtualization and the router algorithm are integrated by the Player software. Player supports the virtual forklift commands control based on an algorithm written in C language.

1466

IV. RESULTS In order to verify the efficiency of the algorithms, several simulations were carried out using the virtual warehouse developed by the Player/Stage Simulator. Our algorithms were applied to control this warehouse. Simulations were run using two test scenarios (as shown below). Each robotic forklift has one loading and unloading task to perform. (Table I and Table II, task #1). TABLE I INFORMATION DEALT IN THE PROPOSED MODEL Forklift

Depot

1

Depot # 1

Task #1 Origin Destination Shelf_I_16 Changing_D

Depot

(a)

Depot # 1

TABLE II INFORMATION DEALT IN THE PROPOSED MODEL Information

Depot

1 2 3 4

Depot # 1 Depot # 2 Depot # 3 Depot # 4

Task #1 Origin Destination Shelf_A_02 Production_B Shelf_A_06 Changing_D Shelf_A_14 Changing_B Shelf_A_13 Changing_B

Depot Depot # 1 Depot # 2 Depot # 3 Depot # 4

Therefore, in the proposed scenario, the route is a set of 3 sub-routes automatically generated by the routing algorithm (Fig. 8). We tested the two stages of routing (A – One Robotic Forklift and B – Four Robotic Forklift), in each one the robotic forklift(s) left its (their) depot(s) and returned to it(them) after finishing the task(s).

(b)

(c) Fig. 9. Routing task applied to four Robotic Forklifts - positions on x-y plane vs. time. The nodes of table II are represented by circles. Collisions and traffic jams are represented by blue stars and emphasized by arrows. Fig. 8. Routes for one forklift. In (a) the minimum route was calculated for the desired tasks; in (b) routes without dead-locks and traffic jams after the rerouting task (one may observe that for one forklift the routes were the same); and in (c) the path was optimized, reducing the total maneuver quantity.

The results show that in Fig. 9-a the Forklift # 3 had two routing problems: a traffic jam with Forklift # 4 (detail represented by a grey arrow) and a deadlock with Forklift # 4 (detail represented by a black arrow). In addition to this, in the conflict-free stage (Fig. 9-b), the time and distance costs can be higher than the previously calculated (Fig 9-a), because the algorithm is avoiding traffic jams and deadlocks. Finally, in the stage of maneuvers optimization (Fig. 9c) the best results for the calculated routes were obtained. Next, the best solution provided by the routing algorithm is simulated using the Player/Stage. We used the A* and the Extended Kalman Filter algorithms to obtain a more realist simulation of the real robotic forklift behavior.

In Fig. 10 one may observe the final path calculated by the navigation controller for the forklift #1 using the A* algorithm. This algorithm gives the robotic forklift the parameters that will be used by the controllers to execute the route.

Fig. 10. 2D warehouse model: final path executed

1467

During the implementation of the EKF in the modeled environment, it was necessary to include cumulative random errors in the robotic forklift odometry and laser sensor data, because Player/Stage software uses data without sensor errors. The EKF showed enough robustness with respect to odometry errors during the simulation because the robot did not collide with walls. It managed to keep the route and position, and the values generated by the filter did not diverge. Table III presents the maximum error, mean, and the standard deviation between the simulated position (without error) and the position estimated by the EKF. These values were obtained while simulating the task presented in Fig. 11. 8,530 EKF updates were used to calculate the values of Table III. TABLE III VALUES OF THE ABSOLUTE ERROR EKF VS. SIMULATED POSITION. Max Mean Standard Deviation

X(m) 0,03836 0,01252 0,01365

Y(m) 0,03950 0,01971 0,01314

Theta(rad) 0,01751 0,00063 0,00086

V. CONCLUSIONS We briefly presented the approach developed in order to route robotic forklifts in an intelligent warehouse environment. Several simulations were carried out using the Player/Stage tools to test the algorithms. As a result, we could solve many bugs and refine the algorithms. The router developed was able to solve traffic jams and collisions, before sending the final paths for the robots. The A* algorithm was a simple way to control the robot maneuvers, and the EKF was sufficient to avoid the position error propagation. Our next step will be a real implementation using mini-robotic forklifts and a scaled environment built in our lab. We also plan some improvements on the algorithm, to refine the routing task planner and consider more parameters (e.g.: velocity changes while maneuvering, load and unload times). ACKNOWLEDGMENT The authors would like to thank FAPESP (Processes 2008/10477-0, 2008/09755-6 and 2009/01542-6), CAPES (Process 33002045011P8) and CNPQ (Process 134214/20099) for the financial support given to this research.

A. One Robotic Forklift

REFERENCES [1] [2] [3]

(a)

(b)

[4]

[5]

[6]

(c) (d) Fig 11. Simulations showing the displacement of forklift # 1, as show in the Table I and Fig. 8 (blue). In (a) it is outing of the Depot#1, (b) loading in the Shelf_I 16, (c) unloading in Changing_D and (d) it is returned for its origin point (Depot # 1).

[7]

B. Four Robotic Forklifs

[10]

[8] [9]

[11]

[12]

[13] Fig. 12. The route execution presented in the Fig. 9-c. Observe that the collision presented in the Fig. 9-a was eliminate by the routing algorithm.

[14] [15]

Figures 11 and 12 present the robotic forklift trails in the warehouse for one (Fig. 11) and four robots (Fig. 12). The final paths provided by the routing algorithm were collisionfree and avoided traffic jams.

[16]

1468

D. Bowersox and M.B. Closs, Cooper, Gestão da cadeia de suprimentos e logística. Rio de Janeiro: Elsevier, 2008. S. Ravizza. Control of Automated Guided Vehicles (AGVs), diploma thesis, ETH Zurich, 2009. Broadbent, A.J. et al., “Free ranging AGV systems: promises, problems and pathways” Proceedings of 2nd International Conference on Automated Materials Handling, UK, pp. 221-237, 1985. Ch.W. Kim and M.A.J Tanchoco “Conflict-free shortest-time bidirectional AGV routing”, International Journal of Production Research vol.29, n. 12, pp.2377–2391, 1991. R. H. Möhring, et al., “Dynamic Routing of Automated Guided Vehicles in Real-time”, Technische Universit at Berlin, Book: Mathematics - Key Technology for the future, pp. 165-177, 2008. I. F. A. Vis, “Survey of research in the design and control of automated guided vehicle systems” European Journal of Operational Research. Elsevier Science, Amsterdam, vol. 170, pp. 677-709, 2006. L. Qiu, W. Hsu, S. Huang and H. Wang “Scheduling and routing algorithms for AGVs: A survey”, International Journal of Production Research, vol. 40, n.3, pp. 745-760, February 15, 2002. R. H. Möhring, et al., “Conflict-free Real-time AGV Routing”, Operations Research Proceedings vol. 2004, Springer Berlin, 2004. E. W. Dijkstra, “A Note on Two Problems in Conexion with Graphs” Numerische Math, 1959, vol. 1, pp. 269-271. J. Desrosiers, F. Soumis, M. Desrochers and M. Sauvé. “Methods for routing with time windows.” European Journal of Operational Research, vol. 23, pp. 236-245, 1986. K.T. Vivaldini, G. Caurin, M. Becker, “Automatic Routing of Forklift robots in warehouse applications” in 20th International Congress of Mechanical Engineering (COBEM 2009), Gramado, Brazil, P. E. Hart, N. J. Nilsson and B. Raphael. A Formal Basis for the Heuristic Determination of Minimum Cost Paths, IEEE Transactions of Systems Science and Cybernetics, Vol. ssc-4, n. 19682. S. Thrun, “Probabilistic Algorithms in Robotics”. School of Computer Science Carrnagie Mello University, Pittsburgh, PA15123, 2000. R. Siegwart and I. R. Nourbakhsh, Introduction to Autonomous Mobile Robots. Cambridge: The MIT Press, 2004. S. Thrun, W. Burgard, D. Fox, Probabilistic Robotics. Cambridge: The MIT Press, 2006. B. Gerkey, et. al."The Player/Stage Project: Tools for Multi-Robot and Distributed Sensor Systems", In Proc. of the Intl Conf. on Advanced Robotics (ICAR), Coimbra: Portugal, pp. 317-323, Jun. 2003.

Suggest Documents