DOI QR코드

DOI QR Code

Rmap+: Autonomous Path Planning for Exploration of Mobile Robot Based on Inner Pair of Outer Frontiers

  • Buriboev, Abror (Department of IT, Samarkand Branch of Tashkent University of Information Technologies) ;
  • Kang, Hyun Kyu (Department of Software, Konkuk University) ;
  • Lee, Jun Dong (Department of Multimedia Engineering, Gangneung-Wonju National University) ;
  • Oh, Ryumduck (Department of Software,Korea National University of Transportation) ;
  • Jeon, Heung Seok (Department of Software, Konkuk University)
  • Received : 2022.08.27
  • Accepted : 2022.09.14
  • Published : 2022.10.31

Abstract

Exploration of mobile robot without prior data about environments is a fundamental problem during the SLAM processes. In this work, we propose improved version of previous Rmap algorithm by modifying its Exploration submodule. Despite the previous Rmap's performance which significantly reduces the overhead of the grid map, its exploration module costs a lot because of its rectangle following algorithm. To prevent that, we propose a new Rmap+ algorithm for autonomous path planning of mobile robot to explore an unknown environment. The algorithm bases on paired frontiers. To navigate and extend an exploration area of mobile robot, the Rmap+ utilizes the inner and outer frontiers. In each exploration round, the mobile robot using the sensor range determines the frontiers. Then robot periodically changes the range of sensor and generates inner pairs of frontiers. After calculating the length of each frontiers' and its corresponding pairs, the Rmap+ selects the goal point to navigate the robot. The experimental results represent efficiency and applicability on exploration time and distance, i.e., to complete the whole exploration, the path distance decreased from 15% to 69%, as well as the robot decreased the time consumption from 12% to 86% than previous algorithms.

Keywords

1. Introduction

Autonomous vehicles (AV) can significantly decrease the influence of drivers’ faults and neglects as a reason of vehicle collision. By considering the time, energy, distance and other factors, AVs should safety and efficiently navigate from one point to another. Path planning algorithm is clue for identification and evaluation of probable trajectories to achieve these objectives. During the performance of navigation tasks, robots' ability includes environmental modeling and localization, navigation control, frontier detection, obstacle avoidance, and navigation in dynamic contexts. There are four main navigation problems. These are perception, localization, mapping, motion control, and path planning [1-3].

Among the aforementioned problems, the most important task of mobile robot navigation is path planning. This task includes mainly three aspects. First, the planned path must be from the specified start point to the specified end point. Secondly, this route must ensure the movement of the robot while avoiding possible obstacles. Thirdly, the path should, among all possible paths that satisfy the first two requirements, be in a certain sense optimal. To analyze the path planning algorithms, we classify them using a various criteria. From point of using intelligent technologies, they can be grouped as traditional methods and heuristic methods. According to the nature of the environment, planning methods can be grouped as planning methods in a static and in dynamic environments (it should, however, be noted that a static environment is rarely encountered in practice). Methods can also be divided according to the completeness of information about the environment: methods with complete information (in this case, they speak of global path planning) and methods with incomplete information (usually we are talking about knowledge of the situation in the immediate vicinity of the robot, in this case we are talking about local route planning). Note that incomplete information on the environment can be a consequence of a changing environment, i.e., in a dynamic environment, path planning is usually local [4].

There are many approaches for path planning. These are methods based on graphs and tree, methods based on cell decomposition, methods of potential fields, optimization methods, and methods based on intelligent technologies, including behavioral techniques.

Currently, the exploration methods in the unknown environment, i.e., pathfinding, collision-free path making, localization and mapping, traverse completeness, can be di-vided into three types:

- The first is random based traversal. This type of exploration is based on move for-ward until the obstacle and randomly turning on, go on forward to complete the exploration. The method requires a lot of working time, energy, and long distance [5].

- The second is pathfinding according to model of existing environment such as grid map and cell decomposition. Grid map and cell decomposition methods divide the environment to regions respectively to grids and cells. Pathfinding for exploration is per-formed according to these grids and cells’ base points [6-8].

- The third is sensor-based traversal without prior data of environment in advance. These types of approaches use algorithm to perform the robot’s navigations according to sensor data which acquired from laser or camera devices [9-10].

Over the past three decades, researchers have explored a range of methods in all three of the above categories that relate to autonomous navigation and exploration in an un-known environment. Bruce et al. [11] proposed a path planning algorithm based on the rapid exploring of random trees. The method uses a waypoint cache and search path planning with adaptive cost.

Jadidi et al. [12] proposed an algorithm for displaying employment of Gaussian processes (GPs) for online mapping because of its stepwise formulation and ensures a continuous uncertainty model map of spatial coordinates. The standard concept for representing geometric boundaries derived from occupancy maps is to appoint binary values to each grid cell. The concept has been extended to new probability boundary maps, efficiently computed using the GP occupancy map gradient. Also proposed a greedy research method based on mutual information, built on this view, which considers all possible future observations. The main advantage of multidimensional map inference is that they require a small number of observations, resulting in a rapid decrease in map entropy during the explore of mapping processes. Evaluations using available datasets show the efficiency of the suggested framework for mapping of robots and research tasks. Exploration method proposed by Liu et al. [13], based on topology of grid hybrid map. The meth-od generates target point on the bases of geometry rules and builds node of topology. Zhang et al. [14] proposed topological and semantic grid map based indoor navigation method. They used natural language for goal point selection. The method increased the safety, efficiency, and robustness of mobile robot navigation. Tunggal et al. [15] introduced the persecution algorithm using the cell decomposition method for robot's path map and a fuzzy inference algorithm for path planning. The researchers claim that the due to obstacle avoiding of mobile robot, it finds the minimum path, and at the result it minimizes the required time to achieve the destination.

Wang et.al. [16] proposed a new autonomous path planning method for exploration in unknown environment using structure of the graph. To build a roadmap, researchers design a sampling strategy to evenly obtain random points in the environment of interest. This roadmap can effectively find a global path from the current location of the robot to the target area. The possible global path is additionally optimized using the proposed path of the trajectory optimization method, considering the restrictions of robot's motion. This mechanism can facilitate the cost estimate of the path to choose the next best target. To select the next best target area, proposed utility cost function that considers both the cost of the path and for obtaining information about the potential target area. In addition, presented a re-targeting mechanism to evaluate the target area and reduce additional path costs.

Cheng et.al. [17] introduced a new algorithm of localization and navigation using the construction of a topological map. Based on the depth curve obtained with a 3D sensor, a progressive Bayesian classifier was developed to implement direct identification of the corridor type. Instead of extracting characteristics from a single observation, information from multiple observations is combined to achieve more reliable characteristics. They proposed to create a topological map and loop closure methods to build a map of un-known environment. Senarathne et.al. [18] proposed computational efficient approach, that handles local updated map data for generation of safe and reliable boundary information. The authors solved two problems. First, gradually updated the database of frontier between unknown and mapped cells that are safety for the robot. The second is gradually determined the achievability of the frontiers in the database. Achieved frontiers are extracted by contours of boundaries.

Dugarjev et al. [19] introduced a cell decomposition technique for an unknown recti-linear environment. They used laser sensor for critical edge detection. To select goal point, algorithm checks the redundancies of planned path. Lu et al. [20] introduced RGB-D sensor for frontier-based exploration in unstructured environment. In their algorithm, obtaining data divided the environment by Octomap. The best frontier is selected as a cost function of obtaining information. Jiang et al. [21] introduced laser-based SLAM algorithm. Authors utilized eight direction of environment and calculate their path vector probability. Using the requirements of exploration, robot plans the next goal point.

1.1 Problem Formulation

A grid map representing information about a multi-cell area is widely implemented for schema display for mobile robots and simultaneous localization and mapping (SLAM) processes. However, the huge number of cells of grid map for detailed map representation imposes an overhead on memory and computational paths in mobile robots. Therefore, in order to prevent the overheads of the grid map, in our previous article we proposed a new mapping scheme to reduce the overhead in SLAM, which we called the Rmap algorithm [27]. This is shown in Fig. 1. This mapping scheme also provides a way to find new data for an unknown environment. The algorithm uses rectangles instead of grid map cells to prevent efficiently exploration when processing the SLAM in unknown environments.

E1KOBZ_2022_v16n10_3373_f0001.png 이미지

Fig. 1. The Rmap architecture

The Rmap process begins to collect the primary information when the sensor-based robot is in an unknown area, Fig. 2a. In this stage, the mobile robot creates primary map of present environment. The raw sensing information is shown as white area in Fig. 2b, it is obtained during the rotation of robot.

The minimal bounding rectangle (MBR) module generates a rectangle as Figured with blue dashed box in Fig. 2b. The MBR is the rectangle drawn outside of all areas obtained during the primary map setup.

The next step is generation and choosing internal rectangle (R1) inside of MBR. Here, R1 is the largest rectangle that can be generated in MBR. Using the rectangle tilling algorithm, Rmap generates R1. Rectangle tilling algorithm is mathematical method to find configurable rectangles in the grid [24]. mxn sized rectangle can be computed in the generated MBR using equation (1).

The robot must explore the area to get new information, as soon as it generates the R1. In our previous study, the exploration path planning was by following the borders of new generated R1, as figured by the red line in Fig. 2c. After completion of exploration phase, robot obtains new areas, such as enlarged white area, as figured in Fig. 2d. Rmap scheme using this navigation strategy develops the path for exploration that re-duces the repetitive path in an unknown area. Experimental results demonstrate that Rmap decrease the grid-map overheads. Depending on the structure of environment, the effectiveness of memory space of Rmap scheme was 85% less than a grid-map.

E1KOBZ_2022_v16n10_3373_f0002.png 이미지

Fig. 2. Exploration and path planning strategy of Rmap algorithm.

In our previous work, rectangle tilling algorithm served to select the frontier, i.e., exploration path strategy for acquiring new environmental information based on the biggest rectangle, which is generated during the previous exploration period. The disadvantage of Rmap algorithm is the long distance, which it expends to explore new environment, i.e., the robot follows the boundaries of the rectangle to obtain new information. Considering the obtained benefits of the Rmap algorithm in terms of memory efficiency and its disadvantages in path planning, it is necessary to develop new improved path planning algorithm that is superior to the existing path planning algorithm of Rmap [27], i.e., this paper proposes improved Rmap+ algorithm by modifying previous Rmap's Exploration sub-module.

There are various path planning algorithms proposed by the researchers. The most widely implemented is Frontier-based exploration algorithm, which proposed by B.Yamauchi [22]. Frontier-based algorithm [22] has two drawbacks: the first is, it takes in-to account the priority of all frontiers equally. Secondly, it wastes a lot of time and distance to explore all frontiers. Simmons [23] and Moorehead [24] proposed a cost utility function for frontier selection during exploration. Gomez et al. [25] proposed geometrical, semantical, and topological cost utility function to select frontiers. A mixed model of integer linear programming was proposed for choosing an informative region by Carlone et al. [26]. Gomez et al. [25] introduced new cost function for selecting the largest frontiers, as figured in Fig. 3. Their work indicates that, the robot moves towards the F1 frontier since F1 is the largest frontier, as illustrated in Fig. 3a, when it arrives to goal point, it recognises that there is an obstacle at the selected boundary, which cannot move further and explore the environment, as illustrated in Fig. 3b. In this instance, the robot, after an unsuccessful detour, must go to the frontier F2, i.e. the robot spends the time and distance traveled.

E1KOBZ_2022_v16n10_3373_f0003.png 이미지

Fig. 3. Gomez's Frontier selection method, here F1 and F2 are defined frontiers: (a) Inition case, (b) after reaching the goal position.

To overcome the disadvantages of Rmap path planning and improve the efficiency of exploration, in this paper we propose the Rmap+ path planning algorithm by improving algorithm of frontier-based [25] exploration. It is known that the robot exploring an un-known environment, visiting positions in accordance with the received data from sensor. Our proposal is to create the ability of robot, to decide where to move, based on the data received from the sensors. The goal of autonomous exploration is to find the best frontiers as quickly as possible and create the shortest path in an environment. In addition, the study is aimed at to make comparison between the performances of path planning algorithms Rmap+ and [27] and topological frontiers [25].

2. The Rmap+ Exploration Algorithm

The proposed exploration algorithm bases of frontier-based conception proposed by Yamauchi [22]. The block diagram of the Rmap+ Exploration module is shown in Fig. 4. The algorithm contains two modules:

E1KOBZ_2022_v16n10_3373_f0004.png 이미지

Fig. 4. The block diagram of Rmap+.

1. In the Mobile Robot module, the mobile robot starts to gather data from LIDAR sensor. Once the Goal point generation submodule sends position data, it starts the movement to reach the target point using the Motion control submodule.

2. The Autonomous Exploration module processes the LIDAR sensor data, defines optimal frontiers, generates a goal point, and upgrades the map with several submodules such as Scanning environment, Frontier detection, Generation of frontier pairs, Frontier selection, Map extension, and Goal point generation. submodules.

In more detail, this framework implements with localization module to perform SLAM algorithm. The Mobile Robot module determines the primary state of the robot on the bases of odometer and rangefinder data. In each exploration round, the mobile robot performs five specific steps to make decision on the best informative frontiers.

1. The environment scanning submodule acquires the initial data of the environment.

2. The frontiers are detected in the unknown area.

3. The External and Internal frontiers are generated in the unknown area.

4. The optimal frontier selected by executing the size of External and Internal frontiers.

5. The selected frontiers will be added to the topology map or to Rmap database depending on where the method has been implemented.

6. The center of frontier will be chosen as the next Goal point for robot navigation.

The aim of this work is autonomous path planning for mobile robot exploration by preventing wasteful navigation in difficult indoor environments, as illustrated in Fig. 3. The figure contains all the information that the mobile robot scanned in indoor environment. The following subsections explain the frontier selection algorithm.

2.1 Selecting the frontiers

In each exploration round of Rmap+, the robot determines the frontiers, F[N], using a fixed sensor range, as shown in Fig. 3a. These frontiers F[N] are called outer frontiers. Then using greedy algorithm, robot's sensor range step-by-step increases the rangefinder from the minimum till the maximum, simultaneously computing the number of defined frontiers f[n] at each round, as illustrated in the Fig. 5, i.e. Rmap+ determines an inner pair of each outer frontiers. When the quantity of Outer and Inner frontiers is equal, the process of increasing the range of the sensor will be stopped. After measuring of each frontier is performed, the submodule compares all frontiers with its corresponding pairs. If the size value of the inner frontier is less than or equal to its corresponding outer frontier, then that outer frontier's center will be selected as the next position for exploration [4].

E1KOBZ_2022_v16n10_3373_f0005.png 이미지

Fig. 5. Selecting the best frontier

Most researchers use outer frontiers to select the best frontier, in our work we generated inner frontiers to select more informative frontier. Frontier cost estimation depends on the structure of frontiers, i.e., we make assumption that if the size of the inner frontier is larger than the size of corresponding pair of outer frontier, then this frontier does not have an informative area, and otherwise this frontier has a closed or non-informative area. An exploration strategy basing on this movement policy minimizes the exploration path distance and travel time [4].

Algorithm 1 describes the entire process of frontier detection, selection, and path planning algorithm, which proposed in this article. Rmap+ for autonomous path planning consist of three parts. These are followings: the outer frontier detection part in lines 10-11, the inner frontier detection part in lines 12-16, and the frontier selection part in lines 17-18. The algorithm's life-cycle is until there is no unexplored area remains.

Algorithm 1. Rmap+ path planning algorithm

1. Begin

2. Let F = {F1, F2, …, Fn} is a set of Frontiers // F is frontiers which defined using MaxRange of sensor

3. Let L= {L1, L2, …, Ln} is a set of Frontiers’ size // F is frontiers’ size which defined using MaxRange of sensor

4. Let f = {f1, f2, …, fn} is a set of frontiers / f is frontiers which defined using a MinRange of sensor

5. Let l = {l1, l2, …, ln} is a set of frontiers’ size // f is frontiers’ size which defined using a MinRange of sensor

6. SET: MaxRange ← Maximum range of sensor

7. SET: MinRange ← Minimum range of sensor

8. Sensing data← PrimaryMapSetting using robot rotation

9. Loop until no unknown area remains

10. F ← Frontiers(sensing data)

11. L ← Frontiers’ size(F)

12. Loop by increasing MinRange until the number of F[] and f[] elements are the same

13. Sensed data ← Exploration with MinRange of sensor

14. f ← Frontiers(Sensed data)

15. l ← Frontiers’ size(f)

16. EndofLoop

17. Navigate the robot the biggest F frontier, where corresponding f frontiers’ size is smaller or equal, i.e., Ln >=ln

18. Sensing data ← exploration using the MaxRange sensor

19. EndOfLoop

End

3. Experimental Results

We have developed the simulation environment and experimented the algorithm using the Robotics Operating System and Robotics System Toolbox of MATLAB environment. The integrated toolbox allows to simulate a robot sensor in a simulation environment. The robotics system toolbox was used to process the rangefinder data and install the changeable range of the sensor for determining the frontiers. To test the robot's ability for autonomous exploration ability, simulated experiments were carried out in three types of environments. The result of the experiment in a non-cyclic environment is shown in Fig. 6. During the simulated experiments, the robot is equipped with a lidar sensor, the information about the parameters and requirements for the study of which are demonstrated in the Table 1. The comparison is performed among the two other exploration algorithms. First of them utilizes the cost function for choosing the best frontier introduced by Gomez [25], and the second one is the path planning algorithm of Rmap proposed by Lee [27]. The difference among the proposed new algorithm and these two strategies is the creation of inner and outer frontiers and their calculation for path planning to select the best frontier. All three algorithms are estimated under the same conditions using a mobile robot which is equipped as illustrated in Table 1.

E1KOBZ_2022_v16n10_3373_f0006.png 이미지

Fig. 6. The path of the robot in a non-cyclic simulated environment: (a) the first and second stages, (b) the third stage, (c) the last stage.

Table 1. Mobile robot's parameters for a simulation experiment.

E1KOBZ_2022_v16n10_3373_t0001.png 이미지

Fig. 7 illustrates the step-by-step frontier selection process and path planning trajectories acquired during the simulation experiments in the cyclic indoor environment. In the Fig. 7a the robot is in the center of circle. There are two circles which are sensor’s range area for Inner and Outer frontiers. The red lines Fig. the Inner and Outer frontiers’ size, respectively F[n] and f[n]. The pointer line shows the next goal point which is the center of optimal frontier. In this indoor environment the exploration process finishes in six steps. In the first step robot determines three pairs of frontiers, respectively F[3] and f[3]. The sizes of External and Internal frontiers are L[2, 3, 2] and l[5, 2, 2]. After obtaining frontiers’ sizes, algorithm compares each Internal frontiers’ size l[5, 2, 2] to its pairs in External frontiers L[2, 3, 2]. It is shown in Fig. 7a. As aforementioned, if inner frontier's size is equal to or less than the corresponding outer frontier, then that outer frontier will be chosen as the next position for exploration. Here F2 is chosen as the next target point for getting new information. In the next step repeats the same process and in the third step the sensor could not install the internal layer, because there is only one external frontier and its size is maximal big, i.e., it is equal to diameter of sensor range. In this case, the robot chooses the center of this single frontier (Fig. 7c). Mapping construction and data structure are implemented as Rmap algorithm [27] because of its high memory efficiency and its data structure is applied as loop closing technique.

E1KOBZ_2022_v16n10_3373_f0007.png 이미지

Fig. 7. Staged process of exploration path in cyclic simulated environment.

Comparison results presented in Fig. 8 and Fig. 9. In these figures illustrate the trajectory of robot during the exploration in two type of environment. In both environment explorations are performed in three algorithms. Fig. 8b present frontier selection method that based on cost function [25], this method requires more steps than the others. The number of steps is equal to the number of goal points, it simplifies the navigation of robot. The greatest exploration time and travel distance is required in the Rmap algorithm [27]. In contrast with two algorithms, our proposed algorithm commits exploration as illustrated in Fig. 8a, and Fig. 9a. The proposed method spends much less time and distance to explore the environment.

E1KOBZ_2022_v16n10_3373_f0008.png 이미지

Fig. 8. The path of robot exploration in a cyclic environment. (a) Rmap+ exploration algorithm, (b) Cost function-based algorithm, (c) Rmap algorithm

E1KOBZ_2022_v16n10_3373_f0009.png 이미지

Fig. 9. The path of robot exploration in a non-cyclic environment. (a) Rmap+ exploration algorithm, (b) Cost function-based algorithm, (c) Rmap algorithm

Table 2 presents the exploration path distance and steps to better demonstrate the comparison between the proposed method and previous methods [25, 27]. However, all of the strategies have coverage capabilities to establish full exploration. Below, main metrics and in Table 3 presents in two environments i.e. exploration step, number of turning points, traversal distance and time consumption. The effectiveness of the proposed path planning method is directly connected with time consumption and path distance. The minimal number of steps point out the amount of target points connected with simplicity of navigation and the distance of the robot's traversal path.

Table 2. The experimental results of exploration stages and path distances.

E1KOBZ_2022_v16n10_3373_t0002.png 이미지

In addition, performance comparison path planning algorithm of Rmap+ and memory efficiency [27], the proposed algorithm was evaluated in the simulated environment, where an area of 20.5 m to 25.5 m. The grid map contains 209,100 cells with 5 cm resolution. The Fig. 10b illustrates Rmap representing results of the experimented environment of Fig. 10a. The result shows, that Rmap generated 48 rectangles for representing the whole area of Fig. 10a while grid mapping scheme used 209,100 cells. The Rmap representing scheme is dramatically decreased the number of cells, which is provided high memory efficiency in contrast to grid mapping scheme.

E1KOBZ_2022_v16n10_3373_f0010.png 이미지

Fig. 10. The memory efficiency of Rmap in the simulated wide environment

Moreover, new path planning strategy, i.e., Rmap+ is also experimented in the wide simulated environment as shown in Fig. 10a. The Fig. 11 demonstrates the process of autonomous exploration and trajectories of robot’s navigation on the bases of three path planning algorithms. In the Figs. 11a and 11b, the blue lines are trajectories of robot path and circled points are Goal point for robot navigation which are generated during the exploration. The exploration trajectory of Rmap differs from the Rmap+ and cost function-based frontier algorithms and is illustrated in Fig. 11c. It represents the trajectory using rectangles.

E1KOBZ_2022_v16n10_3373_f0011.png 이미지

Fig. 11. Robot’s trajectory during the simulated experiments in the wide environment

Table 3 demonstrates the results of simulation experiments. Since all three of the above strategies are capable of producing a map representing the entire environment, the important metrics are the amount of time to explore, the number of turning points, the coverage area, and the travel distance. The number of turning points directly affects the efficiency of the exploration time and the navigation distance of the robot.

Table 3. The Comparison results in three environments

E1KOBZ_2022_v16n10_3373_t0003.png 이미지

In Table 3, we see that the proposed Rmap+ expends less time and traversal distance for exploration in all three types of environments than the previous two strategies [25, 27]. The results of simulation experiments in a wide environment showed that the performance of Rmap+ was 15% higher than a cost function-based frontier algorithm and about 49% higher than a Rmap path planning algorithm. In a small cyclic environment, Rmap+ showed 31% better path distance than cost function-based frontier algorithm and 66% better than the Rmap path planning algorithm. In a small non-cyclic environment, the Rmap+ performed 22% and 69% better than the cost function-based frontier and Rmap algorithms. A small amount of exploration steps, i.e. target points and turning points, is provided to minimize time costs, especially compared to the previous Rmap algorithm. Rmap+ reduced time consumption from 32% to 71% in a small cyclic environment and from 60% to 85% in a small cyclic environment, respectively, Cost function-based frontiers and Rmap methods. In the wide environment, this Fig. was from 12% to 57% better than previous exploration algorithms. The Rmap algorithm achieves the maximum coverage area. However, the coverage area of the proposed Rmap+ algorithm is close to the compared algorithms. The followings are the main aspects:

1. The choice of the best frontiers is based on the formation of inner frontiers. Inner frontiers are generated by iterative calculation. Thereby robot prevents the selection of a non-informative area.

2. The algorithm has the smallest turning points, i.e. the robot makes the minimum number of turns during the exploration and this helps to minimize exploration time and traversal distance.

5. Conclusion

This study proposes a new path planning algorithm for the exploration of autonomous mobile robots in an unknown environment. The proposed Rmap+ algorithm is based on a modified frontier-based algorithm that generates inner and outer frontiers using LIDAR sensor data. In accordance with the formed dimensions of the inner and outer frontiers, the robot selects the next optimal frontier and plans the minimum traversal path. The algorithm allows to prevent and avoid an uninformative environment leading to a long exploration distance of robot. In comparison with previous path planning algorithms, Rmap+ present much better performance in terms of travel time and distance. The ad-vantages of the proposed algorithm in terms of efficiency were evaluated through simulations and experiments in unknown environments. The algorithm currently uses its previous proposed mapping algorithm, i.e. the Rmap data structure introduced in our previous work for mapping and localization. In the future work, we are going to develop a special data structure for our algorithm and implement a complete strategy for several robots in a dynamic environment.

Acknowledgement

This work was supported by the National Research Foundation of Korea (NRF) grant funded by the Korean government (MSIT) (2020R1A2C1101867).

References

  1. Chunhui Z., Green R., "Vision-based autonomous navigation in indoor environments," in Proc. of 2010 25th International Conference of Image and Vision Computing, New Zealand, pp. 1-7, 2010.
  2. Sariff, N., Buniyamin, N., "An Overview of Autonomous Mobile Robot Path Planning Algorithms," in Proc. of 2006 4th Student Conference on Research and Development, pp. 183-188, 2006.
  3. Sariff, N., Buniyamin, N., "Ant colony system for robot path planning in global static environment," in Proc. of the 9th WSEAS International Conference on System Science and Simulation in Engineering (ICOSSSE'10), Takizawa, Japan, pp. 192-197, 4-6 October 2010.
  4. Buriboev A., MuminovA., H.J. Oh, J.D. Lee, Y.A. Kwon, H.S. Jeon, "Internal and external frontier-based algorithm for autonomous mobile robot exploration in unknown environment," Electronics Letters, vol. 57, no. 24, pp. 942-944, 23 September 2021. https://doi.org/10.1049/ell2.12316
  5. Stout, M.S., Brisson, G. F., Di Bernardo, E., Pirjanian, P., Goel, D., Case, J.P., Dooley, M., "Methods and Systems for Complete Coverage of a Surface by an Autonomous Robot," U.S. Patent No. 9,026,302, 5 May 2015.
  6. Montiel, O., Sepulveda, R. & Orozco-Rosas, U., "Optimal Path Planning Generation for Mobile Robots using Parallel Evolutionary Artificial Potential Field," J Intell Robot Syst, 79, 237-257, 2015. https://doi.org/10.1007/s10846-014-0124-8
  7. Seda, M., "Roadmap methods vs. cell decomposition in robot motion planning," in Proc. of the 6th WSEAS International Conference on Signal Processing, Robotics and Automation, Corfu Island, Greece, 16-19 February 2017; World Scientific and Engineering Academy and Society (WSEAS), Stevens Point, WI, USA, pp. 127-132, 2017.
  8. Luo, C., Gao, J., Li, X., Mo, H., Jiang, Q., "Sensor-based autonomous robot navigation under unknown environments with grid map representation," in Proc. of the 2014 IEEE Symposium on Swarm Intelligence (SIS), Orlando, FL, USA, pp. 1-7, 9-12 December 2014.
  9. Boucher, S., Obstacle Detection and Avoidance Using Turtlebot Platform and Xbox Kinect," Department of Computer Science, Rochester Institute of Technology, pp. 1-56, 2012.
  10. Mac Thi, Thoa, Cosmin Copot, Duc Trung Tran, and Robain De Keyser, "Heuristic Approaches in Robot Path Planning: A Survey," ROBOTICS AND AUTONOMOUS SYSTEMS, 86, 13-28, 2016. https://doi.org/10.1016/j.robot.2016.08.001
  11. Bruce, J., Veloso, M.M, "Real-time randomized path planning for robot navigation," in Proc. of the RoboCup 2002, Fukuoka, Japan, 19-25 June 2002.
  12. Ghaffari Jadidi, M., Valls Miro, J., & Dissanayake, G, "Gaussian processes autonomous mapping and exploration for range-sensing mobile robots," Autonomous Robots, 42(2), 273-290, 2018. https://doi.org/10.1007/s10514-017-9668-3
  13. Liu S, Li S, Pang L, Hu J, Chen H, Zhang X, "Autonomous Exploration and Map Construction of a Mobile Robot Based on the TGHM Algorithm," Sensors (Basel), 20(2), 490, 15 Jan 2020.
  14. Zhang, J., Wang, W., Qi, X., Liao, Z., "Social and Robust Navigation for Indoor Robots Based on Object Semantic Grid and Topological Map," Appl. Sci., 10, 8991, 2020.
  15. Tunggal, Tatiya Padang, et al., "Pursuit algorithm for robot trash can based on fuzzy-cell decomposition," International Journal of Electrical and Computer Engineering (IJECE), Vol. 6, No. 6, pp. 2863-2869, December 2016. https://doi.org/10.11591/ijece.v6i6.10766
  16. C. Wang, W. Chi, Y. Sun and M. Q. H. Meng, "Autonomous Robotic Exploration by Incremental Road Map Construction," IEEE Transactions on Automation Science and Engineering, vol. 16, no. 4, pp. 1720-1731, Oct. 2019. https://doi.org/10.1109/tase.2019.2894748
  17. H. Cheng, H. Chen, and Y. Liu, "Topological Indoor Localization and Navigation for Autonomous Mobile Robot," IEEE Transactions on Automation Science and Engineering, vol. 12, no. 2, pp. 729-738, April 2015. https://doi.org/10.1109/TASE.2014.2351814
  18. P.G.C.N. Senarathne, Danwei Wang, "Incremental algorithms for Safe and Reachable Frontier Detection for robot exploration," Robotics and Autonomous Systems, Vol. 72, pp. 189-206, 2015. https://doi.org/10.1016/j.robot.2015.05.009
  19. Dugarjav, B., Lee, SG., Kim, D. et al., "Scan matching online cell decomposition for coverage path planning in an unknown environment," Int. J. Precis. Eng. Manuf., 14, 1551-1558, 2013. https://doi.org/10.1007/s12541-013-0209-5
  20. Lu, L., Redondo, C., Campoy, P., "Optimal Frontier-Based Autonomous Exploration in Unconstructed Environment Using RGB-D Sensor," Sensors, 20, 6507, 2020.
  21. Jiang, L., Zhao, P., Dong, W., Li, J., Ai, M., Wu, X., Hu, Q., "An Eight-Direction Scanning Detection Algorithm for the Mapping Robot Pathfinding in Unknown Indoor Environment," Sensors,18, 4254, 2018.
  22. Yamauchi, B., "A frontier-based approach for autonomous exploration, cira," in Proc. of the 1997 IEEE International Symposium on Computational Intelligence in Robotics and Automation (CIRA'97), Monterey, CA, USA, p. 146, 10-11 July 1997.
  23. R. Simmons, D. Apfelbaum, W. Burgard, D. Fox, M. Moors, S. Thrun, H. Younes., "Coordination for multi-robot exploration and mapping," in Proc. of 17th Nat. Conf. Artif. Intell. 12th Conf. Innov. Appl. Artif. Intell., pp. 852-858, 2000.
  24. S. J. Moorehead, R. Simmons, and W. L. Whittaker, ''Autonomous exploration using multiple sources of information,'' in Proc. of IEEE Int. Conf. Robot. Automat., Vol. 3, pp. 3098-3103, May 2001.
  25. Gomez, C., Hernandez, A.C., Barber, R., "Topological Frontier-Based Exploration and MapBuilding Using Semantic Information," Sensors, 19, 4595, 2019.
  26. Carlone, L., Du, J., Ng, M.K., Bona, B., Indri, M, "An application of Kullback-Leibler divergence to active SLAM and exploration with particle filters," in Proc. of the 2010 IEEE / RSJ International Conference on Intelligent Robots and Systems, Taipei, Taiwan, pp. 287-293, 8-22 October 2010.
  27. Lee, C. W., Lee, J. D., Ahn, J., Oh, H.J., Park, J.K., Jeon, H.S., "A Low Overhead Mapping Scheme for Exploration and Representation in the Unknown Area," Appl. Sci., 9, 3089, 2019.