Open access peer-reviewed chapter

Coverage Technology of Autonomous Mobile Mapping Robots

Written By

SeungHwan Lee

Submitted: 18 September 2022 Reviewed: 18 October 2022 Published: 25 November 2022

DOI: 10.5772/intechopen.108645

From the Edited Volume

Autonomous Mobile Mapping Robots

Edited by Janusz Bȩdkowski

Chapter metrics overview

112 Chapter Downloads

View Full Metrics

Abstract

The coverage technique is one of the essential applications of autonomous mobile mapping robots. There are various approaches for coverage depending on the model (model/non-model), robot systems (single/multi), and its purpose (patrol/cleaning). Coverage components include viewpoint generation and path planning approaches, which are described as CPP research work. Particularly, in surveillance systems, coverage techniques, such as spanning tree, cyclic coverage, and area-based coverage, are reviewed specifically, which can be expanded for multi-robot systems. In addition, required coverage techniques according to conditions for intelligent surveillance systems are summarized. Lastly, several issues on coverage, specifically cyclic coverage, are described and considered.

Keywords

  • coverage
  • surveillance systems
  • issues on coverage
  • multi-robot patrol systems

1. Introduction

Coverage path planning (CPP) is the process of calculating a viable path through all points in a region of interest to scan or investigate a region of interest in the environment [1]. As shown in Figure 1, it is largely applied to the coverage problem of patrol robots and cleaning robots.

Figure 1.

Various robot platforms with coverage algorithms. (a) K5 robot, (b) D-Bot, (c) Samsung robot cleaner, and (d) Mi robot cleaner.

Early CPP studies [2] defined six robot requirements as follows:

  1. Robot should move through all the points in the target area covering it completely.

  2. Robot should cover the region without overlapping paths.

  3. Continuous and sequential operation without any repetition of paths is required.

  4. Robots should avoid all obstacles.

  5. Simple motion trajectories (e.g., straight lines or circles) should be used (for simplicity in control).

  6. An “optimal” path is desired under available conditions.

In addition, it requires robot positioning, autonomous driving capabilities, path planning, detection, and recognition. However, these conditions are not always possible in complex environments. Thus, sometimes only a few conditions are needed.

As aforementioned, CPP is the process of navigating or exhaustively searching a workspace. The CPP must also determine all locations to be visited while avoiding all possible obstacles [2, 3]. Essentially, applications, such as structural painting, object reconstruction, lawn mowing, surveillance, geospatial mapping, agricultural surveying, and floor cleaning, require full coverage. In general, in CPP, it is common to construct a model in real time using a sensor mounted on a robot and to provide information, such as a region of interest in advance [4, 5, 6, 7].

The three main components of CPP are viewpoint generation, path planning, and coverage integrity quantification. In each implementation, CPP can be performed online or offline. Offline CPP requires a reference model. On the other hand, in the case of online CPP, since it is necessary to utilize sensor information, a step to process sensor information is required.

Advertisement

2. Model/non-model-based CPP

There are several research methods for performing CPP using a single robot. These methods can be broadly divided into model-based approaches and non-model-based approaches. In Ref. [8], a heuristic-based approach based on the art gallery problem (AGP) approach [9] was proposed. Figure 2 shows a visual representation of the AGP. In addition, this method solved the traveling salesman problem (TSP) to generate optimized routes for each structure and then randomly assign them based on the time constraints of the UAV and the travel routes of the traveling salesman.

Figure 2.

Visual representation of AGP [9]. This problem refers to the problem of protecting the entire museum with the minimum number of guards. In general, AGP is to ensure that the guard represented by a point on a polygonal map is sufficient to detect all spaces.

There is also an example of performing a TSP algorithm using PSO [10]. PSO is a particle swarm optimization technique that progressively finds an optimal solution using N particles. The solution giving the best score among particles is the output of the PSO. Figure 3(a) shows the structure of the PSO algorithm. It can be seen that the algorithm is configured in the form of finally finding the optimal solution while optimizing the objective function until the termination condition is satisfied. Figure 3(b) shows how each particle converges.

Figure 3.

The representation of the PSO algorithm and convergence [11]. The pseudo-code of PSO is represented in (a). The movements of particles are shown in (b). (a) PSO algorithm (b) visualization of PSO.

The second approach of the single-robot CPP approach follows a non-model-based approach. The work presented in Ref. [12] proposed an extended CPP approach [13] by utilizing surface information to plan coverage paths online using truncated signed distance fields (TSDF). The search space is divided into a surface area and a cuboid area, which are used to create a volume map of the bounding area. The volume map is used to calculate the information gain by considering the cube volume and path length. The Hamiltonian path problem is to compute the visit order for each cuboid while generating the path using the generalized TSP. As shown in Figure 4, the Hamiltonian path problem can be solved by finding out a path through all vertices once in graph theory.

Figure 4.

Hamiltonian path generation problems [14]. Hamiltonian path generation results for various examples are shown.

In Ref. [15], another non-model-based approach, that is, a search algorithm, was presented that selects the next best view (NBV) that maximizes the predicted information gain, taking into account distance and battery life cost. The proposed task dynamically builds a hull surrounding a predefined bounding box that updates based on new information. The visited points are uniformly sampled with a fixed number pointing to the vertical axis through the center of the bounding box. The planning approach follows a probabilistic approach using utility functions that reduce 3D reconstructed model uncertainty, divert combat paths, and generate safe paths based on time constraints. The energy aspect of the non-model-based single-robot approach is considered an important part, especially since the CPP is performed online. Using this type of approach on a single robot makes it difficult to achieve high coverage ratios and increases computational complexity. This difficulty arises from the complexity of environments that contain enclosed areas that are difficult to find with a single robot and require a lot of time to navigate. Single-robot CPP approaches were reviewed and analyzed in Ref. [16].

Advertisement

3. Single/multi-robot

For large areas and structures, leveraging a multi-robot CPP strategy can be a huge advantage to quickly achieve full coverage. Using one robot to cover a large structure or a large area has various disadvantages, such as time, length, robot energy, and quality and quantity of information [6, 7]. The multi-robot CPP approach follows the same approach as single-robot coverage, but requires additional factors and requirements to be considered. These factors include the type of collaboration, information sharing, robustness of agent failure handling, level of autonomy, robot durability, and task assignment. It is necessary to explore different approaches utilizing multi-robot systems in terms of CPP components, including viewpoint generation and path planning approaches. Path planning approaches can be divided into grid-based navigation approaches, geometric approaches, reward-based approaches, NBV approaches, and random incremental planning approaches.

Performing CPP using a multi-robot system for model reconstruction and mapping requires various aspects to be considered. Two key CPP-related aspects for creating feasible coverage routes include viewpoint generation and path planning. The remaining aspects are communication/task assignment and mapping in multi-robot systems, which are important to model or construct regions of interest using the collected data.

3.1 Viewpoint generation

In most studies, the coverage search method is largely divided into the model-based method and the non-model-based method. Model-based methods rely on a reference model of the environment or structure provided first, whereas non-model-based ones perform planning and exploration without prior knowledge of the structure or environment [4, 5]. Based on these classifications, viewpoints are generated to form the search space of the planner. Some methods of generating them are uniformly generated due to the existence of structural or regional models and their dependencies on specific regional or structural models. Other types of viewpoint generators are also randomly assigned due to lack of knowledge of structural or domain models. Viewpoint generation is treated as important in the multi-robot CPP process because it aims to output a set of optimized routes that represent an acceptable set of viewpoints containing the structure or environment of interest. Depending on the search method used and the scope of its application, various techniques for performing viewpoint generation are mentioned in the relevant papers.

3.2 Path planning

The multi-robot CPP approach is being pursued in various studies describing challenging problems and proposed solutions. All of these approaches have a similar goal of providing a collision-free path that achieves the full extent of a structure or area. As a representative method, the visibility graph is used for path generation [17]. Visibility graphs contain a set of points and obstacles where nodes represent locations, and edges consist of line segments that do not pass-through obstacles. Examples of visibility graphs and generated paths are shown in Figure 5.

Figure 5.

Examples of visibility graphs and generated paths [18].

Geometric approaches such as shortest Euclidean path finding and polygonal area coverage are used in many domains. The most popular geometric-based method in multi-robot CPP is the Voronoi diagram. In [19], a dynamic path planning approach was proposed for heterogeneous multi-robot sensor-based coverage (DPP MRSBC) considering energy capacity. The environment was modeled as a generalized Voronoi diagram (GVD) that obscures the edges of the diagram. The proposed algorithm starts with an undirected graph and creates a directed subgraph.

3.3 CPP research work

The main components of the CPP process used in the work recently investigated in this article are summarized in Figure 6. Figure 6 summarizes recent research on multi-robot CPP, which includes the evaluation metrics for the environment type, algorithm processing technique, viewpoint generation method, application path generation method, and application method. According to the researched literature, there are many problems that block the progress of efficient multi-robot cooperative CPP. These issues include heterogeneity, prioritization, robustness, communication, adaptability, open systems, collective intelligence, and multi-robot scheduling.

Figure 6.

Summary of CPP research work [1]. It includes the evaluation metrics for the environment type, algorithm processing technique, viewpoint generation method, application path generation method, and application method.

Advertisement

4. Coverage for patrol robots

With the development of robot technology, research and interest in unmanned patrol robots have been increasing in various fields that require monitoring and security, such as social safety and national defense [20, 21, 22, 23, 24]. In particular, research on multi-object systems consisting of two or more patrol robots in a wide area is being actively conducted [25, 26]. These systems were essentially trying to solve the problem of multi-robot patrols. The challenge is to find the optimal solution for given tasks, that is, monitoring, information gathering, object discovery, anomaly detection, and so on (Figure 7).

Figure 7.

The components of the multi-robot surveillance system [20]. (a) Multi-robot monitoring. (b) Multi-robot patrol mission.

Several studies have been attempted to solve the monitoring and security problems of multi-agent systems, and through this, the necessary parts for an intelligent monitoring system are as follows. Given an environment map, we need to (1) extract nodes automatically to generate a robot roadmap. In particular, when generating nodes, it is necessary to obtain sophisticated node extraction results by reflecting the normal vector direction of the map and the sensing range of the sensor. (2) You need to solve the TSP to create a full patrol route. (3) In order to assign a patrol route to a multi-agent system, it is necessary to represent the relation between the maximum number of robots, the maximum patrol period, and the maximum speed of the robots. As a result, the patrol paths assigned to each agent can be derived. (4) If the environment map or the obstacle probability map according to the density of obstacles other than the point of interest is given, it is necessary to change the maximum velocity of the robot in the corresponding area or to allocate a dedicated robot. A summary of this can be found in Table 1.

Among them, the study of P. Fazli [26] is shown in Figure 8. Several concepts are also represented. First, the path between robots should not overlap, and it is an approach that increases the frequency of visits by reducing the visit period. The method is done according to following process.

  1. Select the position where the fixed guard should be located as the region of interest and use the field of view of the robot at this time.

  2. Complete graph G based on the location of the fixed guards and obstacles of the given polygon. (using visibility graphs or Delaunay triangulation)—complete robotic roadmap.

  3. The graph uses the reduced visibility method or the reduced CDT method to reduce the number of connected nodes.

  4. Perform cluster-based coverage algorithm: Divide the given graph into small pieces of area and assign them to robots. This will soon be the full patrol route for each robot. (There are uniform clustering method, edge-based clustering method, and node-based clustering method.)

  5. In the cluster-based method, patrol routes may not be made similar, so a circular coverage algorithm can be performed for equidistant route assignment. (This method creates the shortest traversal path and assigns it uniformly to each robot.)

  6. Finally, the path generation algorithm is performed using a double-minimum spanning tree or a linked Lin-Kernighan algorithm to create a path that traverses the start and end of the graph assigned to each robot.

Figure 8.

Schematic diagram of the path overlap problem and the visiting frequency problem [26].

4.1 Spanning tree-based coverage (STC)

The input to the STC algorithm is a constrained planar environment, partially filled with smooth and stationary obstacles. The algorithm first subdivides the working area into 2D-sized cells and discards cells partially covered by obstacles. The graph structure G(V, E) is defined as a line segment that defines the center point of each cell as node V and the centers of adjacent cells with edge E. The following algorithm constructs a spanning tree for G and uses this tree to generate coverage paths as shown in Figure 9.

Figure 9.

Coverage path generation result [27]. It is based on the spanning tree for graph G.

4.2 Cyclic coverage algorithm

The cyclic coverage suggested by P. Fazli is similar to the cluster-based coverage algorithm, and the cyclic coverage approach finds the guards, builds a graph (VG), and then reduces the graph, named reduced Vis. It uses the Chained LinKernighan algorithm to generate a path for the entire reduced Vis. The proposed algorithm then distributes the robot equidistantly around the tour and moves it recursively. The cyclic coverage approach produces an optimal or near-optimal solution for a single robot in terms of full path length and total worst-case visit duration.

4.2.1 Issues of cyclic coverage

There are about seven issues that are mainly dealt with in the cyclic coverage problem as shown in Table 2. The goal can be reviewed as a problem of minimizing the worst-case frequency or maximizing a random patrol target. However, most coverage problems were handled by minimizing the worst visiting frequencies. The environment can be largely divided into an indoor environment (corridor space) and an outdoor environment (open space). The third is whether there are any restrictions on the sensor. In practice, it is necessary to approach the problem of limited detection range and deal with it in detail. Agents can be viewed in static or dynamic environments and are usually defined in a goal-oriented fashion, which can be different depending on the given problem. If there are no communication restrictions, centralized control can be conducted to the robots, and the patrol policy can be defined as an area patrol that covers all areas. If it is a border patrol problem, then the method produces how agents approach the border. Since in most cases the exact solution is not known, the goal is to get near-optimal in terms of time and distance.

Map conditionRobot conditionRequired essential techniques
Environments# of robots, patrol interval, patrol frequency, robot maximum vel, sensing rangeGraph reconstruction for robot road map
path generation for N robots
Environments + Obstacle information# of robots, patrol interval, patrol frequency, robot maximum vel, sensing rangeObstacle-based local path regeneration
environments + Region of interests# of robots, patrol interval, patrol frequency, robot maximum vel, sensing rangePath regeneration technology considering dedicated robot assignment

Table 1.

Coverage techniques and conditions for intelligent surveillance systems.

InterestsConsiderations
Objective
  1. Minimize the worst frequency

  2. Maximize the probability of detection

Environment
  1. Open space

  2. Corridor space (complex)

Sensors
  1. Limited range

  2. Unlimited range (like vision)

Agents
  1. Goal oriented

  2. Reactive

Controller
  1. Centralized control

  2. Distributed control

Patrol policy
  1. Area patrolling

  2. Boundary patrolling

Solution
  1. Optimal

  2. Near-optimal

Table 2.

Issues of cyclic coverage methods.

4.2.2 Simulation result of cyclic coverage

The cyclic coverage method [28] can be applied to various maps as shown in Figure 10. (SLAM data set published on Ref. [29]). Three robots were considered for three maps in this simulation. The first figure in Figure 10 is the result of generating a graph (consisting of nodes marked in green and edges) considering the detection range of the robot. By creating a single robot path from this graph and removing redundant paths (leaving unique paths), the path can be represented piecewise. The final result is obtained by merging a number of paths equal to the number of robots and assigning those paths to each robot. From the simulation results in Figure 10, it can be seen that each robot’s coverage area is properly allocated.

Figure 10.

The simulation results of the cyclic coverage method. The SLAM maps are built using the SLAM dataset.

Advertisement

5. Area-based coverage

Path distribution techniques can give poor results depending on the presence and geographic location of overlapping paths. To solve this problem, the process of area allocation can be applied. One method is the DARP (region segmentation based on the robot’s initial position) method [30]. This method divides the area based on Voronoi segmentation and the initial position of the robot. It also scales the area through the metric function. The method has been improved according to the form of versions, such as 0.5, 1.0, and so on.

Advertisement

6. Conclusion

In this chapter, coverage techniques have been reviewed in terms of the model, robot systems, and their purpose by showing their procedures and simulation results. Particularly, in surveillance systems, coverage techniques, such as spanning tree, cyclic coverage, and area-based coverage, were described specifically, which can be expanded for multi-robot patrol systems. In addition, several issues on coverage were described and considered.

Advertisement

Acknowledgments

This research was a part of the project titled “Research on Co-Operative Mobile Robot System Technology for Polar Region Development and Exploration,” funded by the Korean Ministry of Trade, Industry and Energy (1525011633).

References

  1. 1. Almadhoun R, Taha T, Seneviratne L, Zweiri Y. A survey on multi-robot coverage path planning for model reconstruction and mapping. SN Applied Sciences. 2019;1(847):1-24
  2. 2. Galceran E, Carreras M. A survey on coverage path planning for robotics. Robotics and Autonomous Systems. 2013; 61:1258-1276
  3. 3. Valente J, Barrientos A, Cerro JD. Coverage path planning to survey large outdoor areas with aerial robots: A comprehensive analysis, In: Introduction to modern robotics II. iConcept Press. 2011. ISBN: 978-1-463789-442
  4. 4. Scott WR. Model-based view planning. Machine Vision and Applications. 2009;20:47-69
  5. 5. Scott WR, Roth G, Rivest JF. View planning for automated three-dimensional object reconstruction and inspection. ACM Computing Surveys. 2003;35(1):64-96
  6. 6. Choset H. Coverage for robotics—A survey of recent results. Annals of Mathematics and Artificial Intelligence. 2001;31(1-4):113-126
  7. 7. Muddu RSD, Wu D, Wu L. A frontier based multirobot approach for coverage of unknown environments. In: 2015 IEEE international conference on robotics and biomimetics, IEEE-ROBIO 2015. 2015. pp. 72-77
  8. 8. Doitsidis L, Weiss S, Renzagli A, Achtelik MW, Kosmatopoulos E, Siegwart R, et al. Optimal surveillance coverage for teams of micro aerial vehicles in GPS-denied environments using onboard vision. Auton Robots. 2012;33(1-2):173-188
  9. 9. ART Gallery Problem. Available from: https://en.wikipedia.org/wiki/Art_gallery_problem
  10. 10. Phung MD, Quach CH, Dinh TH, Ha Q. Enhanced discrete particle swarm optimization path planning for UAV vision-based surface inspection. Automation in Construction. 2017;81:25-33
  11. 11. PSO algorithm. Available from: https://en.wikipedia.org/wiki/Particle_swarm_optimization
  12. 12. Song S, Jo S. Surface-based exploration for autonomous 3D modeling, In: IEEE International Conference on Robotics and Automation (ICRA’18), Brisbane, Australia. 2018. pp. 4319-4326
  13. 13. Song S, Jo S. Online inspection path planning for autonomous 3D modeling using a micro-aerial vehicle. In: Proceedings—IEEE International Conference on Robotics and Automation. 2017. pp. 6217-6224
  14. 14. Hamiltonian Path. Available from: https://en.wikipedia.org/wiki/Hamiltonian_path
  15. 15. Palazzolo E, Stachniss C. Effective exploration for MAVs based on the expected information gain. Drones. 2018;2(1):9
  16. 16. Almadhoun R, Taha T, Cai G. A survey on inspecting structures using robotic systems. International Journal of Advanced Robotic Systems. 2016;13(6):1-18
  17. 17. Visibility Graph. Available from: https://en.wikipedia.org/wiki/Visibility_graph
  18. 18. Shortest Path Planning on Visibility Graph. Available from: https://fribbels.github.io/shortestpath/writeup.html
  19. 19. Zheng X, Koenig S, Kempe D, Jain S. Multirobot forest coverage for weighted and unweighted terrain. IEEE Transactions on Robotics. 2010;26(6):1018-1031
  20. 20. Yan C, Zhang T. Multi-robot patrol: A distributed algorithm based on expected idleness. International Journal of Advanced Robotic Systems. 2016;13(6):1-12
  21. 21. Witwicki S, Castillo JC, Messias J, Capitan J, Melo F, Limá PU, et al. Autonomous surveillance robots a decision-making framework for networked multi agent systems. IEEE Robotics & Automation Magazine. 2017; 24(3):52-64
  22. 22. Shermer TC. Recent results in art galleries[geometry]. Proceedings of the IEEE. 1992;80(9):1384-1399
  23. 23. Nilsson BJ. Guarding art galleries-methods for mobile guards. [PhD thesis]. Lund University. 1995
  24. 24. Ye Y, Tsotsos JK. Sensor planning in 3D object search. Computer Vision and Image Understanding. 1999;73(2):145168
  25. 25. Fazli P, Davoodi A, Mackworth AK. Multi-robot repeated area coverage: Performance optimization under various visual ranges. Computer and Robot Vision. 2012:298-305
  26. 26. Fazli P, Davoodi A, Mackworth AK. Multi-robot repeated area coverage. Autonomous Robots. 2013;34(4):251-276
  27. 27. Gabriely Y, Rimon E. Spanning-tree based coverage of continuous areas by a mobile robot. Annals of Mathematics and Artificial Intelligence. 2001;31:77-98
  28. 28. Noh D, Choi J, Choi J, Byun D, Youngjae K, Kim H-R, et al. MASS: Multi-agent scheduling system for intelligent surveillance, UR. 2022
  29. 29. Open SLAM. Available from: www.openslam.org
  30. 30. DARP. Available from: https://medium.com/@athanasios.kapoutsis/darp-divide-areas-algorithm-for-optimal-multi-robot-coverage-path-planning-2fed77b990a3

Written By

SeungHwan Lee

Submitted: 18 September 2022 Reviewed: 18 October 2022 Published: 25 November 2022