Next Article in Journal
Performance Index for Dimensional Synthesis of Robots for Specific Tasks
Previous Article in Journal
Empirically Comparing Magnetic Needle Steering Models Using Expectation-Maximization
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Investigating the Impact of Triangle and Quadrangle Mesh Representations on AGV Path Planning for Various Indoor Environments: With or Without Inflation

by
Ahmadreza Meysami
*,†,
Jean-Christophe Cuillière
,
Vincent François
and
Sousso Kelouwani
Mechanical Engineering Department, Université du Québec à Trois-Rivières, Trois-Rivieres, QC G8Z 4M3, Canada
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Robotics 2022, 11(2), 50; https://doi.org/10.3390/robotics11020050
Submission received: 18 February 2022 / Revised: 7 April 2022 / Accepted: 10 April 2022 / Published: 13 April 2022
(This article belongs to the Topic Industrial Robotics)

Abstract

:
In a factory with different kinds of spatial atmosphere (warehouses, corridors, small or large workshops with varying sizes of obstacles and distribution patterns), the robot’s generated paths for navigation tasks mainly depend on the representation of that environment. Hence, finding the best representation for each particular environment is necessary to forge a compromise between length, safety, and complexity of path planning. This paper aims to scrutinize the impact of environment model representation on the performance of an automated guided vehicle (AGV). To do so, a multi-objective cost function, considering the length of the path, its complexity, and minimum distance to obstacles, is defined for a perfect circular robot. Unlike other similar studies, three types of representation, namely quadrangle, irregular triangle, and varying-size irregular triangle, are then utilized to model the environment while applying an inflation layer to the discretized view. Finally, a navigation scenario is tested for different cell decomposition methods and an inflation layer size. The obtained results indicate that a nearly constant coarse size triangular mesh is a good candidate for a fixed-size robot in a non-changing environment. Moreover, the varying size of the triangular mesh and grid cell representations are better choices for factories with changing plans and multi-robot sizes due to the effect of the inflation layer. Based on the definition of a metric, which is a criterion for quantifying the performance of path planning on a representation type, constant or variable size triangle shapes are the only and best candidate for discretization in about 59% of industrial environments. In other cases, both cell types, the square and the triangle, can together be the best representation.

1. Introduction

Automated guided vehicles (AGVs) have been used for several decades [1,2]. They mostly rely on predefined routes to move from one point to another. However, the flexibility and agility introduced by industry 4.0 [3] are pushing these technologies towards a complete autonomous navigation capability [4]. The required autonomy forces the AGVs to know the environment prior to moving intelligently and safely. Therefore, one of the most important tasks for these vehicles is to model the navigation environment as accurately as possible [5]. In indoor navigation on a planar floor of a factory, a 2D model of the environment, including the specifications of the obstacle-free area, is required to perform path planning. Abstracting, encoding, and saving this type of information is called ‘mapping’ in mobile robots [6]. A mobile robot uses this map repeatedly to find a path between the current position and the goal position. The essential information for constructing the environment model is usually obtained from raw sensor data with the help of data structures. There are different types of data structures for saving and reading necessary spatial information in navigation. After saving the information, path planning uses this information via queries (by means of the data structure) to perform a task. Therefore, the data structure types, spatial models, and the resulting map all play decisive roles in the performance of the global planners.
One of the most well-known mapping methods, which has gained special attention due to its simplicity and robustness, is the occupancy grid technique [7]. This method is composed mainly of uniform grids with simple square shapes, which are made cell by cell, independently. Other shapes such as triangles (with application in polygonal mesh [8], reconstruction [9], etc.) can be used for the discretization of the environment. Squares and triangles are the most famous cell types in a planar application. The analogy between the occupancy grid map and a triangular mesh is the creation of a discretized environment model using the cell concept. Their difference, though, lies on the shape and number of cells, as well as their connection rules (topology) in forming a complete and accurate free space model. By utilizing such a model, a global path planner, e.g., cell decomposition method [10], can be used to find an efficient path between two points.
The efficiency of the path planning algorithm is highly dependent on the environment model, which in turn is impacted by the representation type (cell’s shape, number, and topology). For instance, according to the number of cells, it may take a shorter or a longer time to find a path. Moreover, the realized path may have different lengths and distances to the obstacles considering the cell shape and size in the environment. An efficient path should consider all of these essential parameters (such as length, distance, and computational time) [11]. Another aspect worth noting is that, when the conditions of an environment change (new distribution of obstacles), a new representation (discretized model) may lead to a more efficient path. However, investigating the influence of environment model representation on generating a suitable path has escaped the attention of many researchers. Works such as [12,13] have tried to define the environment’s difficulty based on parameters such as obstacle shape and distribution or distance to the nearest obstacles. Nevertheless, they did not consider the effect of a navigation scenario (position of start and goal points) and map representation, and they did not propose any solution to consider this difficulty. Recently, valuable work such as that of [14] tried to relate this difficulty to the robot’s traversal time in navigation benchmarking. However, this work focused on the overall performance of the navigation platform and does not consider the global planner effect. In a similar task, [14] only considers the effect of cell shape and size on computational efficiency and does not consider their effect on the path length and safety. In addition, ref. [13] defines some metrics and compares different path planning methods only on grid-type cells. Other works such as [15], which uses an adaptive mesh for risk-aware path planning, do not mention important parameters such as distance to the nearest obstacle and the effect of robot size. When the environment is cluttered, to our knowledge, there is no straightforward method to select the most appropriate navigation environment approach. For consideration of robot size in path planning, there are various methods. The first strategy applies offset to the boundary of the obstacles, then uses this scaled view as an input for discretization [16]. This strategy is unsuitable when it is necessary to modify the map according to changes in the environment or when the real model of the obstacles is necessary for manipulation. The second strategy is used in the game industry (famous as navigation mesh [17]) and checks each triangle for the input and output edge’s length as a possibility of robot passage [18,19]. The third strategy is map generation based on the actual boundary, then applying the inflation layer on the discretized view (the offset or inflation layer is the robot’s radius plus any optional value for safety, such as the method implemented in the ROS (Robot operating System) [20]). In addition, it is usual to build an inflated map on top of the metric map in robotic applications [21]. Nevertheless, no specific study has been carried out to select the best environment representation based on the effect of this inflation. Therefore, the main contributions of this paper are:
  • Showing that the type of environment representation has a direct impact on path planning, and quantifying this by a metric.
  • Presenting the results showing the pros and cons of each representation when considering the inflation layer
By considering the points discussed, this paper explores the effect of the environment representation on the performance of an AGV. In this regard, a multi-objective cost function is developed, and three kinds of cell decomposition (quadrangle, irregular triangle, and varying-size irregular triangle) are used for environment modeling. Furthermore, the robot size is considered through an inflation layer imposed on the model. To the best of the authors’ knowledge, this is one of the first attempts to explore the impact of different cell decomposition techniques and robot size on the performance of an AGV. A specific platform is used to generate the three representations with different applicable sizes [22]. Then, a performance comparison is performed for each representation using a fixed scenario obtained by a global planner [13,14].
The rest of the paper is organized as follows. Section 2 depicts the problem formulation and assumptions. Section 3 introduces some common concepts concerning cells and neighbors regarding all the representations. In Section 4, the methodology for all representations is explained by a mathematical formulation. Section 5 discusses all the results, corresponding to the simulation tests on various environments and representations. Section 6 summarizes the outcomes and puts forward future directions.

2. Problem Formulation and Assumption

An AGV (Automated guided vehicle), denoted by A, navigates in a factory as workspace Ws. The workspace contains obstacles, Bi, with i { 1 , 2 , 3 , , N o } and N o , the number of obstacles. The obstacle boundaries (Γ(Bi)) are generated by a LIDAR (Light Detection and Ranging) placed on the AGV [23]. These can be polygonal or curvilinear curves. The Ws is divided into WB, the union of all obstacles, and Wfree, the free space. S and G are the start point and the goal point of A, respectively, in the Wfree. According to the distribution of Bis and the size of A, various paths ( τ ) can be traversed to get to G from S. From an economic point of view, τ must be realized quickly, be as short as possible, and keep a safe distance to Bis. If τ does not satisfy one of these properties, AGV cannot be used reliably for a long time. In this regard, an optimal path ( τ opt ) is the one that has the best of the properties mentioned. It is typically determined by a global planner with the help of encoding Wfree to an environment map ( M reps ). The subscript “ reps ” denotes the encoding types or representations, which have a significant impact on finding τ opt .
This study assumes a perfect circular robot without any sensor noise and environment modeling uncertainty, in order to be able to map spatial information into various representation formats. The index for comparing different representations is a multi-objective cost function ( f ) which takes the length of τ opt , the complexity of finding the τ opt (correlated with running time), and minimum distance to obstacles into account [24]. Furthermore, no post-processing on the generated path, such as path smoothing [25], has been performed, since this work studies the behavior of various representations on a global planner (as in the deliberative approach concept, in which information is complete before starting the navigation) [26]). The next section discusses common concepts regarding the environment representation types used in mapping and navigation.

3. Environment Modelling for Navigation

The simplest required information to perform navigation in an environment is the Wfree. In this regard, one of the best-known methods is cell decomposition, in which Wfree is converted into digitized cells or a graph of cells. Various shapes can be used for the discretization of the environment. In the planar application, squares and triangles are the most famous cell types. Another practical cell type is the irregular triangular mesh (ITM), used extensively in computer graphics and gaming [17,18] as well as outdoor robotics applications [27]. Using these cells for navigation needs the definition of the neighbor types as either common-edge and common-node neighbors. In a quadrangle (QUAD) cell in a general condition (far from the obstacle), the number of common-edge neighbors and common-node neighbors is four and four. However, in an ITM, these numbers are generally three for common-edge neighbors or a variable number, depending on the degree of nodes.
As is clear, a QUAD cell with the edges parallel to the global frame of an environment cannot be flexible enough to show the boundary of obstacles in the environment except for shapes parallel with the global frame. This limitation causes some inaccuracy in the definition of the area around obstacles and presents limitations to accessing this area. Solving this problem requires a fine square, which, on the other hand, increases the computational burden. An ITM cell, with the flexibility of an edge’s direction, can accurately show the boundaries of obstacles. Nevertheless, their irregular shape requires the saving of topological and geometrical information, which makes the map larger. Therefore, each cell shape has its own pros and cons. These features can affect the performance of the algorithm that uses the encoded information of these cells.
The cell decomposition method takes a point as the representative of a cell in a navigation task in order to model the Wfree. The cell’s center can be a simple selection for square cells, in order to calculate properties such as the nearest distance to an obstacle, or as a reference for the position of cells and for moving between cells. After obtaining a representative for each cell, a path can be defined as the lines connecting the start and goal points through the center of cells, if they exist. For a fair comparison between QUAD and ITM, the center of the triangle is selected as the representative of each cell in this study (other methods like that of [28] consider the middle of the edges, with lower computational time but with a longer path). Optimal searching in this graph is performed according to criteria such as the cost and the heuristic of each cell with respect to start and goal points. Since the building block of this graph is a cell, the selection of its size is an effective parameter for the construction and searching of the graph. Small cells give more information than large cells after digitizing, but increase the computational effort of the agent. In addition to cell size, the rules of neighboring, which are different for each cell shape, can change the graph. Hence, finding a good path presents the challenge of finding contradictory parameters. The selection of a suitable cell shape and size can help find a reasonable solution. In the next section, the methodology for studying the effects of these various representations will be described.

4. Methodology

The performed analysis in this study is divided into two parts. First, the effect of representation is considered regardless of the robot size. Second, the robot size is considered using the concept of inflation layer. This concept generates the map based on the real boundary. Then, it applies an inflation layer to the discretized view. In fact, the offset or inflation layer is the radius of the robot plus any optional value for safety [20]. This strategy has already been implemented in the ROS (Robot Operating System) [20]. In what follows, the decomposition methods are described.

4.1. Pure Decomposition

The geometry and the physical size of the robot are not considered in this section. Furthermore, the discretized cell is general and does not depend on the specific type of representation. For navigation on a planar surface by cell decomposition method, it is necessary to encode and abstract the environment information into a map representation, M reps .
M reps = { All   c i   ( i = 1 , 2 , N )   ;   c i W free }
where c i denotes the ith cell and implies that the union of all discretized cells (finite number of N) can approximately estimate the free space Wfree. Each path between S and G points in the map is defined as τ , which is a set of cells:
τ = { c s , c 1 , c 2 , , c g } , g N
A set of cells as a path is divided into several segments S ij between successive cells c i and c j in τ . This leads to:
τ = { S s 1 , S 12 , S 23 , , S ij , , S ig } , g N , i = g 1
where S i j is generally a curve connecting two cells ( c i and c j ) together with all the possible points inside the cells. This segment will be a building unit of movement for AGV according to its controller. So, each movement between c i and c j is a line segment between their centers. However, linear movement between the centers of two neighbors does not always guarantee safety near the obstacles. Therefore, it is necessary to check the feasibility of movement for some cells near obstacles. To do so, Mov ( c i , c j ) is defined as:
Mov ( c i , c j ) = { True   if   p Line ( cent ( c i ) , cent ( c j ) ) p W free False   if   p Line ( cent ( c i ) , cent ( c j ) ) p W free
If Mov ( c i , c j ) is true, it shows that the movement between the centers of c i and c j is feasible. Otherwise, there is the possibility of collision between agents and obstacles. In the geometrical view, if the combination of neighbor’s vertices is convex, then the linear segment will be inside the union of cells, and the movement is safe. Nevertheless, if the combination of c i and c j ’s vertices is concave, then the movement is not permitted. This is because it increases the possibility of collision with an obstacle. To include this extra condition into τ :
τ = { { c s , c 1 , c 2 , , c g } ,   c i   and   c j   Mov ( c i , c j ) = True }
Checking the movement feasibility is simple for QUAD cells as the common-edge neighbor produces a convex shape. However, in ITM, it is possible to have a concave shape even for common-edge neighbors near obstacles. Hence, the movement feasibility needs to be checked in this mesh. This extra checking enhances the computational effort of this mesh type [29].
Among all possible τ , finding τ opt is of great interest. According to the discretized nature of the path, it is possible to convert cells and movement between them into vertices and edges of a graph. Then a graph search algorithm can be used to find τ opt between the start and goal cells. A*, as a popular graph search method [30], is employed in this study. This method uses Euclidean distance for calculating the cost and heuristic criterion between start and goal [31]. The cost of cell ( c i ) is given by:
( c i ) = cent ( c i ) , cent ( par ( c i ) )  
where cent ( c i ) stands for the center of the cell, Symbol a , b is the Euclidean distance between point a and point b, which are the center of two successive cells, and par( c i ) is the parent of c i . This cost starts from S and, in each sequence, accumulates the Euclidean distance between the current cell and its parent in a graph. The heuristic criterion of the cell (h ( c i ) ) is calculated by:
h ( c i ) = cent ( c i ) , goal
The result of A* is a τ with the minimum cost between two cells containing start and goal points. This τ is shown by τ opt :
τ opt = { { c s , c 1 , c 2 , , c g } ,   c i   and   c j ,
c i = par ( c j )   L τ opt min ( L τ )
where L τ denotes the length of a path.
As stated earlier, in this study, the utilized multi-objective cost function is composed of three metrics. These are the complexity of A* algorithm for finding τ opt , length of τ opt , and minimum distance between AGV and obstacles when it follows τ opt .
Herein, the complexity ( C reps ) is defined by counting the number of visited (In A*, visited cells go to a list named open list, so C reps = size (Open list)) nodes during A*.
C reps = Number   of   visited   cells   in   A
The length of the optimal path ( L τ opt ,   reps ) is calculated as follows:
L τ opt ,   reps = i = S i = G cent ( c i ) , cent ( par ( c i )
The minimum distance to the nearest obstacle is calculated with the help of the Euclidean distance grid, as explained in [32,33].
DT ( p ) = d k ,   p   c RG , k
where DT ( p ) is a function for mapping each point of free space p into a cell c RG , k in the reference grid ( RG ), which is a Euclidean distance transform on a 200 × 100 grid. c RG , k contains the value of distance to the nearest obstacle as d k .
Therefore, D min , reps , as the minimum distance between all agent’s distances to the nearest obstacles, is given by:
D min , reps = min ( DT ( τ ) )   which   c i τ     cent ( c i ) c RG , k
In triangular representation, as shown in Figure 1, there are some free points near obstacles that are not placed inside any cells in the RG . In this situation, the Euclidean distance between the point and other nodes and edges, which are tagged as the obstacle, is calculated. Then, the minimum value is returned as the minimum distance. This value may be smaller and larger than the previous distance value of the path and must be compared to the current minimum distance.
After calculating the three normalized metrics, a linear weighted sum approach is utilized to define the cost function for each representation.
{ LN reps = L τ opt ,   reps L max CN reps = C reps C max DN reps = D min D min , reps
where LN reps is the normalized optimal length, CN reps is the normalized complexity for finding optimal length, DN reps is the minimum distance of agent to the nearest obstacle when following the optimal path, L τ opt , reps is the optimal length obtained by (10), C reps is the calculated complexity from (9), D min , reps is the minimum distance of the optimal path from (12), and L max , C max , and D min are the maximum lengths between start and goal, maximum complexity to find this maximum length path, and the minimum possible distance between agent and obstacle, respectively. Finally, the multi-objective cost function ( f reps ) is formulated as:
f reps = ω 1 ×   LN reps + ω 2 ×   CN reps +   ω 3 ×   DN reps
where ω 1 ,   ω 2   and   ω 3 are the weights. For simplicity, equal importance is considered for all weights: ω 1 = ω 2 = ω 3 = 0.333.

4.2. Decomposition of Inflation Layer

In this sub-section, the robot size is integrated into the inflation layer. The inflation layer is defined as follows:
Inflation   layer   = {   p W free ,   DT ( p ) < ( r AGV + SD ) }
where r AGV is the radius of AGV, and SD is an optional value for a safe distance between the AGV and an obstacle. According to (15), the inflation layer is formed by all the points in Wfree whose distance to the nearest obstacle is lower than a specific value. With this definition, the resulting map considering this inflation will be:
M reps = { c i ( i = 1 , 2 , N ) ;   c i W free ; cent ( c i )   inflation   layer }

5. Results and Discussion

This section presents the results regarding the AGV performance in different conditions. After this, the considered case studies and the utilized platform are first explained. Subsequently, the results concerning environment representation and the inflation layer are discussed.

5.1. Platform for Experiment

The intended comparative study is expected to clarify the best representation ( M reps ) for each obstacle’s distribution (Ws) according to the above-explained multi-objective cost function ( f ). In this regard, a fixed scenario (a path planning between S and G) is utilized for various M reps and Ws. The following types of representation ( M reps ) are considered in this study:
  • QUAD mesh (GRID Nx × Ny): four cell sizes (GRID 100 × 50, GRID 120 × 60, GRID 160 × 80, and GRID 200 × 100) are considered for this mesh where Nx and Ny are the number of cells in horizontal and vertical directions.
  • ITM: four cell sizes (ITM-700, ITM-500, ITM-300, ITM-100) are also considered for this mesh. ITM-100 refers to a triangle with an average of 100 mm edges. For some environments where this was not applicable, larger triangles and smaller ones were used.
  • Varying-size ITM (VITM): Concerning this mesh, ITM-100-700 is utilized. This size refers to a triangular mesh with an average edge size of 700 mm, which has been refined to size 100 mm in some places. When confronting narrow passages, VITM-50-700 or VITM-30-700 have also been utilized.
Concerning various factory environments, the following Ws are taken into account (see Figure A1):
  • Area with single obstacle: Map_1 (small-size obstacle), Map_2 (medium-size polygonal obstacle), Map_3 (medium-size circular obstacle)
  • Space with dividers (Map_4)
  • Narrow passage (Map_5)
  • Curvilinear passage: Map6
  • Area with regular multi-obstacles: Map_7, Map_8 (two groups), Map_9 (different size)
  • Area with irregular multi-obstacles: Map_10, Map_11 (two groups), Map_12 (circular), Map_13 (different shapes)
  • Hybrid with wide space: Map_14
  • Corridor and dividers: Map_15
  • Hybrid narrow space environments: Map_16, Map_17 (including all the previous environments)
In this study, a research platform developed by our team (ERICCA, Equipe de Recherche en Integration Cao-CAlcul) is utilized to perform the mesh generation for different environments. This platform is based on the Unified Topological Model [22] and automatic meshing and remeshing tools, as explained in [34,35,36,37]. The computer for using this platform and simulation was Intel Core i7-4790 RAM 32GiB. Since the main task is to study the effect of the discretized cell types and sizes on the generated path by the global planner, the required map preprocessing is performed by the operator. For instance, an STP file (the STP is a standard format for exchange of modelling data) is used to define the boundary edges of obstacles and the exterior frame of the environment. This preprocess is similar to changing a point cloud, as sensor data, into a continuous curve of the obstacle’s boundary. Using the STP file as an input, various representations (QUAD, ITM, and VITM) with different sizes can be produced by the mentioned platform. A rectangle area of 10,000 × 5000 (mm) is utilized as the environment for all the performed simulations. Various types of obstacle distribution (single and multi-obstacles) are carried out regularly and randomly in this environment. A fixed scenario, navigation between points (300, 300) as the start and (9600, 4400) as the goal, is utilized for all the tests. The reason for selecting this path is that AGV needs to turn around the obstacles to pass the optimal length. After the generation of each map, the UTM platform makes it possible to perform global path planning and find the length, distance, and complexity in order to calculate the cost function for different representations. The running time of the utilized search algorithm is calculated by means of the number of visited cells in the graph search. This strategy is selected in order to be independent of coding details while comparing different cases.

5.2. Result—Environment and Representations

Consider an environment with a single medium obstacle as an example, which has been discretized by the three representations (QUAD, ITM, and VITM) with different sizes. Figure 2 represents the optimal path obtained by A* solely for one size of each representation. The scenario is to find a path between the start (300, 300) and goal (9600, 4400) points without considering inflation. Table 1 reports the length, minimum distance to obstacles, complexity, and cost of each case. From this table, ITM-700 has reached the lowest cost followed by VITM-100-700 while the GRID 200 × 100 has led to the highest cost. Therefore, ITM-700 and VITM-100-700 perform better than GRID 200 × 100 in terms of finding an optimal path in an environment with medium-size obstacles in parallel with the global frame.
Similar scenarios have been performed for various environments and cell sizes, as shown in Figure A2. The considered environments are the different distributions variously mentioned in Section 5.1. Moreover, different cell sizes of QUAD, ITM, and VITM, as explained earlier, are considered. The complete result is presented in Table A1, and for simplicity, only the best representation of each environment (minimum f values among others) is shown in Table 2. According to this table, a coarse ITM (like ITM-700 or ITM-500) seems to be a good candidate for almost all environments except the hybrid environment where a VITM (VITM-100-700) shows better performance. It is worth reminding the reader that the detailed results, as in Table 1, are presented in the Appendix for all environments. The discussed results have been obtained by considering the pure decomposition effect without an inflation layer. In the next sub-section, the results concerning the effect of robot size or inflation layer are explored.

5.3. Result—Inflation Effect on the Representations

In practice, it is necessary to consider the robot size in path planning. This is normally done by imposing an inflation layer around the obstacles. In this regard, the tests performed in the previous sub-section are repeated herein, considering the inflation layer.
Firstly, the test regarding the environment with medium-size obstacles is repeated by considering a robot size diameter of 354 mm (turtle bot 2 [38]). Figure 3 shows the obtained optimal path for this new case. The red layer around the obstacle and exterior boundary is not accessible by the robot. Therefore, the movements between the neighbors are affected by this layer, and the results will be changed. The new values considering this limitation are given in Table 3 for the three different representations. From this table, VITM-100-700 reaches the best performance ( f r e p s : 0.009) compared to the other two cases. This shows that considering the inflation layer influences the choice of the best representation, due to the change in complexity.
Secondly, all the previously considered environments of different types and sizes are repeated, considering the inflation layer. The obtained results are shown in Table 4. In this new analysis, as opposed to the case in which inflation was ignored, it is seen that many ITM representations have not been able to find the path, and they have been replaced by the VITM and QUAD representations. Furthermore, it has been necessary for the VITM to use finer triangles in the narrow passages that have not been blocked completely. Decreasing the size of triangles (increasing their number) can increase the chance of finding more triangles whose centers are inside the free space, and movement between them and their children is possible. Some of the generated paths are presented in Figure 4. According to Table 4, coarse ITM shows the best performance for a single obstacle or hybrid environment, with enough wide space (for Map_1, Map_3, and Map_14). Regarding the corridor and regular multi-obstacles, the coarse grid is the best method. In irregular multi-obstacles and a curvilinear passage, a VITM indicates the best performance.
To find the effect of inflation on each type of representation, Table 5 shows the average cost function (f values) for all environments in two conditions, without inflation and with an inflation layer. Their ratio shows that ITM is more sensitive to the inflation layer, and misses its benefit. QUAD representation shows better behavior when using inflation.
To compare the complexity of finding a path for each type of representation, we have calculated the average complexity (number of visited cells when graph searching) of each type of representation in Table 6. If any size could not give a path, a smaller size has been used to produce one. Overall, VITM shows the lowest complexity as compared to other types.

5.4. Results—Discussion

Finding the best representation for an AGV inside a factory according to different environment encounters during its navigation is an important part of the use of autonomous agents. Different representations give different path. A good path has a short length with a maximum distance to obstacles that can be calculated quickly. Without knowing this path, a mobile robot can be an unfeasible solution for a factory, along with increasing energy consumption due to a less than optimal path, lowering efficiency by inappropriate planning time and increased cost due to the high risk of an inadequate distance to obstacles (high probability of collision). By considering all these important parameters of path planning, this work defined a single criterion and checked it for different types and sizes of representation for the various environments inside a factory.
The obtained results show that for various types of environments, such as single or multi obstacles and corridor-like, some level of coarse ITM is the predominant strategy for achieving a compromise solution for length, safety, and computation time; this verifies the work in [14], which shows that refinement is not necessary for some motion planning. However, what has not been considered is that, when considering the inflation layer around obstacles, VITM and GRID representations are better. It is clear that, by increasing the resolution or decreasing the cell size, the complexity increases, and in most cases, the nearest distance to the obstacles decreases, with some average improvement in length. According to this result, when the robot is of a fixed size in a static environment, and it is possible to apply first the robot size to the map, it is better to use the ITM method with coarse size like [16] in which inflation has been applied as offset during the first mapping. However, when there are the following situations, it is better to use VITM or GRID representations:
  • In multi-robot sizes conditions, when is not possible to apply the offsetting method.
  • Some changes in the environment make it necessary to apply online inflation to the map, and not by offsetting the obstacles in the primary map.
  • There are narrow passages for a robot which makes ITM representation useless.
This benchmark also demonstrated that varying the size of the triangular mesh with a different strategy for refinement could be a competitive method when ITM cannot find the answer. Of course, this needs to be more refined when using the elements in an area with narrow passages. The other benefit of VITM is the more straightforward implementation relative to the quadtree method for neighbor finding, such as regular triangulation.
Robotic navigation in a real factory with multi AGVs with non-circular shapes is a more complicated task. This paper surveyed the effect of environment and map representation types on path planning considering a single circular AGV. Although a circle can cover any shape as a peripheral circle, it cannot obtain a path in some narrow passages. According to the robot’s footprint, this limitation leads to consideration of a more complex definition of the inflation layer. In addition, to show the clear behavior of various cell shapes in response to A* search graph, we did not consider any path smoothing, which causes a non-optimal path from the point of energy consumption.

6. Conclusions and Future Work

In using an AGV as a feasible solution in a factory in response to the fourth industrial revolution, it is necessary to consider a flexible multi-objective path planner to give better answers according to the changes in the environment. Hence, this paper investigates the impact of two important factors, environment model representation and robot size, on the performance of an AGV. In this regard, a multi-objective cost function, considering length, complexity, and minimum distance to obstacles, is formulated for a perfect circular robot with a fixed path. Subsequently, three types of representation, namely QUAD, ITM, and VITM, with different cell sizes are employed to model the environment. Moreover, an inflation layer is imposed on the discretized view to check its influence on the performance. A* is utilized to find the optimal path for the different cell representations and sizes with and without the inflation layer. The obtained results show that a coarse ITM is a good candidate for a relatively unchanging environment with fixed robot size and wide space. However, when it is possible to repeatedly change the factory’s plan and use different ‘robot sizes, VITM and GRID representations give better performance by applying an inflation layer, especially in narrow spaces. In comparing triangle and square representations, in about 59% of industrial environments, constant or variable size triangle shapes are the only best for the discretization of that specific environment.
Future work can pursue the following paths, which will bring important practical application in the field of AGV environment modeling and navigation. Consideration of dynamic environments will enrich the optimization function with more complex criteria using a solution such as right-hand traffic, and applying some simultaneous constraints on the navigation of a narrow passage. Furthermore, the results of this paper can be used as an efficient map server that selects the best representation according to the environment. This can bring a smarter AGV platform to industry.

Author Contributions

Conceptualization, J.-C.C., V.F. and S.K.; Methodology, A.M., J.-C.C., V.F. and S.K.; Software, V.F. and A.M.; Validation, A.M., J.-C.C., V.F. and S.K.; Formal Analysis, A.M.; Investigation, A.M., J.-C.C., V.F. and S.K.; Resources, J.-C.C., V.F. and S.K.; Data Curation, A.M.; Writing—Original Draft Preparation, A.M.; Writing—Review & Editing, A.M., J.-C.C., V.F. and S.K.; Visualization, A.M.; Supervision, J.-C.C., V.F. and S.K.; Project Administration, S.K.; Funding Acquisition, S.K. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by Natural Sciences and Engineering Research Council of Canada, grant Number CRSNG RDCPJ 518029-18.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Acknowledgments

The authors would like to thank the Natural Sciences and Engineering Research Council of Canada, Noovelia and the Foundation de l’Université du Québec à Trois-Rivières.

Conflicts of Interest

The authors have no conflict of interest for this work.

Appendix A

  • Figure A1: All defined environments
  • Figure A2: Sample of various representation types and sizes
  • Table A1: Result without consideration of inflation for all environments and representations
  • Table A2: Result with consideration of inflation for all environments and representations
Figure A1. All defined environments.
Figure A1. All defined environments.
Robotics 11 00050 g0a1
Figure A2. Various environments with different representation types and sizes of QUAD, ITM and VITM. (a) Map_1-ITM-700, (b) Map_2-ITM-100, (c) Map_3-VITM-100-700, (d) Map_7-GRID 200 × 100 (e) Map_7-ITM-300, (f) Map_11-ITM-500, (g) Map_10-VITM-100-700, (h) Map_10-ITM-300, (i) Map_8-VITM-100-700, (j) Map_4-VITM-100-700, (k) Map_6-VITM-100-700, (l) Map_14-ITM-700, (m) Map_16-VITM-30-700, (n) Map_16-ITM-100, (o) Map_15-VITM-100-700, (p) Map_17-GRID 200 × 100, (q) Map_178-ITM-300, (r) Map_17-VITM-100-700.
Figure A2. Various environments with different representation types and sizes of QUAD, ITM and VITM. (a) Map_1-ITM-700, (b) Map_2-ITM-100, (c) Map_3-VITM-100-700, (d) Map_7-GRID 200 × 100 (e) Map_7-ITM-300, (f) Map_11-ITM-500, (g) Map_10-VITM-100-700, (h) Map_10-ITM-300, (i) Map_8-VITM-100-700, (j) Map_4-VITM-100-700, (k) Map_6-VITM-100-700, (l) Map_14-ITM-700, (m) Map_16-VITM-30-700, (n) Map_16-ITM-100, (o) Map_15-VITM-100-700, (p) Map_17-GRID 200 × 100, (q) Map_178-ITM-300, (r) Map_17-VITM-100-700.
Robotics 11 00050 g0a2
Table A1. The length, minimum distance to obstacle, complexity, and cost function values for all representations without considering the inflation layer in the same scenario.
Table A1. The length, minimum distance to obstacle, complexity, and cost function values for all representations without considering the inflation layer in the same scenario.
Map NameRepresentationsS (300, 300)
G (9600, 4400)
ParametersSingle Criteria
TypeSizeInflationLength mmMin Distance mmComplexityf Cost Function
Map_1QUADGRID 100 × 50010,9867522690.042
QUADGRID 120 × 60011,02212531600.056
QUADGRID 160 × 80011,0077554630.095
QUADGRID 200 × 100010,9922583590.143
ITM700010,4511331140.005
ITM500010,4332751680.006
ITM300010,381463580.010
ITM100010,32927516440.031
VITM100_700010,29211180.008
Map_2QUADGRID 100 × 50010,9862522510.042
QUADGRID 120 × 60011,0222532060.058
QUADGRID 160 × 80011,0072554520.097
QUADGRID 200 × 100010,9922583230.145
ITM700010,7491551340.006
ITM500010,375251530.006
ITM300010,484463690.010
ITM100010,57012530300.055
VITM100_700010,521191770.007
Map_3QUADGRID 100 × 50010,9862522550.042
QUADGRID 120 × 60011,0222530490.056
QUADGRID 160 × 80011,0072552690.093
QUADGRID 200 × 100010,9922581170.141
ITM700010,521171060.006
ITM500010,559751900.007
ITM300010,45634440.012
ITM100010,3991921910.041
VITM100_700010,394401730.007
Map_4QUADGRID 100 × 50012,4162526950.051
QUADGRID 120 × 60012,4092537070.069
QUADGRID 160 × 80012,3402564680.117
QUADGRID 200 × 100012,2932510,0780.179
ITM700012,5651161640.007
ITM500012,438752950.010
ITM300012,222757470.017
ITM100012,0311356130.102
VITM100_700011,953154120.012
Map_5QUADGRID 100 × 50010,9867521020.039
QUADGRID 120 × 60011,0222529170.053
QUADGRID 160 × 80011,0072550640.090
QUADGRID 200 × 100010,9922578120.136
ITM700010,29487920.005
ITM500010,2851251530.006
ITM300010,3391333080.009
ITM100010,37911623160.043
VITM100_700010,4041252200.007
Map_6QUADGRID 100 × 50011,6302515790.053
QUADGRID 120 × 60011,6572521340.070
QUADGRID 160 × 80011,5922537260.116
QUADGRID 200 × 100011,5192557400.175
ITM700011,10946940.009
ITM500011,403751880.012
ITM300011,048463600.017
ITM100011,0651428590.091
VITM100_700011,052252750.015
Map_7QUADGRID 100 × 50012,3862522890.066
QUADGRID 120 × 60012,3802529950.085
QUADGRID 160 × 80012,3272555020.150
QUADGRID 200 × 100012,1732583880.225
ITM700012,760461900.012
ITM500012,357202260.013
ITM300012,233115520.021
ITM100011,7980.444280.130
VITM100_700012,031455130.020
Map_8QUADGRID 100 × 50011,5662522240.054
QUADGRID 120 × 60011,6402534180.080
QUADGRID 160 × 80011,5212555320.126
QUADGRID 200 × 100011,5112588360.199
ITM700011,938201670.009
ITM500011,465272420.011
ITM300011,444396110.019
ITM100011,181047370.117
VITM100_700011,58454350.015
Map_9QUADGRID 100 × 50011,4082517050.046
QUADGRID 120 × 60011,4612524830.064
QUADGRID 160 × 80011,3732540690.102
QUADGRID 200 × 100011,3432565200.160
ITM700011,207311200.008
ITM500011,10821900.011
ITM300010,921133790.015
ITM100010,8781027930.072
VITM100_700010,925173150.013
Map_10QUADGRID 100 × 50011,2392514580.037
QUADGRID 120 × 60011,1892522520.055
QUADGRID 160 × 80011,2222537710.089
QUADGRID 200 × 100011,2012557590.132
ITM700011,105141190.008
ITM500011,149452090.010
ITM300011,29225830.020
ITM100010,814325070.061
VITM100_700010,854324400.015
Map_11QUADGRID 100 × 50011,1562516500.036
QUADGRID 120 × 60011,1202524980.053
QUADGRID 160 × 80011,1192542140.086
QUADGRID 200 × 100011,1192563950.128
ITM700010,50013950.006
ITM500010,615451400.007
ITM300010,519323560.011
ITM100010,5501829980.062
VITM100_700010,596213170.010
Map_12QUADGRID 100 × 50011,0692516510.039
QUADGRID 120 × 60011,0912523210.053
QUADGRID 160 × 80011,0582540660.089
QUADGRID 200 × 100011,0332563160.135
ITM700010,5314940.007
ITM500010,454241530.008
ITM300010,369292300.009
ITM100010,5222420260.046
VITM100_700010,398422990.011
Map_13QUADGRID 100 × 50011,2392514790.036
QUADGRID 120 × 60011,1892523660.055
QUADGRID 160 × 800----
QUADGRID 200 × 100011,2012559990.132
ITM700011,048121260.008
ITM500011,026441600.008
ITM300011,011234940.015
ITM100010,8911438020.086
VITM100_700011,063212540.010
Map_14QUADGRID 100 × 50011,9032530250.060
QUADGRID 120 × 60011,8552542700.083
QUADGRID 160 × 80011,9182576230.145
QUADGRID 200 × 100011,8922511,9320.225
ITM700011,568422140.008
ITM500011,469463270.010
ITM300011,573467710.019
ITM100011,346959360.114
VITM100_700011,59052980.010
Map_15QUADGRID 100 × 50017,1922531180.068
QUADGRID 120 × 60017,2462544220.093
QUADGRID 160 × 80017,0312574720.153
QUADGRID 200 × 100016,7692511,6760.235
ITM700017,764312090.011
ITM500018,192463530.014
ITM300017,480299190.025
ITM100016,593870530.145
VITM100_700016,78614030.020
Map_16QUADGRID 200 × 100029,8302513,9780.303
ITM100030,072082150.219
VITM28_700030,183515380.045
Map_17QUADGRID 120 × 60032,8762551570.119
QUADGRID 160 × 80032,3082594840.206
QUADGRID 200 × 100032,0752515,0000.318
ITM300032,204512070.039
ITM100031,732324550.064
ITM50030,498092320.216
VITM100_700031,494110950.037
Table A2. The length, minimum distance to obstacle, complexity, and cost function values for all representations considering the inflation layer in the same scenario (Robot diameter = 354 mm).
Table A2. The length, minimum distance to obstacle, complexity, and cost function values for all representations considering the inflation layer in the same scenario (Robot diameter = 354 mm).
Map NameRepresentationsS (300, 300)
G (9600, 4400)
ParametersSingle Criteria
TypeSizeInflationLength mmMin Distance mmComplexityf Cost Function
Map_1QUADGRID 100 × 50110,9864821600.040
QUADGRID 120 × 60111,022430170.055
QUADGRID 160 × 80111,007452220.092
QUADGRID 200 × 100110,9922279780.137
ITM700110,560983670.010
ITM500110,433983310.009
ITM300110,472985810.013
ITM100110,3299818450.034
VITM100_700110,362983450.009
Map_2QUADGRID 100 × 50110,9864821010.040
QUADGRID 120 × 60111,0224829950.055
QUADGRID 160 × 80111,0072249870.089
QUADGRID 200 × 100110,9922275550.132
ITM700110,878985320.013
ITM500110,492484570.011
ITM300110,597487490.016
ITM100110,6351037140.067
VITM100_700110,469483270.009
Map_3QUADGRID 100 × 50110,9864820290.038
QUADGRID 120 × 60111,0221028420.052
QUADGRID 160 × 80111,0071049020.087
QUADGRID 200 × 100110,9922274580.130
ITM700110,671983240.009
ITM500110,56644640.012
ITM300110,519986220.014
ITM100110,508428690.053
VITM100_700110,641676730.015
Map_4QUADGRID 100 × 50113,0994823870.046
QUADGRID 120 × 60113,076433960.064
QUADGRID 160 × 80113,126460160.110
QUADGRID 200 × 100113,151492400.166
ITM700112,777819280.021
ITM500112,6331013650.028
ITM300112,9888117420.035
ITM100112,751476710.138
VITM100_700112,6861013340.028
Map_5QUADGRID 100 × 501----
QUADGRID 120 × 60111,0224826650.049
QUADGRID 160 × 80111,007446110.083
QUADGRID 200 × 100110,9922270570.124
ITM7001----
ITM5001----
ITM3001----
ITM100110,402425540.048
VITM50_700110,40946810.016
Map_6QUADGRID 100 × 501----
QUADGRID 120 × 601----
QUADGRID 160 × 801----
QUADGRID 200 × 100111,900446070.143
ITM5001----
ITM3001----
ITM1001----
ITM50111,668413,9780.418
VITM50_700111,545411110.040
Map_7QUADGRID 100 × 50112,756487300.026
QUADGRID 120 × 60112,800411880.038
QUADGRID 160 × 80112,779420490.061
QUADGRID 200 × 100112,7972228280.080
ITM7001----
ITM5001----
ITM3001----
ITM100113,176449330.136
VITM100_700116,061417060.054
Map_8QUADGRID 100 × 50111,7034815230.039
QUADGRID 120 × 60111,668421930.054
QUADGRID 160 × 80111,690438920.091
QUADGRID 200 × 100111,6682258020.132
ITM7001----
ITM5001----
ITM3001----
ITM100111,854457650.132
VITM100_700112,003411380.031
Map_9QUADGRID 100 × 50111,5844810950.032
QUADGRID 120 × 60111,604415800.044
QUADGRID 160 × 80111,581426560.069
QUADGRID 200 × 100111,5842241250.103
ITM700112,842489690.029
ITM500112,047412500.036
ITM300111,9642216130.044
ITM100111,584449780.124
VITM100_700111,972414320.041
Map_10QUADGRID 100 × 501----
QUADGRID 120 × 60113,171420370.052
QUADGRID 160 × 80112,162424610.061
QUADGRID 200 × 100112,211437310.089
ITM5001----
ITM3001----
ITM1001----
ITM50112,065413,8970.313
VITM30_700112,547414850.039
Map_11QUADGRID 100 × 50111,4041015410.034
QUADGRID 120 × 60111,258422950.049
QUADGRID 160 × 80111,274438940.080
QUADGRID 200 × 100111,284458760.135
ITM7001----
ITM500111,07448510.021
ITM3001----
ITM100111,214463900.128
VITM100_700112,754420120.044
Map_12QUADGRID 100 × 50111,9152213330.033
QUADGRID 120 × 60111,465417910.043
QUADGRID 160 × 80111,494431100.070
QUADGRID 200 × 100111,4112246300.101
ITM700111,60248530.023
ITM500111,796411230.029
ITM300110,8951011190.028
ITM100111,533446760.102
VITM28_700111,449412630.032
Map_13QUADGRID 100 × 50112,4251018780.045
QUADGRID 120 × 60112,205427800.065
QUADGRID 160 × 80112,256448080.108
QUADGRID 200 × 100112,316474300.164
ITM7001----
ITM5001----
ITM3001----
ITM100112,133495110.208
VITM100_700112,306417970.044
Map_14QUADGRID 100 × 50114,5402224210.050
QUADGRID 120 × 60113,2451038600.076
QUADGRID 160 × 80114,370459850.117
QUADGRID 200 × 100113,2472210,2930.195
ITM700112,918413450.030
ITM500114,584415730.035
ITM300114,2584823990.050
ITM100112,786410,7290.203
VITM50_700113,2081017170.037
Map_15QUADGRID 100 × 50118,6401020730.048
QUADGRID 120 × 60118,717431070.069
QUADGRID 160 × 80118,525453120.112
QUADGRID 200 × 100118,651481800.168
ITM7001----
ITM5001----
ITM3001----
ITM100118,584410,9100.221
VITM50_700118,918417010.042
Map_16QUADGRID 120 × 60135,929426610.071
QUADGRID 200 × 100135,954468780.159
ITM100136,679411,4020.253
VITM28_700136,430428010.074
Map_17QUADGRID 120 × 601----
QUADGRID 160 × 80137,557440200.098
QUADGRID 200 × 100138,084462420.143
ITM3001----
ITM1001----
ITM50137,727428,1350.588
VITM50_700138,756431800.081

References

  1. De Ryck, M.; Versteyhe, M.; Debrouwere, F. Automated guided vehicle systems, state-of-the-art control algorithms and techniques. J. Manuf. Syst. 2020, 54, 152–173. [Google Scholar] [CrossRef]
  2. Oyekanlu, E.A.; Smith, A.C.; Thomas, W.P.; Mulroy, G.; Hitesh, D.; Ramsey, M.; Kuhn, D.J.; Mcghinnis, J.D.; Buonavita, S.C.; Looper, N.A. A review of recent advances in automated guided vehicle technologies: Integration challenges and research areas for 5G-based smart manufacturing applications. IEEE Access 2020, 8, 202312–202353. [Google Scholar] [CrossRef]
  3. Fragapane, G.; Ivanov, D.; Peron, M.; Sgarbossa, F.; Strandhagen, J.O. Increasing flexibility and productivity in Industry 4.0 production networks with autonomous mobile robots and smart intralogistics. Ann. Oper. Res. 2020, 1–19. [Google Scholar] [CrossRef] [Green Version]
  4. Martínez-Barberá, H.; Herrero-Pérez, D. Autonomous navigation of an automated guided vehicle in industrial environments. Robot. Comput.-Integr. Manuf. 2010, 26, 296–311. [Google Scholar] [CrossRef]
  5. Eykhoff, P. System Identification; Wiley: New York, NY, USA, 1974; Volume 14. [Google Scholar]
  6. Thrun, S. Robotic mapping: A survey. Explor. Artif. Intell. New Millenn. 2002, 1, 1. [Google Scholar]
  7. Moravec, H.; Elfes, A. High resolution maps from wide angle sonar. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation, St. Louis, MO, USA, 25–28 March 1985; pp. 116–121. [Google Scholar]
  8. Botsch, M.; Kobbelt, L.; Pauly, M.; Alliez, P.; Lévy, B. Polygon Mesh Processing; CRC Press: Boca Raton, FL, USA, 2010. [Google Scholar]
  9. Marton, Z.C.; Rusu, R.B.; Beetz, M. On fast surface reconstruction methods for large and noisy point clouds. In Proceedings of the 2009 IEEE International Conference on Robotics And Automation, Kobe, Japan, 12–17 May 2009; pp. 3218–3223. [Google Scholar]
  10. Latombe, J.-C. Robot Motion Planning; Springer Science & Business Media: Berlin/Heidelberg, Germany, 2012; Volume 124. [Google Scholar]
  11. Fujimura, K. Path planning with multiple objectives. IEEE Robot. Autom. Mag. 1996, 3, 33–38. [Google Scholar] [CrossRef] [Green Version]
  12. Rañó, I.; Minguez, J. Steps towards the automatic evaluation of robot obstacle avoidance algorithms. In Proc. of Workshop of Benchmarking in Robotics, in the IEEE/RSJ Int. Conf. on Intelligent Robots and Systems (IROS); IEEE: Beijing, China, 2006; Volume 88, pp. 90–91. [Google Scholar]
  13. Tsardoulias, E.; Iliakopoulou, A.; Kargakos, A.; Petrou, L. A review of global path planning methods for occupancy grid maps regardless of obstacle density. J. Intell. Robot. Syst. 2016, 84, 829–858. [Google Scholar] [CrossRef]
  14. Plaku, E.; Kavraki, L.E.; Vardi, M.Y. Impact of workspace decompositions on discrete search leading continuous exploration (DSLX) motion planning. In Proceedings of the 2008 IEEE International Conference on Robotics and Automation, Pasadena, CA, USA, 19–23 May 2008; pp. 3751–3756. [Google Scholar]
  15. Aggarwal, R.; Kumar, M. Chance-Constrained Approach to Optimal Path Planning for Urban UAS. In AIAA Scitech 2020 Forum; American Institute of Aeronautics and Astronautics, Inc.: Orlando, FL, USA, 2020; p. 0857. [Google Scholar]
  16. Liu, Y.; Jiang, Y. Robotic Path Planning Based on a Triangular Mesh Map. Int. J. Control. Autom. Syst. 2020, 18, 2658–2666. [Google Scholar] [CrossRef]
  17. van Toll, W.; Triesscheijn, R.; Kallmann, M.; Oliva, R.; Pelechano, N.; Pettré, J.; Geraerts, R. Comparing navigation meshes: Theoretical analysis and practical metrics. Comput. Graph. 2020, 91, 52–82. [Google Scholar] [CrossRef]
  18. Kallmann, M. Shortest Paths with Arbitrary Clearance from Navigation Meshes. In Symposium on Computer Animation; Eurographics Association: Madrid, Spain, 2010; pp. 159–168. [Google Scholar]
  19. Oliva, R.; Pelechano, N. A generalized exact arbitrary clearance technique for navigation meshes. In Proceedings of Motion on Games; Association for Computing Machinery: New York, NY, USA, 2013; pp. 103–110. [Google Scholar]
  20. Guimarães, R.L.; de Oliveira, A.S.; Fabro, J.A.; Becker, T.; Brenner, V.A. ROS navigation: Concepts and tutorial. In Robot Operating System (ROS); Springer: Berlin/Heidelberg, Germany, 2016; pp. 121–160. [Google Scholar]
  21. Fernandes, E.; Costa, P.; Lima, J.; Veiga, G. Towards an orientation enhanced astar algorithm for robotic navigation. In Proceedings of the 2015 IEEE International Conference on Industrial Technology (ICIT), Seville, Spain, 17–19 March 2015; pp. 3320–3325. [Google Scholar]
  22. Cuillière, J.-C.; Francois, V. Integration of CAD, FEA and topology optimization through a unified topological model. Comput.-Aided Des. Appl. 2014, 11, 493–508. [Google Scholar] [CrossRef]
  23. Kumar, G.S.; Kalra, P.K.; Dhande, S.G. Curve and surface reconstruction from points: An approach based on self-organizing maps. Appl. Soft Comput. 2004, 5, 55–66. [Google Scholar] [CrossRef]
  24. Stanimirovic, I.P.; Zlatanovic, M.L.; Petkovic, M.D. On the linear weighted sum method for multi-objective optimization. Facta Acta Univ. 2011, 26, 49–63. [Google Scholar]
  25. Ravankar, A.; Ravankar, A.A.; Kobayashi, Y.; Hoshino, Y.; Peng, C.-C. Path smoothing techniques in robot navigation: State-of-the-art, current and future challenges. Sensors 2018, 18, 3170. [Google Scholar] [CrossRef] [Green Version]
  26. Lamini, C.; Benhlima, S.; Elbekri, A. Genetic algorithm based approach for autonomous mobile robot path planning. Procedia Comput. Sci. 2018, 127, 180–189. [Google Scholar] [CrossRef]
  27. Rekleitis, I.; Bedwani, J.-L.; Dupuis, E. Autonomous planetary exploration using LIDAR data. In Proceedings of the 2009 IEEE International Conference on Robotics and Automation, Kobe, Japan, 12–17 May 2009; pp. 3025–3030. [Google Scholar]
  28. Kallmann, M. Path planning in triangulations. In Proceedings of the IJCAI Workshop on Reasoning, Representation, and Learning in Computer Games, Edinburgh, Scotland, 31 July 2005; pp. 49–54. [Google Scholar]
  29. Mark, d.B.; Otfried, C.; Marc, v.K.; Mark, O. Computational Geometry Algorithms and Applications; Spinger: Berlin/Heidelberg, Germany, 2008. [Google Scholar]
  30. Hart, P.E.; Nilsson, N.J.; Raphael, B. A formal basis for the heuristic determination of minimum cost paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  31. Liu, X.; Gong, D. A comparative study of A-star algorithms for search and rescue in perfect maze. In Proceedings of the 2011 International Conference on Electric Information and Control Engineering, Wuhan, China, 15–17 April 2011; pp. 24–27. [Google Scholar]
  32. Fabbri, R.; Costa, L.D.F.; Torelli, J.C.; Bruno, O.M. 2D Euclidean distance transform algorithms: A comparative survey. ACM Comput. Surv. (CSUR) 2008, 40, 1–44. [Google Scholar] [CrossRef]
  33. Lau, B.; Sprunk, C.; Burgard, W. Efficient grid-based spatial representations for robot navigation in dynamic environments. Robot. Auton. Syst. 2013, 61, 1116–1130. [Google Scholar] [CrossRef]
  34. Cuillière, J.-C. An adaptive method for the automatic triangulation of 3D parametric surfaces. Comput.-Aided Des. 1998, 30, 139–149. [Google Scholar] [CrossRef]
  35. François, V.; Cuilliere, J.-C. 3D automatic remeshing applied to model modification. Comput.-Aided Des. 2000, 32, 433–444. [Google Scholar] [CrossRef]
  36. Cuillière, J.-C.; François, V.; Lacroix, R. A new approach to automatic and a priori mesh adaptation around circular holes for finite element analysis. Comput.-Aided Des. 2016, 77, 18–45. [Google Scholar] [CrossRef]
  37. François, V.; Cuillière, J.-C. Automatic mesh pre-optimization based on the geometric discretization error. Adv. Eng. Softw. 2000, 31, 763–774. [Google Scholar] [CrossRef]
  38. Clearpath Robotics Inc. Turtlebot-2-Open-Source-Robot. Available online: https://clearpathrobotics.com/turtlebot-2-open-source-robot/ (accessed on 9 April 2022).
Figure 1. Methodology for calculation of distance when the checking point is not placed inside any cell. 1.0 shows the minimum number in a grid, but some values can be calculated based on the edge of nodes shared with obstacles boundaries.
Figure 1. Methodology for calculation of distance when the checking point is not placed inside any cell. 1.0 shows the minimum number in a grid, but some values can be calculated based on the edge of nodes shared with obstacles boundaries.
Robotics 11 00050 g001
Figure 2. Different paths for a fixed scenario in an environment according to different representations. (a) A GRID 200 × 100. (b) An ITM-700. (c) A VITM-100-700.
Figure 2. Different paths for a fixed scenario in an environment according to different representations. (a) A GRID 200 × 100. (b) An ITM-700. (c) A VITM-100-700.
Robotics 11 00050 g002
Figure 3. Different paths for the medium-size obstacle scenario considering the inflation layer. (a) A GRID 200 × 100. (b) An ITM-700. (c) A VITM-100-700.
Figure 3. Different paths for the medium-size obstacle scenario considering the inflation layer. (a) A GRID 200 × 100. (b) An ITM-700. (c) A VITM-100-700.
Robotics 11 00050 g003
Figure 4. Different paths for some environments. (a) Blue path for Map_10-VITM-30-700. (b) Blue path for Map_8-100-700. (c) Blue path showing the capability of ITM in a maze map. (d) Blue path passing a narrow curvilinear passage by VITM method. (e) Blue path for a narrow passage by GRID 120 × 60 (f) Path in the corridor by GRID 160 × 80 (g) Representation ITM-700 with the generated path on a wide hybrid map (h,i) Two hybrid-narrow-passage environments with VITM representation.
Figure 4. Different paths for some environments. (a) Blue path for Map_10-VITM-30-700. (b) Blue path for Map_8-100-700. (c) Blue path showing the capability of ITM in a maze map. (d) Blue path passing a narrow curvilinear passage by VITM method. (e) Blue path for a narrow passage by GRID 120 × 60 (f) Path in the corridor by GRID 160 × 80 (g) Representation ITM-700 with the generated path on a wide hybrid map (h,i) Two hybrid-narrow-passage environments with VITM representation.
Robotics 11 00050 g004
Table 1. The length, minimum distance to obstacle, complexity, and cost function values for three sample representations for a sample map with a fixed scenario.
Table 1. The length, minimum distance to obstacle, complexity, and cost function values for three sample representations for a sample map with a fixed scenario.
RepresentationsCalculated Parametersf (Single Criteria)
ItemTypeSizeLength (mm)Min Distance (mm)ComplexityCost Function
1QUADGRID 200 × 10010,9922583230.145
2ITM70010,7491551340.006
3VITM100_70010,521191770.007
Table 2. Best representation for each environment according to f, cost function values without inflation.
Table 2. Best representation for each environment according to f, cost function values without inflation.
MAPEnvironment DescriptionRepresentation with the Lowest f ValueMAPEnvironment DescriptionRepresentation with the Lowest f Value
Map_1Small obstacleITM-700Map_9Regular different sizeITM-700
Map_2Medium polygonal obstacleITM-700Map_10Irregular obstaclesITM-700
ITM-500
VITM-100-700
Map_3Medium circular obstacleITM-700Map_11Irregular two groupsITM-700
ITM-500
VITM-100-700
Map_4Space with dividersITM-700Map_12Irregular circular obstaclesITM-700
Map_5narrow passageITM-700Map_13Irregular different shape obstaclesITM-700
Map_6Curvilinear passageITM-700Map_14Hybrid with wide-spaced obstaclesITM-700
Map_7Regular obstaclesITM-700Map_15Corridor and dividersITM-700
Map_8Regular two groupsITM-700Map_16,17Hybrid narrow-space environmentsVITM-28-700
VITM-100-700
Table 3. The length, minimum distance to obstacle, complexity, and cost function values for three sample representations considering the inflation layer.
Table 3. The length, minimum distance to obstacle, complexity, and cost function values for three sample representations considering the inflation layer.
RepresentationsCalculated ParametersF (Single Criteria)
ItemTypeSizeLength (mm)Min Distance (mm)ComplexityCost Function
1QUADGRID 200 × 10010,9922275550.132
2ITM70010,878985320.013
3VITM100_70010,469483270.009
Table 4. Best representation for each environment according to f, cost function values with consideration of the inflation layer.
Table 4. Best representation for each environment according to f, cost function values with consideration of the inflation layer.
MAPEnvironment DescriptionRepresentation with the Lowest f ValueMAPEnvironment DescriptionRepresentation with the Lowest f Value
Map_1Small obstacleITM-500Map_9Regular different sizeITM-700
VITM-100-700GRID 100 × 50
Map_2Medium polygonal obstacleVITM-100-700Map_10Irregular obstaclesVITM-30-700
Map_3Medium circular obstacleITM-700Map_11Irregular two groupsITM-500
Map_4Space with dividersITM-700Map_12Irregular circular obstaclesITM-700
Map_5narrow passageVITM-50-700Map_13Irregular different shape obstaclesVITM-100-700
GRID 100 × 50
Map_6Curvilinear passageVITM-50-700Map_14Hybrid with wide-spaced obstaclesITM-700
Map_7Regular obstaclesGRID 100 × 50Map_15Corridor and dividersVITM-50-700
GRID 100 × 50
Map_8Regular two groupsVITM-100-700Map_16,17Hybrid narrow-space environmentsGRID 120 × 60
VITM-28-700
GRID 100 × 50VITM-50-700
GRID 160 × 80
Table 5. Average of cost function value on all environments, without and with inflation, and its ratio.
Table 5. Average of cost function value on all environments, without and with inflation, and its ratio.
Repsfwithout_inflfwith_inflfwith/fwithout
QUAD0.1140.0890.78
ITM0.0380.2175.71
VITM0.0160.0362.25
Table 6. Average of complexity value for all environments and each representation type.
Table 6. Average of complexity value for all environments and each representation type.
RepsQUADITMVITM
Average Complexity395842441453
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Meysami, A.; Cuillière, J.-C.; François, V.; Kelouwani, S. Investigating the Impact of Triangle and Quadrangle Mesh Representations on AGV Path Planning for Various Indoor Environments: With or Without Inflation. Robotics 2022, 11, 50. https://doi.org/10.3390/robotics11020050

AMA Style

Meysami A, Cuillière J-C, François V, Kelouwani S. Investigating the Impact of Triangle and Quadrangle Mesh Representations on AGV Path Planning for Various Indoor Environments: With or Without Inflation. Robotics. 2022; 11(2):50. https://doi.org/10.3390/robotics11020050

Chicago/Turabian Style

Meysami, Ahmadreza, Jean-Christophe Cuillière, Vincent François, and Sousso Kelouwani. 2022. "Investigating the Impact of Triangle and Quadrangle Mesh Representations on AGV Path Planning for Various Indoor Environments: With or Without Inflation" Robotics 11, no. 2: 50. https://doi.org/10.3390/robotics11020050

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop