Next Article in Journal
Simultaneous Prediction of Soil Properties Using Multi_CNN Model
Previous Article in Journal
Energy Harvested and Cooperative Enabled Efficient Routing Protocol (EHCRP) for IoT-WBAN
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Graph Search-Based Exploration Method Using a Frontier-Graph Structure for Mobile Robots

Department of Mechatronics Engineering, Kangwon National University, Chuncheon KR24341, Korea
Sensors 2020, 20(21), 6270; https://doi.org/10.3390/s20216270
Submission received: 14 August 2020 / Revised: 26 October 2020 / Accepted: 2 November 2020 / Published: 3 November 2020
(This article belongs to the Section Remote Sensors)

Abstract

:
This paper describes a graph search-based exploration method. Segmented frontier nodes and their relative transformations constitute a frontier-graph structure. Frontier detection and segmentation are performed using local grid maps of adjacent nodes. The proposed frontier-graph structure can systematically manage local information according to the exploration state and overcome the problem caused by updating a single global grid map. The robot selects the next target using breadth-first search (BFS) exploration of the frontier-graph. The BFS exploration is improved to generate an efficient loop-closing sequence between adjacent nodes. We verify that our BFS-based exploration method can gradually extend the frontier-graph structure and efficiently map the entire environment, regardless of the starting position.

1. Introduction

Mapping is one of the most critical prerequisites for mobile robots performing various high-level tasks. Simultaneous localization and mapping (SLAM) algorithms construct maps of the environment around a robot while localizing the robot at the same time using continuously received sensor data [1,2,3]. For two decades, many researchers have developed various SLAM algorithms to improve the accuracy of SLAM states in terms of global consistency under the accumulated sensor error caused by large motion sequences. However, SLAM does not select the next target destination for efficient mapping, and only focuses on estimating the state of the robot.
Classic exploration methods find a path that increases information about the environment [4,5,6]. They rely on detecting frontier areas, edges between empty and unknown/unexplored areas. Because these are usually at the limit of the sensors’ range, the robot has a higher probability of obtaining new information about unexplored areas at frontiers than at non-frontier positions. The purpose of frontier-based exploration methods is full coverage of the environment, rather than accuracy of the mapping and localization states.
Instead of considering the mapping coverage, active localization algorithms increase localization accuracy by only calculating a target position within the previously constructed map [7,8]. Active localization algorithms can be combined with path planning algorithms, and are suitable for maintaining the uncertainty of the localization state below a certain level while the robot heads towards its destination.
Integrated exploration, also known as active SLAM, plans a path to improve localization accuracy and increase mapping coverage in an unknown environment [9]. Most integrated exploration algorithms employ the concept of information gain to select the next target candidates for localization and mapping [10,11] and define a cost function based on the information gain to choose one target position. The final result of the integrated exploration algorithm should be an accurate map of the entire environment. Many integrated exploration algorithms detect frontiers using a grid map to guarantee the mapping coverage. The frontier areas can also be detected on dense point cloud maps or continuous representations for environments. Detecting frontier areas and inspecting the mapping coverage can be easy from a grid map because mapped empty areas and unmapped areas are clearly distinguished on grid maps. Although the basic SLAM framework of integrated exploration constructs a feature map or a pose graph for state estimation, a grid map is also produced whenever the robot needs to detect frontiers [12,13]. At this time, the estimated trajectory and corresponding measurements at each pose are used to construct one global grid map.
This paper presents an integrated exploration method that constructs a frontier-graph structure using a local grid map and selects the next exploration target based on this frontier-graph. We address the exploration problems in two-dimensional (2D) environments. The proposed frontier-graph is based on detecting frontier information on grid maps. If we define a frontier area in three-dimensional (3D) representations, the proposed approach can be extended to 3D exploration problems. But, in this paper, we think over 2D exploration problems. The previous integrated exploration approaches that maintain one global grid map can suffer from decreasing efficiency due to the growing size of the map as exploration proceeds. To overcome this, we propose a method that uses several local maps assigned to frontier positions. Unlike most previous approaches that use extracted frontier information to decide just the next target, and do not manage them systematically for further exploration steps, we construct a frontier-graph structure from the frontier nodes on each local map. The frontier-graph structure shows the exploration priority of the adjacent frontier nodes, and we can obtain a loop-closing path, as necessary for the global consistency of SLAM. Therefore, the loop-closure of the SLAM algorithms can be induced by the proposed exploration approach.
The remainder of this paper is organized as follows. Section 2 summarizes related work. In Section 3, we present the frontier-graph structure constructed by the frontier cell segmentation using a local grid map. In Section 4, we present an improved graph-search-based exploration method, breadth-first search exploration, to select the next target node. Section 5 shows simulation results in a well-known benchmark environment to compare the efficiency of two graph-search-based exploration methods. In Section 6, we present our conclusions.

2. Related Work

Many integrated exploration algorithms detect frontier areas on grid maps to complete mapping for the whole environment. Several works maintain only a feature map and do not depend on the grid map [14,15,16]. In these cases, their target environments are usually simple, and the purpose is to achieve accurate state estimation rather than full coverage.
Frontier-based integrated exploration algorithms repeat the following three steps until no frontier cells are detected on a global grid map: identifying frontier cells, evaluating the frontier cells using a defined utility function, and selecting the next target. Researchers have mainly studied how to define an appropriate utility or cost function to evaluate the localization and mapping uncertainty reduction at each frontier area. A balanced utility function, which independently calculates the localization uncertainty based on a feature-based map and expected information gain on a grid map, was proposed in [17]. In this approach, an Extended Kalman Filter (EKF) is used for the SLAM estimation problem.
An entropy-based utility function that calculates the joint map and path entropy decrease has also been proposed [10,18]. One study [10] used a Rao-Blackwellized particle filter (RBPF) to estimate and represent the posterior of the map and the robot’s trajectory. Unlike the EKF, the RBPF can be performed in not only feature-based maps, also grid maps. Only one type of map representation, the grid map, was used for both SLAM estimation and frontier detection. The expected information gain along each action sequence for candidate frontier positions was computed by generating the expected measurement on the grid map. Another study [18] employed a pose graph-SLAM as the estimation framework. The pose graph-SLAM maintains the robot’s pose trajectory in the form of a sparse graph [19,20]. It optimizes the graph using relative motion constraints that connect the pose nodes via sensory data. Because the graph-SLAM algorithm does not use a grid representation for state estimation, two studies [11,18] constructed a global grid map using the mean pose of the node in the graph, then used the corresponding raw sensor data or log-odds of the grid map to extract the frontier information.
In the above grid map-based exploration methods, each grid cell shows the binary occupancy information of the corresponding position in the environment. In two studies [21,22], a Gaussian processes (GPs) occupancy map was constructed, with each cell of the GP map containing a continuous occupancy probability. Using GPs’ high-dimensional map inference and a mutual information-based greedy exploration strategy, one of these studies [21] completed mapping for the entire environment with fewer observations than standard binary grid mapping. To learn GP parameters, a study [22] applied a Rapidly Exploring Random Tree (RRT) search guiding a robot towards unvisited informative locations.
Recently, deep learning approaches have been applied to the selection of the next-best-view position on the grid map during integrated exploration. One study [23] proposed an exploration architecture that uses a deep reinforcement learning model to integrate common knowledge in office floor plans. Another study [24] used a deep neural network to predict a robot’s most informative exploratory action.
Most of the methods mentioned above focused on two actions [25]. The first is exploration to select the most informative frontier position on a global grid map constructed through accumulated sensor data until the time of the decision. The aim of this action is to increase the robot’s knowledge of the environment. The second action is exploration that leads the robot to the already mapped areas to reduce the SLAM state uncertainty through active loop-closing. These actions are evaluated on the current global grid map. As the exploration proceeds, the size of the global grid map increases. The growing size of the global map means that the number of candidate positions or actions to be evaluated becomes large. This affects the overall exploration efficiency for achieving full coverage, because frontier-based exploration continues until there is no frontier on the global grid map. The Wavefront Frontier Detector (WFD) and Fast Frontier Detector (FFD) were proposed to avoid processing all the data characterizing the growing grid map [26]. WFD is a graph-search-based algorithm that evaluates only known/observed areas. FFD examines only newly obtained laser measurements to detect frontier cells.
The conventional integrated exploration approaches select the next exploration target from the newly detected frontier regions and previously visited regions on the robot’s trajectory. These next target candidates are re-calculated for each decision, but they are not systematically managed for further decisions. Moreover, the efficiency of frontier-based exploration algorithms depends on the frontier information on the grid map. The global grid map used for detecting frontier regions is continuously merged with the current sensor data based on the current robot position obtained from the SLAM algorithm. The resulting global grid map and its frontier information are affected by the SLAM state’s accuracy. Prior to loop-closing, the uncertainty of the SLAM estimation becomes larger as the travel distance increases [3,27]. In general, it is difficult to correct the occupancy information using a single global grid map unless the robot accesses all the past trajectories and corresponding sensor measurements. In terms of efficient exploration, we need a systematic map updating strategy when the robot’s pose accuracy has been recovered by loop-closing.
Local map-based exploration methods have previously been proposed [28,29] to overcome the inefficiencies that arise due to dependence on one global grid map for detecting frontier cells and to systematically organize the target candidates. In local map-based exploration, the frontier cells are detected from a local map constructed based on current sensor measurements, not from the global grid map. A representative cell is selected among the local frontier cells, and the representative cell and local map are registered to the frontier-tree structure as a node. The relative transformation between the frontier nodes becomes the edge of the frontier-tree. We can efficiently extract real frontier cells, which are frontiers in both the current local map and the local maps of the adjacent nodes, using the frontier-tree structure and map merging process. Moreover, we can select the next target node of the frontier-tree structure according to the exploration priority using two graph search-based exploration methods, depth-first search (DFS) exploration or breadth-first search (BFS) exploration, i.e., a loop-closing event can be induced efficiently using frontier-tree structure. If global consistency of the edge between the frontier nodes is achieved by loop-closing, the local maps of the corresponding loop nodes are merged using the corrected edge information. The local maps of the loop nodes are updated to the merged map.
In this paper, we extend these works in three respects. First, we refine the database of the frontier-graph structure by focusing on the integrated exploration itself, and improve a method for segmenting frontier cells. Segmenting the frontier cells and calculating the frontier node of each segment is crucial to the exploration efficiency. Second, we present a method to register frontier nodes that makes an efficient loop-closing sequence. Furthermore, we compare BFS exploration and DFS exploration using a publicly available environment. This paper assumes that a robot has a 360 scanning range sensor to obtain range measurements for all directions. It means that we do not consider the issues about sensing coverage according to the robot’s orientation. The proposed exploration approach decides the next target position but not the robot’s orientation on the target position.

3. Frontier-Graph Structure

In our previous works, we proposed a method to extract frontier nodes on a local grid map and construct the frontier-tree for local map-based exploration [28,29]. In this paper, we rename the frontier-tree to obtain a frontier-graph that represents the proposed frontier node-edge structure. The frontier nodes and their relative transformations constitute a graph. However, there are several loops, and the nodes have hierarchical relationships: root, parent, and child nodes, unlike in the case of a general graph. We present the tree-like graph structure containing the frontier information.
In this section, we elaborate on the frontier-graph structure used for local map-based exploration. Figure 1 shows the overall process of the integrated exploration using the frontier-graph structure and the corresponding local maps. The integrated exploration algorithm consists of three sub-processes: SLAM, exploration, and path planning. When local sensor data are obtained, the SLAM algorithm estimates the state vector, which contains the pose of the robot and representation of the environment. Using the estimated pose of the robot and local sensor data, the exploration algorithm detects frontier regions and decides the next destination. Then the robot goes to the next destination along the safe path calculated by the path planning algorithm, until it reaches its destination. In this paper, we assume that the SLAM and path planning algorithm performs adequately to estimate the pose of the robot and steer it to the target position at the desired frequency. We focus on the function of the exploration algorithm that selects the next target destination for expanding the map information or reducing the uncertainty of the robot’s pose by loop-closing.

3.1. Constructing Frontier-Graph Structure Using Local Maps

3.1.1. Frontier-Graph Database

From the perspective of the proposed local map-based exploration method for constructing the frontier-graph, exploration is the sequential process of expanding the graph by detecting and adding frontier nodes until new nodes are no longer discovered. Eventually, the entire environment is modeled as distributed nodes and edges between these nodes. Before we present details on the frontier-graph, we define the frontier area and the non-frontier area for the sake of clarity. A frontier area is an edge segment that separates the known (explored) empty regions from unknown (unexplored) regions. It can be an unknown cell next to known empty cells or a known empty cell next to unknown cells. In this paper, the frontier area is defined as a known empty cell next to unknown cells. The position of the frontier area can be the next exploration target, and it needs to be empty so that the robot can arrive there. A non-frontier area is a grid cell that is not a frontier cell. Table 1 shows the components of the frontier node and local grid map database (DB) for the frontier-graph structure. There are two types of DB: frontier node DB ( N o d e ) and local map DB ( M a p ). The frontier node DB includes geometric information regarding the frontier segments and exploration state. The local map DB stores local grid map information of each visited frontier node.
Each node, n o d e i d , has its own identification number ( i d ). If a new representative node of the frontier segment is selected from the current node’s local grid map, the new node is registered to the frontier node DB as the child of the current node. i d parent is the ID of the parent node, and c e l l s i d stores the metric position of each frontier cell in n o d e i d ’s segment. Because the newly detected frontier node means that it has not been explored yet, the ID of the local grid map, i d map , is initially set to 0. When the robot arrives at the node and obtains the local grid map, the local grid map is added to the local map DB and the corresponding local map ID is assigned to i d map of n o d e i d . f l a g known is the exploration state, which indicates whether the node has been explored or not. It is F A L S E when the node is initially registered, and transforms to T R U E after the robot has explored the node or the node has been revealed to be a known area on the merged map. f l a g loop closing indicates whether a loop has been closed at the node, and is initially set to F A L S E . If the robot revisits the node and a loop-closing event occurs, it becomes T R U E . If n frontier segments are extracted at the current node, the IDs of the n representative cells are stored in i d child 1 , , i d child n as child nodes.
The root node is the starting position of the exploration process. If the robot detects n frontier segments at the starting position, the information concerning the root node and n child nodes is as follows:
root node : n o d e 1 = 1 , 0 , , 1 , T R U E , F A L S E , 2 , , n + 1
n child nodes : n o d e 2 = 2 , 1 , c e l l s 2 , 0 , F A L S E , F A L S E , , , n o d e n + 1 = n + 1 , 1 , c e l l s n + 1 , 0 , F A L S E , F A L S E ,
We define the root node’s ID to be 1, and its parent’s ID to be 0. Because the robot essentially starts the exploration process in an empty region, the root node does not appertain to any frontier segments: the third component in Equation (1) is . e d g e i , j is the information concerning the relative transformation from n o d e i to n o d e j , and consists of the shortest distance, d i s t i , j , between the two nodes and the geometric relative transformation vector, tr i , j . A general tree structure only has directed edges between the parent and child nodes. In our frontier-graph structures, all child nodes have one parent node, and there are edges between the parent and child nodes. Moreover, because we can compute the relative transformations between child nodes when new child nodes are detected on the local grid map, there are edges between child nodes, i.e., sibling nodes.
If the robot has visited a frontier node, the local grid map is assigned to the node and this local map, along with its ID, is added to the local map DB. g r i d m a p i d of m a p i d contains the grid map data, such as the occupancy probability. i d n o d e 1 , , i d n o d e m shows the IDs of the nodes that share m a p i d , and  p n o d e 1 , , p n o d e m are their positions in m a p i d . One local map has one node at the time that it is added to the local map DB. If the robot constructs a local map at the current n o d e k and there have already been q local maps in the local map DB, the new local map is added as follows:
m a p q + 1 = q + 1 , g r i d m a p q + 1 , k , 0 , 0 , 0 T
The pose of the node on the local grid map is initially set to 0 , 0 , 0 T because the local grid map is constructed at the node. If a loop is closed at the current node, the local maps of nodes that make up the loop will be merged into a larger grid map, and the poses of the loop nodes are corrected on the larger grid map. The map information of the current node, i.e., the loop-closing node, is also updated and contains several nodes and corresponding corrected poses. In other words, the loop nodes with accurate states share the same merged map after loop-closing. An example of the node and map DB before/after loop-closing when the root node has two child nodes is presented in Table 2. The underlined components are the updated components. Notably, the loop-closing state of n o d e 1 , the sixth component, was changed to T R U E .

3.1.2. Frontier Segmentation

If the robot arrives at a new frontier node, the current local grid map is assigned to the current node of the frontier-graph structure. Because the efficiency of the graph-based algorithm depends on the number of nodes, it is crucial to extract real frontier cells and register several representative nodes to the frontier-graph by segmenting real frontier regions. Although conventional frontier-based exploration uses global information from the entire grid map, the proposed local map-based exploration only uses local information to detect frontiers and select the next target. The frontier cells are extracted from the current local grid map. At this time, fake frontier regions, which are frontier regions on the local map that have already been explored so are known regions on the adjacent nodes’ local maps, can be detected. To prevent fake frontier nodes from being registered to the graph and distinguish them from real frontier cells, we merge the local maps of adjacent neighbor nodes. We segment the frontier cells that are frontiers on both the current local map and the merged map.
m a p merged = m a p current m a p current parent m a p current previous
Three adjacent nodes take part in this map merging operation, as in Equation (4). The local maps of the current, parent, and previous nodes are merged. The previous node is the node that the robot has visited just before arriving at the current node. If the previous node is the parent node, two local maps, the local maps of the current and the parent nodes, are merged. In Equation (4), the reference frame of the merged map is the same as the reference frame of the current local map, and the previous and parent local maps have to be transformed with respect to the pose of the current node. Figure 2 shows how local maps and their merged maps are used to detect real frontier cells. In Figure 2d, the robot is at the root node, and only one grid map is used. Two adjacent local maps, the local maps of the current node and parent node, are merged in Figure 2e. Three adjacent local maps, the local maps of the current node, parent node, and previous node, are merged in Figure 2f.
In our previous works, we constructed a polar histogram of the frontier cells with respect to the current robot pose so that we could segment them. To distinguish the disconnected frontier region, we used a threshold value: the number of empty histogram bins between two frontier cells. If the orientation differences in two adjacent frontier cells are higher than the threshold value, two cells are divided into different segments. However, this previous method does not deal with the case where there is a thin obstacle between frontier regions, and the threshold value depends on the size of a grid cell and the distance to the frontier cell. To overcome these problems, we apply an efficient computer vision approach, the connected components labeling (CCL) algorithm [30]. The CCL algorithm is an image segmentation algorithm that assigns a unique label to all pixels of each connected component in a binary image. We convert the local grid map to a binary image where the frontier cells are 1 and the others are 0. Applying the CCL algorithm with 8-connectivity to the frontier binary image, we can obtain several frontier segments and select the representative frontier cell of each segment.
Algorithm 1 shows the new node registration algorithm by frontier segmentation for when the robot arrives at the newly visited node. We describe the algorithm assuming that the current node is n o d e n , the parent node is n o d e n 2 , and the previous node is n o d e n 1 . The current node and the previous node are siblings to each other. In other words, they were detected at the parent node, n o d e n 2 . The map IDs of the parent node and the previous node are M 2 and M 1 . At the current node, the current local grid map is constructed and added to the local map DB according to Equation (3), and the local map ID is M (line 1). The current local map is merged with the local maps of adjacent nodes in line 2. In line 3, we detect frontier cells in the current grid map, g r i d m a p c u r . The empty cells adjacent to unknown/unobserved cells are extracted as the frontier cells. The second input argument, w i n d o w _ s i z e , is the range to check the safety against occupied cells by obstacles. The algorithm inspects whether there are any occupied cells within the window centered each frontier candidate position or not. Among the extracted frontier cells of the local grid map, we select the real frontier cells that are also frontiers on the merged map (lines 4–13). The cell position, r , c T , in the local map is transformed to the position with respect to the merged map frame using the edge DB (line 7), and is inspected by Algorithm 3 (line 8). The real frontier cells are divided into several segments according to their adjacent connectivity using CCL algorithm (line 14). For each frontier segment, we decide the representative frontier node that is the nearest cell to the median of the frontier cell positions in the segment and calculate the edge information about the relative transformation between the current node and the representative cell that becomes a child node (lines 18–22). In addition, we calculate the edge information between the child nodes (line 23), which can be obtained by the composition operator [31], as follows:
tr c h i l d 1 , c h i l d 2 = tr c u r , c h i l d 1 tr c u r , c h i l d 2
The shortest travel distance, d i s t i , j , among the frontier nodes of E d g e , can be determined by the grid-based path-finding algorithm such as A* search algorithm using the local grid map [32].
In our previous works, we added new nodes to the frontier node DB in any order. Here, we propose regisinformation between the child nodestering new nodes according to the solution of the traveling salesman problem (TSP) (line 24). As described in Section 4, we use BFS exploration to select the next target from the frontier nodes, which induces sequential loop-closing from the root node. The robot goes back to the parent node after exploring all child nodes during the “induced” loop-closing, and the nearest child or sibling node was selected as the next target according to the previous method. In this paper, we treat finding an efficient loop-closing path, an efficient exploration order, among the parent and the child nodes as solving a TSP [33,34]. Using the shortest traveling distance, d i s t i , j in E d g e n e w , is the cost matrix of the TSP algorithm, we decide the exploration priority for the current and new nodes. The new nodes are registered to the node DB as the current node’s child nodes in the order of the solution to the TSP (lines 24–26). This means that the higher number of the node’s ID, the higher its priority during the induced loop-closing. Figure 2d–f shows the solutions to the TSP for the current and child nodes (cyan lines).
Algorithm 1 Registration of new nodes by frontier segmentation
Require: 
current local grid map g r i d m a p c u r , frontier-graph database N o d e = n o d e i d | 1 i d N , E d g e , M a p = m a p i d | 1 i d M 1 , size of window for detecting safe frontier cells w i n d o w _ s i z e
Ensure: 
updated frontier-graph database, N o d e , E d g e , M a p
▹ The algorithm assumes that the current node is n o d e n , the parent node is n o d e n 2 , and the previous node is n o d e n 1 . n o d e n and n o d e n 1 are siblings to each other. The map IDs of the parent node and previous node are M 2 and M 1 .
1: add m a p M = M , g r i d m a p M , M , 0 , 0 , 0 T into M a p
2: obtain g r i d m a p m g by merging the adjacent local maps, m a p M 2 , m a p M 1 , m a p M ,
3: g r i d m a p _ f r o n t i e r Detect-Frontier-Cell g r i d m a p c u r , w i n d o w _ s i z e
   ▹ R o w S i z e is the number of rows g r i d m a p _ f r o n t i e r and g r i d m a p c u r .
   ▹ C o l S i z e is the number of columns g r i d m a p _ f r o n t i e r and g r i d m a p c u r .
4: for r = 1 to R o w S i z e do
5:     for c = 1 to C o l S i z e do
6:         if g r i d m a p _ f r o n t i e r r , c = 1 then
7:             r m g , c m g T cell _ coordinate _ transform r , c T , g r i d m a p c u r , g r i d m a p m g , E d g e
8:            if Inspect-Safe-Frontier-Cell r m g , c m g T , w i n d o w _ s i z e , g r i d m a p m g = 0 then
9:                 g r i d m a p _ f r o n t i e r r , c 0
10:            end if
11:         end if
12:     end for
13: end for
14: f r o n t i e r _ s e g m e n t connected _ component _ labeling g r i f m a p _ f r o n t i e r
15: if f r o n t i e r _ s e g m e n t then
16:      r e l a t i v e _ t r a n s
17:      n e w _ N o d e
18:     for all f r o n t i e r i f r o n t i e r _ s e g m e n t do
19:          n o d e i d n e w , t r n , i d n e w Initialize-New-Node f r o n t i e r i , n , i d n e w
20:          n e w _ N o d e n e w _ N o d e n o d e i d n e w
21:          r e l a t i v e _ t r a n s r e l a t i v e _ t r a n s t r n , i d n e w
22:     end for
23:      E d g e n e w calculate _ edge n o d e n , n e w _ N o d e , r e l a t i v e _ t r a n s , g r i d m a p c u r
24:      n e w _ N o d e _ o r d e r e d TSP n o d e n , n e w _ N o d e , E d g e n e w
25:      update _ node _ DB N o d e , n e w _ N o d e _ o r d e r e d
26:      update _ edge _ DB E d g e , E d g e n e w
27: end if
Algorithms 2–4, which are used in Algorithm 1, are to detect frontier cells on a grid map, inspect a safe frontier cell without nearby occupied cells, and initialize new node information, respectively. Algorithm 2 first finds empty cells whose occupancy probability is lower than the empty threshold (lines 4–8). By applying the morphological closing operation to the image that presents 1( T R U E ) for empty regions and 0( F A L S E ) for the other regions, we can remove tiny unknown noise cells between empty cells (line 9). We perform morphological erosion with the closed grid map image (line 10). The windows for the morphological operations, w d w _ c l o s e and w d w _ e r o s i o n , determine how many noise cells are removed and the width of the internal boundary. We obtain the empty regions’ internal boundary by subtracting the eroded image from the closed image (line 11), and the cells consisting of the internal boundary are frontier candidate cells. The safe frontier cells are obtained by inspecting the nearby occupied cells presented in Algorithm 3 (line 14).
Algorithm 2 Frontier cell detection
Require:   g r i d m a p = c e l l i , j 1 i R o w S i z e , 1 j C o l S i z e , w i n d o w _ s i z e
Ensure:   g r i d m a p _ f r o n t i e r
1: function Detect-Frontier-Cell( g r i d m a p , w i n d o w _ s i z e )
2:     set g r i d m a p _ e m p t y = e m p t y i , j e m p t y i , j = 0 , 1 i R o w S i z e , 1 j C o l S i z e
3:     set g r i d m a p _ f r o n t i e r = f r o n t i e r i , j f r o n t i e r i , j = 0 , 1 i R o w S i z e , 1 j C o l S i z e
4:    for all c e l l i , j do
5:        if c e l l i , j < t h empty then
6:            e m p t y i , j 1
7:        end if
8:    end for
9:     g r i d m a p _ e m p t y _ c l o s e image _ morph _ close g r i d m a p _ e m p t y , w d w _ c l o s e
10:     g r i d m a p _ e m p t y _ e r o s i o n image _ morph _ erosion g r i d m a p _ e m p t y , w d w _ e r o s i o n
11:     g r i d m a p _ e m p t y _ e d g e g r i d m a p _ e m p t y _ c l o s e g r i d m a p _ e m p t y _ e r o s i o n
12:    for all g r i d _ e m p t y _ e d g e i , j g r i d m a p _ e m p t y _ e d g e do
13:        if g r i d _ e m p t y _ e d g e i , j = 1 then
14:            f r o n t i e r i , j Inspect-Safe-Frontier-Cell i , j T , w i n d o w _ s i z e , g r i d m a p
15:        end if
16:    end for
17:    return g r i d m a p _ f r o n t i e r
18: end function
Algorithm 3 counts the occupied and unknown cells around a frontier candidate cell (lines 5–13). If there are no occupied cells and the number of unknown cells is higher than the threshold around one frontier cell, we classify the cell as a safe frontier cell (lines 14–16). Figure 3 shows an example of how to detect safe frontier cells using morphological operations. The safe frontier cells are indicated as red stars in Figure 3d.
Algorithm 4 initializes a new node for each frontier segment. The representative node position that could be the robot’s exploration target position in future steps is determined to be the nearest cell to the median of the frontier segment cells (lines 2–4). The edge information defined by the relative transformation between two nodes is also calculated (line 5). With the metric positions of the frontier segment cells with respect to the current node, the new node is initialized and registered as a child of the current node (lines 6–11).
Algorithm 3 Safety inspection of a frontier cell
Require: empty cell position r , c T , size of window for detecting safe frontier cells w i n d o w _ s i z e , g r i d m a p = c e l l i , j 1 i R o w S i z e , 1 j C o l S i z e
Ensure:  f l a g frontier
1: function Inspect-Safe-Frontier-Cell( r , c T , w i n d o w _ s i z e , g r i d m a p )
2:      f l a g frontier 0
3:      n u m b e r _ o f _ u n k n o w n 0
4:      n u m b e r _ o f _ o c c u p i e d 0
5:     for p = r round w i n d o w _ s i z e / 2 to r + round w i n d o w _ s i z e / 2 do
6:         for q = c round w i n d o w _ s i z e / 2 to c + round w i n d o w _ s i z e / 2 do
7:            if c e l l p , q > t h occupied then
8:                 n u m b e r _ o f _ o c c u p i e d n u m b e r _ o f _ o c c u p i e d + 1
9:            else if c e l l p , q > t h empty then
10:                 n u m b e r _ o f _ u n k n o w n n u m b e r _ o f _ u n k n o w n + 1
11:            end if
12:         end for
13:     end for
14:     if n u m b e r _ o f _ o c c u p i e d < 1 and n u m b e r _ o f _ u n k n o w n > t h num _ unknown then
15:          f l a g frontier 1
16:     end if
17:     return f l a g frontier
18: end function
Algorithm 4 New node initialization
Require:  cell positions of one frontier segment c e l l s _ f r o n t i e r , the current node’s ID i d c u r , a new frontier node’s ID i d n e w
Ensure:  n o d e i d n e w , t r i d c u r , i d n e w
1: function Initialize-New-Node( c e l l s _ f r o n t i e r , i d c u r , i d n e w )
2:      r m , c m T calculate _ median _ position c e l l s _ f r o n t i e r
3:      r r e p , c r e p T arg min p , q T c e l l s _ f r o n t i e r p r m 2 + q c m 2
4:      x r e p , y r e p T find _ metric _ position r r e p , c r e p T , g r i d m a p c u r
5:      t r i d c u r , i d n e w x r e p , y r e p , 0 T
6:      c e l l s i d n e w
7:     for all p , q T c e l l s _ f r o n t i e r do
8:          x , y T find _ metric _ position p , q T , g r i d m a p c u r
9:          c e l l s i d n e w c e l l s i d n e w x , y T
10:     end for
11:      n o d e i d n e w i d n e w , i d c u r , c e l l s i d n e w , 0 , F A L S E , F A L S E ,
12:     return n o d e i d n e w , t r i d c u r , i d n e w
13: end function

3.2. Updating Frontier-Graph Structure by Loop-Closing

We register new frontier nodes as child nodes to the frontier-graph structure when the robot arrives at the previously unexplored node and detects safe frontier cells. We update the node and local map DB if the SLAM algorithm corrects the edge information by loop-closing. The SLAM algorithm deals with detecting the loop-closing event and the consequent state update, and is beyond the scope of this paper. We focus on how to update the proposed frontier-graph structure after loop-closing.
There are two types of loop-closing events: induced loop-closing and accidental loop-closing. Induced loop-closing is intentionally performed using the exploration algorithm to select the next target. Accidental loop-closing is caused by the property of the local map-based approach, namely that the robot only depends on adjacent local information to inspect the exploration state of the nodes, whether explored or not. This is the case when the robot revisits the same node by chance. The robot does not realize that the target node has already been explored or is very close to a previously visited node.
In induced loop-closing from a child node to its parent node, the loop sequence is distinct. We can obtain the node hierarchy from the frontier-graph, and the sequence is composed of the parent node and explored child nodes, as follows:
n o d e parent n o d e child 1 n o d e child 2 n o d e child n n o d e parent
We can obtain the loop constraint from the edge information of the node DB, and the SLAM algorithm optimizes and corrects the corresponding states according to the constraint. Based on the corrected edge information, the local maps are merged into a larger map, and the loop nodes are computed with respect to the parent node.
In accidental loop-closing, we first must find a sequence that is not composed of just a parent node and its child nodes. To do this, we find a path from the revisited node (the start node) to the previous node (the target node) using the edge information of the node DB and a shortest path algorithm for graphs, such as Dijkstra’s algorithm. This path, together with the current node, makes the following loop sequence:
n o d e revisited n o d e s 1 n o d e s n n o d e previous n o d e current n o d e revisited
The edge between the current node and the revisited node is acquired from SLAM’s loop-closure detection. We update the edge and local maps of the loop nodes in the same manner as induced loop-closing. We also register the edges between the current and revisited nodes’ neighbor nodes.
Figure 4 shows the updated edges after accidental loop-closing. Considering the fact that the current and revisited nodes are close to each other, it is reasonable to think that the current node and the revisited node share the same parent and child nodes. In Figure 4, we generate the edge that links the parent node ( n o d e p 2 ) of the current node ( n o d e i ) and the revisited node ( n o d e i ). The parent node ( n o d e p 1 ) of the revisited node and the current node are connected. Edges between the current node and the revisited node’s children are created. Using this additional edge registration, two parts that are distant from each other in the graph structure, but close together in the geometric structure, will be connected.

4. Graph-Search-Based Exploration for Frontier-Graph Structure

One of the essential aspects of exploration is to efficiently select the next target according to priority. We can recognize exploration priority by inspecting the exploration state and adjacency of the frontier-graph structure’s nodes. We can induce a loop-closing event by going back to a previously explored adjacent node or making the robot go to the nearest unexplored node by traversing the edges of the graph.
In the BFS exploration, unexplored sibling nodes have a higher priority than child nodes [29]. If all sibling nodes have been explored and have local maps, the robot goes back to the parent node for loop-closing. Until then, BFS exploration prefers to improve the accuracy and consistency between the registered nodes rather than add new nodes to expand the mapped area. However, the DFS selects the nearest unexplored child node as the next target until the robot reaches a leaf node that has no child nodes [28]. When new frontier nodes are not detected at the current node, the robot returns to the parent node. This means that the number of nodes increases until we arrive at the leaf node. In simple corridor environments with closed walls at both ends, the DFS performs efficiently because the walls become leaf nodes. However, in complex or large environments, the efficiency of DFS-based exploration depends on the loop-detection performance of SLAM. If no opportunity for accidental loop-closing is detected, updating the node DB and merging the local maps are delayed, and there is a higher probability of adding fake frontier nodes. This issue becomes severe where there is a structural loop in the environment. The robot continuously adds new nodes while traveling multiple times around the loop, until loop-closing occurs by chance. To efficiently manage the number of frontier nodes according to the consecutive map merging from the beginning of the exploration process, we improve BFS exploration in this paper.
The previous BFS exploration algorithm selects the nearest unexplored child node after exploring the parent node, or selects the nearest unexplored sibling node before induced loop-closing to the parent node, i.e., the shortest traveling distance plays a critical role in deciding the next target node. In this paper, we applied the TSP solution to register new child nodes in Section 3.1.2. This is used to find an efficient loop-closing sequence, and we improve BFS-based exploration using the loop-closing sequence obtained from the solution to the TSP.
Algorithm 5 shows the improved BFS exploration using the solution to the TSP. First, the robot inspects whether there are unexplored siblings or not (line 1) using the component f l a g known in the node DB. If unexplored sibling nodes are recognized, the robot selects the next node from these. At this time, among several unexplored siblings, the node next to the current node along the node sequence obtained from the solution to the TSP is selected (line 3). If all siblings have been explored, we consider the loop-closing state f l a g loop closing of the parent node. If loop-closing has not been completed at the parent node, the robot goes to the parent node to close the loop composed of the parent, current, and sibling nodes (lines 4 and 5). The fact that loop-closing has not been performed at the current node means that there have not been sufficient measurements to make loop-constraints between the current node and the child nodes. Therefore, the robot goes to one of the unexplored child nodes to obtain measurements and local maps (line 7). Next, we check the loop-closing state of the siblings and child nodes. The corresponding un-loop-closed node is selected as the next target according to the solution of the TSP (lines 10–16). If loop-closing has been performed at all adjacent nodes and all adjacent nodes’ local maps are merged, the robot goes to the nearest unexplored node (line 20). When there is no unexplored node in the frontier-graph, the exploration process is considered complete.
Algorithm 6 describes a method for finding the next target node of the reference/current node from the TSP solution among adjacent nodes. Because we added new child nodes to the frontier-graph DB in the order of the TSP solution, which makes a loop consisting of adjacent nodes, we can determine the traveling priority between the adjacent nodes through each node’s ID. We arrange the adjacent nodes, N o d e T S P , in the ascending order of each node’s ID (line 2). Next, we find the position of the reference node in the sorted array (line 3). The next target node of the TSP node sequence is at the position next to the reference node. If the reference node’s position is the end of the array, the next node is the first node of the array, because these compose the loop (lines 4–8).
Algorithm 5 Breadth-first search (BFS) exploration to decide the next target node
Require: node DB N o d e , the current node’ ID i d c u r , local map DB M a p
Ensure:  the next target node n o d e n e x t
1: N o d e u n e x p _ s i b l i n g find _ unexplored _ siblings   N o d e , i d c u r
2: if N o d e u n e x p _ s i b l i n g then
3:      n o d e n e x t Find-Next-Node-In-TSP-Solution N o d e u n e x p _ s i b l i n g , i d c u r
4: else if f l a g loop _ closing n o d e p a r e n t = F A L S E then
5:      n o d e n e x t n o d e p a r e n t
6: else if f l a g loop _ closing n o d e c u r = F A L S E then
7:      N o d e u n e x p _ c h i l d find _ unexplored _ child N o d e , i d c u r
8:     n o d e n e x t Find-Next-Node-In-TSP-Solution N o d e u n e x p _ c h i l d , i d c u r
9: else
10:      N o d e u n L C _ s i b l i n g find _ unLoopClosed _ siblings N o d e , i d c u r
11:     if N o d e u n L C _ s i b l i n g then
12:          n o d e n e x t Find-Next-Node-In-TSP-Solution N o d e u n L C _ s i b l i n g , i d c u r
13:     else
14:          N o d e u n L C _ c h i l d find _ unLoopClosed _ child N o d e , i d c u r
15:         if N o d e u n L C _ c h i l d then
16:             n o d e n e x t Find-Next-Node-In-TSP-Solution N o d e u n L C _ c h i l d , i d c u r
17:         else
18:             N o d e u n e x p find _ unexplored N o d e
19:            if N o d e u n e x p then
20:                 n o d e n e x t find _ nearest N o d e u n e x p , i d c u r
21:            else
22:                 n o d e n e x t 0 ▹ The exploration has been completed.
23:            end if
24:         end if
25:     end if
26: end if
Algorithm 6 Next node selection in the solution to the traveling salesman problem (TSP)
Require:  N o d e T S P , the reference node’s ID i d R e f
Ensure:  n o d e n e x t
1: function Find-Next-Node-In-TSP-Solution( N o d e T S P n o d e R e f )
2:      N o d e o r d e r e d sort _ node _ ascend N o d e T S P
3:      p o s R e f find _ node _ position _ in _ node _ array N o d e o r d e r e d , i d R e f
4:     if p o s R e f < N thenN: the number of components in N o d e o r d e r e d
5:          n o d e n e x t p o s R e f + 1 th component of N o d e o r d e r e d
6:     else
7:          n o d e n e x t the first component of N o d e o r d e r e d
8:     end if
9:     return n o d e n e x t
10: end function

5. Simulation Results

We simulated our BFS-based exploration algorithm to verify that it efficiently manages frontier information and merges the local maps assigned to the frontier position from the root node, until the robot has explored the whole environment. We compare BFS- and DFS-based exploration in terms of the nodes’ state in the frontier-graph structure.
We used a publicly available cave-like environment [35] for this comparison. All the simulations were performed in Matlab. We assumed that the robot has a laser range finder (LRF) that scans in all directions (360 ) around the robot. We assume that the SLAM algorithm gives the robot’s state in the global reference frame at every decision step in all simulations, because we focus on the exploration method itself in this paper. However, we only use the SLAM global state to calculate the relative transformation between the frontier nodes. Our local map-based exploration does not depend on SLAM’s global information, and is performed using local information about the frontier nodes, which will be merged incrementally as the exploration proceeds. To merge the local grid maps, the overlapped regions are updated using Bayes’ rule [36]. Figure 5 shows the environment used in the simulations. The robot started the exploration process at 80 different positions (blue dots) for each exploration method. The starting positions were extracted by quadtree cell decomposition [37]. The size of the environment was 20 × 20 m, and it was simulated as a 500 × 500-pixel array. Each local map was constructed using grid cells of 0.1 × 0.1 m size.
Figure 6 and Figure 7 compare the results of the DFS- and BFS-based exploration. Table 3 and Table 4 are the corresponding statistical results. We compared both methods in terms of four criteria. The first is the number of exploration (exp.) steps, which indicates how many steps/decisions were performed until the entire environment had been mapped. The fewer exploration steps needed, the more efficient the exploration method. Next, we compared the number of registered nodes in the frontier-graph structure. Because the local map-based exploration continues its mapping process until there are no unexplored frontier nodes in the graph, it is crucial to detect and register well-distributed frontier nodes to cover the entire environment. If too many nodes have been registered to the graph, then there are repetitive nodes at similar positions, which makes the exploration process inefficient. Active nodes are the frontier nodes that have been actually explored/visited by the robot among the registered frontier nodes of the frontier-graph structure. The number of active nodes is the same as the number of local maps or measurements used for the entire mapping. The total travel distance is the sum of the distance that the robot went along while traversing the shortest path between the current node and the next node.
As shown in Figure 6 and Figure 7, almost every value for BFS exploration is lower than the corresponding value for DFS exploration, except in very few simulations. The difference between the BFS’s results and the DFS’s results was larger in the case of 8 m LRF than 4 m LRF. Moreover, BFS is more stable than DFS for different starting positions. This means that the efficiency of DFS exploration is critically affected by where the robot starts its exploration process. This is because the local map merging by loop-closing is delayed until the leaf node and multiple frontier nodes can be detected at a similar position in the DFS exploration. The environment is not a simple corridor, which made the exploration inefficient before the accidental loop-closing event.
Table 3 and Table 4 explicitly show the effects of varying the starting position for each method. The ratio of the maximum value to the minimum value ranges from 9.0 to 14.4 in the case of DFS-based exploration with 4 m LRF. The DFS exploration’s maximum travel distance is extremely high, 22,278 cells. However, the ratio of the maximum value to the minimum value ranges from 2.0 to 2.6 in the case of BFS. this is relatively low compared to that of DFS-based exploration. In the case of the results from 8 m LRF, the maximum-minimum ratio is in the range 4.4–6.4 for DFS, while it is in the range 1.7–3.1 for BFS.
The robustness of the BFS exploration is validated based on the standard deviation (SD). The SD of the DFS exploration is much higher than that of the BFS exploration. Because the DFS results are very different for each simulation, we need to select the starting position very carefully to use DFS for exploration. However, this does not coincide with the general mapping assumption or situation, in which the process starts in an unknown environment. The SD of the BFS exploration is low, which implies that we can efficiently explore the environment from any starting position using BFS-based exploration. The local maps of the frontier nodes are systematically merged from the root node, and the merged map is critical for deciding whether each locally detected frontier cell is valuable or not. This prevents a fake frontier region in the local map being registered to the frontier-graph as an exploration target. Therefore, BFS-based exploration proceeds under a stable graph structure, in terms of the number of frontier nodes.
Figure 8 shows the resulting frontier-graph structure. The numbers indicate the ID of each frontier node, and ID-1 is the root node and starting position. The starting positions are the same in both simulations. The red lines show the edges between the parent and child nodes. The dotted green lines indicate the edges between sibling nodes. The blue circles are the active frontier nodes, at which the robot arrived and obtained local maps. The white circles are the nodes that were registered to the frontier-graph, but the robot did not visit. In both results, the entire environment is represented by well-distributed frontier nodes and edges between them. We also carried out simulations using another benchmark environment, Freiburg 079 building [35]. This environment is composed of a corridor and several rooms, and its size is 40 × 13.8 m. The 4 m LRF was used, and the grid map was constructed from 0.07 × 0.07 m grid cells. We can see that the frontier nodes are distributed throughout the environment in Figure 9.

6. Conclusions

This paper describes a graph search-based exploration method using frontier detection and segmentation. The proposed method can overcome the difficulty of updating a single global grid map that depends on the exploration state or SLAM in conventional exploration methods. The detected frontier segments on each local grid map and their relative transformations constitute a frontier-graph structure. Because the frontier-graph structure systematically contains the frontier information for the growing map, the robot can gradually construct a map of its environment by traveling along the edges between the frontier nodes.
To select the next exploration target from adjacent frontier nodes, we applied BFS-based exploration that induces incremental map merging by loop-closing from the root node, which is the starting position. Because the proposed method uses only adjacent local information to detect frontiers, BFS is more efficient for exploration than DFS. We verified that BFS-based exploration could achieve more stable results, regardless of the starting position, than DFS-based exploration by carrying out simulations using benchmark environments. Therefore, we can efficiently map unknown environments using the proposed BFS-based exploration method with a frontier-graph structure.
In this paper, we assumed the robot could obtain range measurement in all 360 directions. The field of view of sensors definitely affects exploration efficiency. The reduced field of view sensors can be used for the proposed approach, but the travel distance and the number of active nodes may increase. Taking into account the sensing coverage according to the robot’s orientation will be a valuable future work for a wide range of practical applications.

Funding

This research was supported by a project of Korean government (No. 10073166).

Conflicts of Interest

The author declares no conflict of interest.

References

  1. Debeunne, C.; Vivet, D. A Review of Visual-LiDAR Fusion based Simultaneous Localization and Mapping. Sensors 2020, 20, 2068. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  2. Esparza-Jiménez, J.O.; Devy, M.; Gordillo, J.L. Visual ekf-slam from heterogeneous landmarks. Sensors 2016, 16, 489. [Google Scholar] [CrossRef] [PubMed]
  3. Latif, Y.; Cadena, C.; Neira, J. Robust loop closing over time for pose graph SLAM. Int. J. Robot. Res. 2013, 32, 1611–1626. [Google Scholar] [CrossRef]
  4. Yamauchi, B. Frontier-based exploration using multiple robots. In Proceedings of the Second International Conference on Autonomous Agents, Minneapolis, MN, USA, 9–13 May 1998; pp. 47–53. [Google Scholar]
  5. Shade, R.; Newman, P. Choosing where to go: Complete 3D exploration with stereo. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 2806–2811. [Google Scholar]
  6. Freda, L.; Oriolo, G. Frontier-based probabilistic strategies for sensor-based exploration. In Proceedings of the 2005 IEEE International Conference on Robotics and Automation, Barcelona, Spain, 18–22 April 2005; pp. 3881–3887. [Google Scholar]
  7. Murtra, A.C.; Tur, J.M.M.; Sanfeliu, A. Action evaluation for mobile robot global localization in cooperative environments. Robot. Auton. Syst. 2008, 56, 807–818. [Google Scholar] [CrossRef] [Green Version]
  8. Gottipati, S.K.; Seo, K.; Bhatt, D.; Mai, V.; Murthy, K.; Paull, L. Deep active localization. IEEE Robot. Autom. Lett. 2019, 4, 4394–4401. [Google Scholar] [CrossRef] [Green Version]
  9. Makarenko, A.A.; Williams, S.B.; Bourgault, F.; Durrant-Whyte, H.F. An experiment in integrated exploration. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Lausanne, Switzerland, 30 September–4 October 2002; Volume 1, pp. 534–539. [Google Scholar]
  10. Stachniss, C.; Grisetti, G.; Burgard, W. Information gain-based exploration using rao-blackwellized particle filters. Robot. Sci. Syst. 2005, 2, 65–72. [Google Scholar]
  11. Valencia, R.; Miró, J.V.; Dissanayake, G.; Andrade-Cetto, J. Active Pose SLAM. In Proceedings of the 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems, Algarve, Portugal, 7–12 October 2012; pp. 1885–1891. [Google Scholar]
  12. Carrillo, H.; Dames, P.; Kumar, V.; Castellanos, J.A. Autonomous robotic exploration using occupancy grid maps and graph slam based on shannon and rényi entropy. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 487–494. [Google Scholar]
  13. Juliá, M.; Gil, A.; Reinoso, O. A comparison of path planning strategies for autonomous exploration and mapping of unknown environments. Auton. Robot. 2012, 33, 427–444. [Google Scholar] [CrossRef]
  14. Sim, R.; Roy, N. Global a-optimal robot exploration in slam. In Proceedings of the 2005 IEEE International Conference on Robotics and Automation, Barcelona, Spain, 18–22 April 2005; pp. 661–666. [Google Scholar]
  15. Carrillo, H.; Reid, I.; Castellanos, J.A. On the comparison of uncertainty criteria for active SLAM. In Proceedings of the 2012 IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, 14–18 May 2012; pp. 2080–2087. [Google Scholar]
  16. Amigoni, F.; Caglioti, V. An information-based exploration strategy for environment mapping with mobile robots. Robot. Auton. Syst. 2010, 58, 684–699. [Google Scholar] [CrossRef]
  17. Bourgault, F.; Makarenko, A.A.; Williams, S.B.; Grocholsky, B.; Durrant-Whyte, H.F. Information based adaptive robotic exploration. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Lausanne, Switzerland, 30 September–4 October 2002; Volume 1, pp. 540–545. [Google Scholar]
  18. Vallvé, J.; Andrade-Cetto, J. Potential information fields for mobile robot exploration. Robot. Auton. Syst. 2015, 69, 68–79. [Google Scholar] [CrossRef] [Green Version]
  19. Grisetti, G.; Kümmerle, R.; Stachniss, C.; Burgard, W. A tutorial on graph-based SLAM. IEEE Intell. Transp. Syst. Mag. 2010, 2, 31–43. [Google Scholar] [CrossRef]
  20. Dai, J.; Yan, L.; Liu, H.; Chen, C.; Huo, L. An Offline Coarse-To-Fine Precision Optimization Algorithm for 3D Laser SLAM Point Cloud. Remote Sens. 2019, 11, 2352. [Google Scholar] [CrossRef] [Green Version]
  21. Jadidi, M.G.; Miro, J.V.; Dissanayake, G. Gaussian processes autonomous mapping and exploration for range-sensing mobile robots. Auton. Robot. 2018, 42, 273–290. [Google Scholar]
  22. Viseras, A.; Shutin, D.; Merino, L. Robotic Active Information Gathering for Spatial Field Reconstruction with Rapidly-Exploring Random Trees and Online Learning of Gaussian Processes. Sensors 2019, 19, 1016. [Google Scholar] [CrossRef] [Green Version]
  23. Zhu, D.; Li, T.; Ho, D.; Wang, C.; Meng, M.Q.H. Deep reinforcement learning supervised autonomous exploration in office environments. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, Australia, 21–25 May 2018; pp. 7548–7555. [Google Scholar]
  24. Bai, S.; Chen, F.; Englot, B. Toward autonomous mapping and exploration for mobile robots through deep supervised learning. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 2379–2384. [Google Scholar]
  25. Krause, A.; Guestrin, C. Nonmyopic active learning of gaussian processes: An exploration-exploitation approach. In Proceedings of the 24th International Conference on Machine Learning, Corvallis, OR, USA, 20–24 June 2007; pp. 449–456. [Google Scholar]
  26. Keidar, M.; Kaminka, G.A. Efficient frontier detection for robot exploration. Int. J. Robot. Res. 2013, 33. [Google Scholar] [CrossRef]
  27. Bailey, T.; Nieto, J.; Guivant, J.; Stevens, M.; Nebot, E. Consistency of the EKF-SLAM algorithm. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006; pp. 3562–3568. [Google Scholar]
  28. Ryu, H.; Chung, W.K. Local map-based exploration for mobile robots. Intell. Serv. Robot. 2013, 6, 199–209. [Google Scholar] [CrossRef]
  29. Ryu, H.; Chung, W.K. Local map-based exploration using a breadth-first search algorithm for mobile robots. Int. J. Precis. Eng. Manuf. 2015, 16, 2073–2080. [Google Scholar] [CrossRef]
  30. He, L.; Ren, X.; Gao, Q.; Zhao, X.; Yao, B.; Chao, Y. The connected-component labeling problem: A review of state-of-the-art algorithms. Pattern Recognit. 2017, 70, 25–43. [Google Scholar] [CrossRef]
  31. Smith, R.; Self, M.; Cheeseman, P. Estimating uncertain spatial relationships in robotics. In Autonomous Robot Vehicles; Springer: New York, NY, USA, 1990; pp. 167–193. [Google Scholar]
  32. Botea, A.; Müller, M.; Schaeffer, J. Near Optimal Hierarchical Path-Finding. J. Game Dev. 2004, 1, 1–30. [Google Scholar]
  33. Ryu, H. A Revisiting Method Using a Covariance Traveling Salesman Problem Algorithm for Landmark-Based Simultaneous Localization and Mapping. Sensors 2019, 19, 4910. [Google Scholar] [CrossRef] [Green Version]
  34. Applegate, D.L.; Bixby, R.E.; Chvatal, V.; Cook, W.J. The Traveling Salesman Problem: A Computational Study; Princeton University Press: Princeton, NJ, USA, 2006. [Google Scholar]
  35. Howard, A. The Robotics Data Set Repository (Radish). 2003. Available online: http://radish. sourceforge. net/ (accessed on 2 November 2020).
  36. Thrun, S. Learning occupancy grid maps with forward sensor models. Auton. Robot. 2003, 15, 111–127. [Google Scholar] [CrossRef]
  37. Katevas, N.I.; Tzafestas, S.G.; Pnevmatikatos, C.G. The approximate cell decomposition with local node refinement global path planning method: Path nodes refinement and curve parametric interpolation. J. Intell. Robot. Syst. 1998, 22, 289–314. [Google Scholar] [CrossRef]
Figure 1. Overview of the proposed integrated exploration algorithm using a frontier-graph structure and graph search-based decision.
Figure 1. Overview of the proposed integrated exploration algorithm using a frontier-graph structure and graph search-based decision.
Sensors 20 06270 g001
Figure 2. Examples of frontier segmentation. Medium gray indicates unknown cells; black indicates occupied cells; very light gray indicates empty cells; red stars are detected frontier cells; cyan dots are representative nodes; red dots are current nodes; yellow dots are unexplored next targets; the blue dot is the next explored target; cyan lines show the solution to the traveling salesman problem (TSP) for the current node and its child nodes: (a) Local map constructed at the root node (b) local map constructed at the root node’s first child node (c) local map constructed at the root node’s third child node (d). A single map is used at the root node to discriminate real frontiers. (e) The local maps of the current and parent nodes are merged. The previous node is the parent node. The root/parent node’s second child node is not at the frontier area in the merged map, and is eliminated from the exploration target list to obtain a new observation. (f) The local maps of the current, parent, and previous nodes are merged. The previous node is the sibling node.
Figure 2. Examples of frontier segmentation. Medium gray indicates unknown cells; black indicates occupied cells; very light gray indicates empty cells; red stars are detected frontier cells; cyan dots are representative nodes; red dots are current nodes; yellow dots are unexplored next targets; the blue dot is the next explored target; cyan lines show the solution to the traveling salesman problem (TSP) for the current node and its child nodes: (a) Local map constructed at the root node (b) local map constructed at the root node’s first child node (c) local map constructed at the root node’s third child node (d). A single map is used at the root node to discriminate real frontiers. (e) The local maps of the current and parent nodes are merged. The previous node is the parent node. The root/parent node’s second child node is not at the frontier area in the merged map, and is eliminated from the exploration target list to obtain a new observation. (f) The local maps of the current, parent, and previous nodes are merged. The previous node is the sibling node.
Sensors 20 06270 g002
Figure 3. Frontier cell detection: (a) Local grid map. (b) Empty region of local grid map. (c) Internal boundary of empty region extracted by morphological operations. (d) Safe frontier cells (red stars) on merged map.
Figure 3. Frontier cell detection: (a) Local grid map. (b) Empty region of local grid map. (c) Internal boundary of empty region extracted by morphological operations. (d) Safe frontier cells (red stars) on merged map.
Sensors 20 06270 g003
Figure 4. Registering the edges between the current and revisited nodes’ neighbors in the frontier node DB after accidental loop-closing.
Figure 4. Registering the edges between the current and revisited nodes’ neighbors in the frontier node DB after accidental loop-closing.
Sensors 20 06270 g004
Figure 5. The environment and 80 starting positions.
Figure 5. The environment and 80 starting positions.
Sensors 20 06270 g005
Figure 6. Simulation results. Maximum range of the LRF is 4 m: (a) Number of exploration steps until the exploration is completed. (b) Total number of registered frontier nodes in the frontier-graph. (c) Number of active nodes. (d) Total traveling distance.
Figure 6. Simulation results. Maximum range of the LRF is 4 m: (a) Number of exploration steps until the exploration is completed. (b) Total number of registered frontier nodes in the frontier-graph. (c) Number of active nodes. (d) Total traveling distance.
Sensors 20 06270 g006
Figure 7. Simulation results. Maximum range of the LRF is 8 m: (a) Number of exploration steps until completion of exploration. (b) Total number of registered frontier nodes in the frontier-graph. (c) Number of active nodes. (d) Total traveling distance.
Figure 7. Simulation results. Maximum range of the LRF is 8 m: (a) Number of exploration steps until completion of exploration. (b) Total number of registered frontier nodes in the frontier-graph. (c) Number of active nodes. (d) Total traveling distance.
Sensors 20 06270 g007
Figure 8. Resulting frontier-graph structure on the final grid map by the BFS exploration. The number is the ID of each frontier node. Red lines are edges between the parent and child nodes. Dotted green lines are edges between sibling nodes. Blue circles are active nodes, and white circles are inactive nodes: (a) Frontier-graph from 4 m LRF. (b) Frontier-graph from 8 m LRF.
Figure 8. Resulting frontier-graph structure on the final grid map by the BFS exploration. The number is the ID of each frontier node. Red lines are edges between the parent and child nodes. Dotted green lines are edges between sibling nodes. Blue circles are active nodes, and white circles are inactive nodes: (a) Frontier-graph from 4 m LRF. (b) Frontier-graph from 8 m LRF.
Sensors 20 06270 g008
Figure 9. Frontier-graph structure on the final grid map obtained from BFS exploration. The numbers indicate the ID of each frontier node. Red lines are edges between the parent and child nodes. Dotted green lines are edges between sibling nodes. Blue circles are active nodes, and white circles are inactive nodes.
Figure 9. Frontier-graph structure on the final grid map obtained from BFS exploration. The numbers indicate the ID of each frontier node. Red lines are edges between the parent and child nodes. Dotted green lines are edges between sibling nodes. Blue circles are active nodes, and white circles are inactive nodes.
Sensors 20 06270 g009
Table 1. Frontier node database and local map database of the frontier-graph structure.
Table 1. Frontier node database and local map database of the frontier-graph structure.
Frontier node DB:
N o d e = n o d e i d | 1 i d N
n o d e i d = i d , i d parent , c e l l s i d , i d map , f l a g known , f l a g loop closing , i d child 1 , , i d child n
c e l l s i d = x 1 , y 1 T , , x f , y f T the metric position of each frontier cell in n o d e i d s frontier segment w . r . t . n o d e i d
E d g e = e d g e i , j | the relative transformation from n o d e i to n o d e j
e d g e i , j = d i s t i , j , tr i , j
Local map DB:
M a p = m a p i d | 1 i d M
m a p i d = i d , g r i d m a p i d , i d n o d e 1 , , i d n o d e m , p n o d e 1 , , p n o d e m
N: the number of frontier nodes
n: the number of child nodes
f: the number of frontier cells in n o d e i d ’s frontier segment
M: the number of local maps
m: the number of frontier nodes that share m a p i d
p n o d e m : the pose of n o d e m in the local map m a p i d
tr i , j : x i , j , y i , j , θ i , j T
d i s t i , j : the shortest distance between n o d e i and n o d e j
Table 2. An example of a frontier node and local map DB before/after loop-closing.
Table 2. An example of a frontier node and local map DB before/after loop-closing.
Before loop-closing:
n o d e 1 = 1 , 0 , , 1 , T R U E , F A L S E , 2 , 3 , m a p 1 = 1 , g r i d m a p 1 , 1 , 0 , 0 , 0 T
n o d e 2 = 2 , 1 , c e l l s 2 , 2 , T R U E , F A L S E , i d chil d 2 _ 1 , , i d chil d 2 _ n ,
m a p 2 = 2 , g r i d m a p 2 , 2 , 0 , 0 , 0 T
n o d e 3 = 3 , 1 , c e l l s 3 , 3 , T R U E , F A L S E , i d chil d 3 _ 1 , , i d chil d 3 _ n ,
m a p 3 = 3 , g r i d m a p 3 , 3 , 0 , 0 , 0 T
After loop-closing:
n o d e 1 = 1 , 0 , , 1 , T R U E , T R U E ̲ , 2 , 3 , m a p 1 = 1 , g r i d m a p 1 , 1 , 2 , 3 ̲ , 0 , 0 , 0 T , p 2 , p 3 ̲
n o d e 2 = 2 , 1 , c e l l s 2 , 1 ̲ , T R U E , F A L S E , i d chil d 2 _ 1 , , i d chil d 2 _ n , m a p 2 = ̲
n o d e 3 = 3 , 1 , c e l l s 3 , 1 ̲ , T R U E , F A L S E , i d chil d 3 _ 1 , , i d chil d 3 _ n , m a p 3 = ̲
Table 3. Simulation results for 4 m LRF in Figure 6.
Table 3. Simulation results for 4 m LRF in Figure 6.
DFS Exp.BFS Exp.
Min.Avg. (Std.)Max.Min.Avg. (Std.)Max.
# of exp. steps46128.4 (85.9)6634455.6 (10.4)115
# of frontier nodes62143.9 (72.5)5552329.9 (4.5)53
# of active nodes3680.9 (41.1)3321921.5 (3.0)38
Travel distance (cells)19294401.8 (2754.8)2227811731500.3 (258.4)2852
Table 4. Simulation results for 8 m LRF in Figure 7.
Table 4. Simulation results for 8 m LRF in Figure 7.
DFS Exp.BFS Exp.
Min.Avg. (Std.)Max.Min.Avg. (Std.)Max.
# of exp. steps4278.3 (35.3)2671523.7 (5.2)47
# of frontier nodes95194.9 (74.2)4661926.3 (3.9)47
# of active nodes3155.6 (18.6)135811.0 (1.7)20
Travel distance (cells)16173142.4 (1054.8)72038091082.8 (139.2)1383
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Ryu, H. Graph Search-Based Exploration Method Using a Frontier-Graph Structure for Mobile Robots. Sensors 2020, 20, 6270. https://doi.org/10.3390/s20216270

AMA Style

Ryu H. Graph Search-Based Exploration Method Using a Frontier-Graph Structure for Mobile Robots. Sensors. 2020; 20(21):6270. https://doi.org/10.3390/s20216270

Chicago/Turabian Style

Ryu, Hyejeong. 2020. "Graph Search-Based Exploration Method Using a Frontier-Graph Structure for Mobile Robots" Sensors 20, no. 21: 6270. https://doi.org/10.3390/s20216270

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