1 Introduction

Coverage path planning (CPP) is the process of computing a feasible path encapsulating a set of viewpoints through which a robot must pass in order to completely scan or survey the structure or environment of interest. Various technological developments and advancements in sensor technology, navigational, communication and computational systems have facilitated the increase in the level of autonomy in multi-robot systems. Therefore, some autonomous systems shifted over the past decade towards cooperative systems in order to achieve (CPP) objectives more efficiently and robustly [18, 74].

Different research approaches have been followed in the past to perform CPP depending on the environment, the shape of the structure, and the level of the required details. The two main challenging components of CPP are viewpoints generation and coverage path generation. Viewpoints generation defines the positions and orientations of the sensor from where the data will be collected, thus affecting the overall coverage. The performance of the coverage planning approach is usually measured by the coverage completeness and its optimality. The main contributing factors that affect the overall multi-robot system, and model/map quality include the information gathering method whether it is continuous or discrete, the coverage path generation method whether it is online or offline, and the mapping or reconstruction methods.

Generally, the development of cooperative multi-robot systems is concerned with a group of agents that work collectively to achieve a common objective. Typical common objectives include surveillance, monitoring, surveying, and modeling. Wide range of applications utilize cooperative multi-robot systems including: search and rescue missions [74], forest fire monitoring [50], industrial inspection [12, 22], and natural disaster monitoring and relief [18]. The objectives in these applications can be achieved far more efficiently and reliably using a team of cooperative agents rather than a single agent. In these kinds of applications, CPP plays a vital role in coordinating the tasks of each of these agents in order to achieve the main objective.

Multi-robot CPP is the process of computing a set of feasible paths encapsulating a set of viewpoints through which the team of robots must visit, each with its assigned path, in order to completely scan, explore or survey the structure or environment of interest. In specific applications, CPP is a process used for autonomous mapping and reconstruction where these generated maps or models can hold different level of information, such as temperature, occupancy, or signals strength, and can be used for various applications.

CPP strategies were deployed on various autonomous robotic systems in the literature varying from Unmanned Aerial Vehicles (UAVs), Unmanned Ground Vehicles (UGVs) to marine robots. Recently, the interest in UAVs have grown steadily, especially due to decreases in their weight, size and cost, and the increase in their actuators performance. Moreover, the availability of cheap light-weight processing power and miniaturized accurate sensors increased their level of autonomy. Furthermore, UAVs covers a broad set of applications that cannot be fulfilled by other types of robots due to their agility, and ability to move in unstructured environments.

Technically, various robotic capabilities are required in order to perform CPP including: localization, navigation and path planning, and sensing and perception. The level of complexity of these requirements varies based on the number of robots and the environment dimensionality. As such, the robots need to be equipped with various intelligent sensing capabilities that provide information with enhanced quality in order to reconstruct the structure of interest or map the environment accurately.

The main factors that could effect the performance of a multi-robot CPP approach include: information sharing (whether it is centralized, decentralized, or distributed), viewpoints generation, path generation, task allocation, reacting to dynamic changes (collision avoidance), and model reconstruction or mapping approach. Majority of existing approaches in literature attempt to: reduce the computational cost (time need to compute and execute the CPP mission) [61, 84], avoid collision internally between team of robots and externally with the structure or environment [1, 7, 39], and gather information with sufficient resolution for mapping and reconstruction [69, 80].

Most of the existing surveys in this topic address issues such as perception, exploration, guidance and control. A few surveys address the CPP problem focusing on single robot CPP problems and briefly mentioning the multi-robot as an extension [26, 79], or focusing on multi-robot area coverage problems [77]. Although some of the techniques performed in single robot CPP can be extended and applied to multi-robot systems, several additional aspects must be considered including viewpoints generation, communication/task allocation, robustness (failure handling), and mapping. Also, the dimensionality of the CPP differs between area coverage and large structures coverage problems.

This paper presents a survey on multi-robot coverage path planning. Our review focuses on approaches related to multi-robot systems applied on environments of different dimensions. The survey provides details about the main aspects of performing CPP using multi-agent systems including: viewpoints generation, path planning, communication/task allocation, and mapping. A detailed discussion about the main aspects is also provided with a flow chart showing the information flow throughout a multi-robot CPP mission. A set of research perspectives in this topic are discussed for further future developments. The main performance metrics are also explored in the survey and shown in a table summarizing the most recent work in this topic using multi-robot systems.

In this survey paper, the main components of the multi-robot CPP process are detailed in separate sections. Section 2 focuses on single and multi robot CPP. Viewpoints generation strategies will be reviewed in Sect. 3.1, and multi-robot CPP approaches in Sect. 3.2. An overview discussion of the main aspects and future research perspectives of CPP are presented in Sect. 4. Finally, conclusions are presented in Sect. 5.

2 Overview of CPP

Coverage path planning (CPP) is the process of exploring or exhaustively searching a workspace, whether it is a structure of interest or an environment, and determining in the process the set of locations to visit while avoiding all possible obstacles [26, 78]. Some applications require achieving complete coverage using the various CPP techniques such as structure painting, object reconstruction, lawn mowing, surveillance, geo-spatial mapping, agricultural surveying, and floor cleaning. Generally in CPP, either the model is reconstructed in real time utilizing the robot’s sensing capabilities, or a reference model is provided in advance for the structure or the environment of interest [72, 73]. Extensive reviews of the various CPP methods in literature are presented in [15, 26] describing their functionalities and applications.

The main components of CPP include: viewpoints generation, path planning, and coverage completeness quantification. These components are directly dependent on the exploration method selected for the structure or environment of interest coverage whether it is performed offline or online. Performing offline CPP requires using a reference model of the structure or environment of interest while performing CPP online requires utilizing the sensors information to perform coverage.

2.1 Model based or non-model based CPP

Several approaches exist in the literature for performing CPP using single robot. These approaches are classified into model and non-model based approaches. A heuristic based approach is proposed in [60] which takes into consideration length, timing, coverage, and UAV endurance constraints for a distributed structure inspection application. In this work, an Art Gallery Problem (AGP) approach is used to generate the set of viewpoints based on the selected structures’ mesh models. A Travelling Salesman Problem (TSP) is used to generate optimized paths for each structure, which are then assigned randomly based on time constraints and TSP path for the UAV. The work presented in [63] proposed an inspection path planning approach that formulate the CPP as an extended TSP, where coverage and obstacle avoidance are taken into account. The surface of the mesh model of the structure of interest is used to generate viewpoints perpendicular and at a distance from the structure surface. The TSP is solved using an enhanced Particle Swarm Optimization (PSO) approach developed in GPU framework.

Additional research work performing model-based CPP and considering the UAV energy are presented in [23, 82]. The work presented in [23] proposed multi-objective Evolutionary Algorithm (EA) to generate coverage path for complex structure inspection targeting coverage and energy objectives. The proposed work performs uniform sampling based on an existing model, utilizing a predefined bounding box, and discretization resolution. The EA plans the path using the Non determined Sorting Genetic algorithm (NSGA-II), then it measures energy and coverage scores offline and penalize paths with collisions. Minghan and Volcan in [82] proposed a CPP approach that considers the energy of the UAV in order to perform area coverage. The area is represented as polygonal grid with single charging station where the polygonal grid represents the viewpoints. The coverage planning approach follows a depth-first approach, where three types of robot motion are defined including Advance (move to the next cell providing shortest path), Retreat (return to charge) and Follow (follow current contour). Most of the presented single robot model-based CPP approaches targets area coverage and simple structures. Some of the approaches focuses on the energy aspect without focusing on the quality of the scans and the computational cost which are critical in CPP applications [13, 82].

The second approach of the single robot CPP approaches follows a non-model based approach. The work presented in [76] proposed a CPP approach extended from [75] by utilizing the surface information to plan the coverage path online using Truncated Signed Distance Fields (TSDF). The search space is divided into cuboid regions that are used to build a volumetric map of containing surface regions and frontier regions. The volumetric map is used in computing the Information Gain (IG) considering the cuboid volume and path length. Visitation order is computed for each cuboid applying Hamiltonian path problem while the path is generated using Generalized TSP. Another non-model based approach is presented by Emanuele and Cyrill in [58] where they proposed an exploration algorithm, which selects the Next Best View (NBV) that maximizes the predicted information gain, taking into consideration the cost of the distance, and battery life. The proposed work dynamically builds a hull that surrounds a predefined bounding box which is updated based on the new information. The viewpoints are uniformly sampled into a fixed number where they point to the vertical axis that passes through the centroid of the bounding box. The planning approach follows probabilistic approach with a utility function that reduces the 3D reconstructed model uncertainty, turns in the flight path, and produce safe path based on time limits. The energy aspect in non-model based single robot approaches is considered a critical part, especially because the CPP is performed online. Using this type of approaches with a single robot makes it hard to achieve a high coverage percentage and increase the computational complexity. This difficulty arise from the complexity of the environments which include occluded regions that are hard to be found by single robot and consumes a lot of time of exploration. A review of other single robot CPP approaches with critical analysis is presented in [5]. The advantages and disadvantages of model/non-model based approaches are highlighted in the viewpoint generation subsections and the discussion section.

2.2 Single or multi-robot

For large areas and structures, utilizing multi-robot CPP strategies could have great advantages in achieving full coverage rapidly. Utilizing a single robot to cover a large structure or a wide area suffers from various drawbacks including time, length, robot energy, and quality and quantity of information [15, 26]. Multi-robot CPP approaches follow the same approaches of single robot coverage but additional factors and requirements have to be considered. These factors are: cooperation type, information sharing, robustness of agent failure handling, autonomy level, robot endurance, and task allocation. This paper surveys different approaches that utilizes multi-robot systems from the perspective of the CPP components including the viewpoints generation and path planning approach. Viewpoint generation will be surveyed in details in Sect. 3.1. Path planning approaches can be divided into grid based search approaches, geometric approaches, reward based, NBV approaches, and random incremental planners. Each of these approaches will be surveyed in Sect. 3.2.

3 Multi-robot CPP

Various aspects need to be considered in order to perform CPP using multi-robot systems for model reconstruction and mapping. The two main CPP related aspects in order to generate a feasible coverage path include viewpoints generation and path planning. The remaining aspects are communication/task allocation which is critical for multi-robot systems, and mapping which is important for modeling the area or structure of interest using the gathered data. This section provides a detailed description of each of these aspects and the employed approaches in each one of them.

3.1 Viewpoints generation

In majority of the work presented in literature, the coverage exploration methods are classified into model-based, and non-model based exploration methods. The model-based exploration methods depend on a reference model of the environment or the structure is provided priori, while the non-model based methods perform planning and exploration without having a prior knowledge of the structure or environment [72, 73]. Based on this classification, the viewpoints are generated to form the search space of the planner.

Some of the viewpoints generation methods are uniform due to the dependency on the structure or region model existence, and the predetermined region or structure model. Other types of viewpoints generators are randomized due to the lack of knowledge about the model of the structure or the regions.

Viewpoints generation is considered critical in multi-robot CPP process, since it aims to output a set of optimized paths representing a set of admissible viewpoints that covers the structure or environment of interest. Various techniques are used in literature to perform viewpoints generation based on the used exploration method and the coverage application.

3.1.1 Model-based

Having a CPP algorithm with uniformity characteristics means that the robotic sensors are deployed to a predefined coverage pattern [44]. Most of the algorithms in literature are of a uniform nature especially when the model information is already available. Having the model simplifies the process of generating viewpoints especially in critical areas giving higher weights to some high priority areas of the model. It also facilitates the process of connectivity network generation which forms the search space for the path planners. The main limitation of these approaches is the size and quality of the existing model or region.

A good example of model-based viewpoints generation method is a grid-based sensors deployment and the grids can be of different shapes like: triangular lattice, square, hexagon, diamond, etc. The work presented in [56] performed grid based decomposition according to each UAV footprint considering sensor size, focal length, and UAV altitude. The squares of the grid are divided into residential, empty and energy depots in directed graph. The authors in [61] proposed a hexagon pattern as shown in Fig. 1 for their cell decomposition. The generated 2D hexagon cells are used for 2D planning and the generated paths are transformed into 3D adding z elevation value based on an elevation map. The work in [25] performed subsequent Trapezoidal decomposition (convex polygons) of the 2D environment until it computed a set of samples (guards) where each guard can cover one convex polygon. The samples are used as part of graph computed using a reduced constrained delaunay triangulation. A Boustrophedon Cell Decomposition (BCD) approach is used in [39] to generate either a weighted graph called Reep graph or divide regions into passes that are used in unweighted graph. Furthermore, the work in [28, 55] performed grid based decomposition for a 2D area of interest. The decomposed area is used then in planning the path and the assignment of the regions to the team of robots. Similarly in [50], the area is divided into evidence grid cells based on an elevation map where each cell holds the value of posterior probability of fire using fire front contours. The fire front contours are obtained using a fire segmentation algorithm from several images. The obtained fire fronts by each vehicle in the team of robots are used by the central station to update the probabilities of each cell of the grid.

Fig. 1
figure 1

Hexagonal decomposition steps including a Hull of area, b generating a set of hexagons that are inside area in green or intersecting, and c calculating centroid of every hexagon. d An example of non flight-able zones inside possible grids. Courtesy of IEEE [61]

In addition to grid based approaches, the work in [7] performed 2D decomposition into sweeping rows, where each row represent an edge in the graph representation. A rotated polygon is used to define the sweeping direction with low turns and rows. The distance between rows is computed based on the sensor footprint overlap. A Vehicle Routing Problem (VRP) is then solved to divide sweeping rows among the set of UAVs. The authors in [47] divided a 3D complex structure using horizontal planes translated vertically along z-axiz to check number of loops and intersection points as shown in Fig. 2. An offset is added to the structure to generate the viewpoints at a distance from the structure. A graph theory approach is used to check the number of loops then a clustering algorithm is used to categorize the number of points to each loop that are then used as viewpoints. if the structure had one slice, then the viewpoints are categorized based on the reference yaw difference between UAVs. In the case of multiple slices, each UAV is assigned to a slice where each one of them will have the same number of viewpoints. The work in [44] divided the area of interest into big voronoi cells based on the used number of agents. Furthermore, the work in [45] used different representation for the region of interest such as a 1.5D terrain where the altitude value for every x along a single dimension is returned by a function interpreting the 1.5D terrain. This process utilizes fixed altitude paths and the chain visibility property of 1.5D terrains to generate visibility segments that are then used to extract viewpoints for each agent.

Fig. 2
figure 2

Concept of plane slicing and intersection points. Courtesy of [47]

In [4], a generalized Voronoi diagram approach was utilized in order to perform safe uniform distribution of many robots in complex areas for the purpose of coverage. This work performs initially a grid decomposition of the complex area which converges to the computed Voronoi partitioning. The complex area is partitioned using a modified Dijkstra algorithm and growing functions to provide safe distances between multiple robots.

The work presented in [12] proposed a grid based decomposition approach to divide the area and generate the viewpoints for multi climbing robots. A set of voronoi cells were used in the decomposition to divide a user selected area in order to be explored by the team of robots. In this work, either agents spread locally and then interact for coverage globally to sweep over the area (method 1), or agents assign areas of operation cooperatively then each agent sweep over their areas (method 2).

Majority of the mentioned papers are following 2D grid based approaches consisting of cells. However, grid based representations with its various shapes have limitations in the coverage of boundaries areas and handling partially occluded cells. On the other hand, sweep based approaches ensure every point has been seen by at least one robot performing progressive movements through the environment. These type of approaches is considered energy and time consuming approaches. Furthermore, structures and environments of complex shapes are hard to be decomposed and will generate a set of slices of different shapes. Distributing these slices among different robots is difficult in terms of effort where some robots might have large areas and others have small ones. Therefore, efforts distribution is another issue that need to be maintained in multi-robot systems considering trajectory distance, area to be covered, time, and energy.

3.1.2 Non-model based

The locations of the viewpoints in non-model based CPP algorithms are not predetermined. Additionally, it is suitable in the cases when there is no information about the model of the structure or the region. Non-model based algorithms are preferred in large scale coverage problems where the positions and number of required viewpoints cannot be predetermined. The main challenge in non-model based approaches is maximizing coverage while minimizing the energy consumed by the team of robots.

A set of approaches of randomized characteristics are presented in literature and classified in various ways. The work presented in [20] proposed a frontier based exploration algorithm for a team of robots. Initially the robots are randomly located in an unknown environment where an initial map is generated by the first robot and utilized by the other robots to localize themselves using particle filter algorithm. The approach is based on identifying frontiers in the initial created occupancy grid map and performing threshold rank based frontier allocation.

Additional work with random characteristics is presented in [21], where two-step procedure that allows aligning a team of flying vehicles is proposed for the purpose of surveillance in GPS denied areas. The algorithm starts by generating an elevation map using modified visual Simultaneous Localization and Mapping (SLAM) and meshing approach. Then, the map used to generate a set of initial candidate positions (viewpoints) for the team of robots. This set is randomly generated at the beginning, and then it is optimized using cognitive and adaptive methodology. This methodology aims at maximizing visibility and coverage while minimizing the path distance. Furthermore, Sai and Srikanth in [80] proposed an uncertainty aware path planning approach for multiple UAVs that collaborate between each other for vision based localization. This approach Involves solving an NBV by taking the initial poses of the UAVs, then minimizing a weighted heuristic function to generate better poses at each iteration. This optimization function is solved using Covariance Matrix Adaptation Evolution Strategy (CMA-ES) algorithm which contains certain degree of randomness. The heuristic involves different aspects including visibility, span, overlap, baseline, vergence angle, collisions and occlusions.

These articles presented non-model based approaches of randomized behavior which consumes time and energy. Generating the candidate viewpoints at each step for each robot consumes time and requires cooperation to avoid repeated coverage. Non-model based approaches are considered practical in cluttered environments where the environment has unknown dynamic objects like in search and rescue, or disastrous environments, but model-based approaches are more practical in applications like inspection, modeling, and fault traceability. Non-model based approaches require no prior knowledge and also allow performing online re-planning in case of a failure of one of the agents. Moreover, performing decentralized non-model based exploration is costly compared to centralized exploration as interactions across and within robots increases. However, using decentralized non-model based approach provides long term benefits of reaching high performance.

3.2 Path planning approaches

Various multi-robot CPP approaches are surveyed in literature illustrating the challenging problems and the proposed solutions. All these approaches have similar goal which is to provide a collision-free path that achieves full coverage of the structure or region. These approaches are classified based on the path planning methodology into: grid based search, geometric, reward based, NBV, random incremental planners approaches.

3.2.1 Grid based search approaches

The most important grid based search methods in cooperative CPP consist of Cell Decomposition (CD) methods, and tree based search methods. The cell decomposition methods are further classified into exact and approximate cell decomposition.

The work of Rekleitis et al. [67] extended the BCD approach from single robots to multi-robot systems for covering unknown arbitrary environments. Based on the communication restrictions, two types of algorithms were presented including distributed coverage and team-based coverage. Both types utilize a sensor based approach and assume an unknown environment. This work minimizes repeated coverage employing an auction mechanism which facilitates cooperative behavior among the team of robots. Another work utilizing BCD approach is presented in [14] which divides the cells equally among the robots. Each of these cells is covered by an atomic cycle algorithm. The main objective of this work is to minimize the path execution time. Adiyabaater et. al [33] proposed a method of path planning for coverage that plans the minimal turning path based on the shape and size of the grid cell. This approach provides efficient covering order over the cells based on distance among centroids of cells. It also provides more optimal coverage path and reduces the rate of energy consumption and working time.

Moreover, a recent study in [7] proposed a two stage multi-robot coverage approach similar to the presented work in [83]. The first stage constructs a complete graph by decomposing the area of interest into line sweeping rows as shown in Fig. 3 where the borders of the coverage rows represent the vertices of the graph. The second stage utilizes the generated graph to divide the sweeps among the team of robots by solving a VRP. This approach ensures performing coverage in short time for UAVs in contrast to other approaches as claimed by the authors. Minimizing the number of required robots for completing the coverage is one of the main objectives of this work. However, this work could only be employed in clear areas with no obstacles.

An exact cellular decomposition method is proposed in [32] to achieve complete coverage utilizing flow networks using single and multiple mobile robots. In this work, the free space of the environment is divided into a number of cells utilizing sweeping lines. These cells are approximated to be either trapezoidal or rectangular which form the flow network nodes. Then, the minimum cost path from the generated flow network is computed using a search algorithm. Each cell in the flow network is covered using twelve developed templates of back-and-forth motion. The total coverage time is calculated considering the duration of covering the cells and the durations of the moves between the cells taking into consideration of the order in the flow network.

Fig. 3
figure 3

The back-and-forth sweep motion performed along lines perpendicular to the sweep direction for a rectangular area coverage. The number of turns outside the area of interest is influenced by the sweep direction which affects the coverage duration. Courtesy of [7]

An additional classical approach is developed by Fazli et al. [24] which include several algorithms for the problem of multi-robot repeated area coverage. The overall proposed approach is divided into stages. The first stage include generating a set of points called static guards such that the entire environment of interest is observed joining all the points. The number of guards is assumed to be similar to the number of robots. The second stage involves creating a graph connecting the guards and the workspace nodes. The third and forth stages include reducing the size of the graph and covering the graph using either cyclic coverage or cluster based coverage. The aim of the cyclic coverage is to generate the shortest path by allocating a portion of the generated path which passes through all the guards to each robot in the team. However, the cluster based approach divides the graph into clusters according to the number of robots. The authors presents several algorithms to tackle the problems of each mentioned stage.

A classical grid based approach is proposed also in [8] where the area is divided into hexagonal cells which are then clustered. These clusters are allocated to groups of aerial vehicles based on the battery level and position in order to acquire data. The cells can be covered by either centroid, square or lawnmower patterns with specific configurations to address the constraints of magneto-metric (geophysical) surveys. The three patterns are illustrated in Fig. 4. In this work, collisions are avoided by assigning different altitudes for the UAVs. This approach aims to minimize the survey time and to be adaptable for different vehicles and resolutions.

Fig. 4
figure 4

Different patterns of coverage including Lawnmower shown in (a), Square pattern shown in (b), and Hexagon centroid shown in (c). Courtesy of Springer [8]

Furthermore, the work in [19] proposed a greedy approach to calculate the path for exploration. The used graphs for path search are grid graphs. The main aim of this work is to minimize the total UAV traveled distance ensuring that every node in the path is visited exactly once. The same amount of nodes are assigned to every UAV to explore assuming there is no jumps. The work presented in  [38] proposed a coverage approach for multi-robot system to deal with the complete, optimal, and communication-less coverage problem. The problem is defined as Min Max k-Chinese postman problem where the main goal is to minimize the maximum coverage cost over a group of robots. This paper proposed two approximation heuristics for solving the multi-robot coverage problem. The first presented solution is an extension of exact CD approach which is considered as an efficient single robot area coverage algorithm. In this solution, a Eulerian graph (every vertex in the graph has even degree) is generated, then a Eulerian path is computed (a path where each graph edge is visited once). The second solution is using a greedy approach (Breadth First Search) by which the area of interest is divided into equal parts, then a single robot coverage approach is applied to each part.

Different classical CPP approaches were used in fire monitoring applications as described in [9, 48, 49, 62]. In [48], a CPP approach is proposed for forest fire surveillance. The main parts of the proposed approach of fire monitoring involves fire detection, confirmation and precise localization with several cooperating UAVs. The fire detection and confirmation is achieved by applying fire segmentation to extract fire contours which are used then to compute the fire front position. The overall area to be surveyed by the team of UAVs is divided into convex searching regions. The UAVs perform back and forward rectilinear sweeps in order to cover their convex regions. The area decomposition is performed taking into consideration minimizing the number of sweep turns. These sweep turns consume significant amount of time for the UAV stop, rotate and then accelerate for the next sweep. A similar approach to [48] was followed in [49] and focused on the perception system and the contour detection. The work in [62] proposed a distributed coverage control approach in order to monitor a wildfire and track its development in open spaces using a team of UAVs. The area is divided into discrete grid that include information about the fire spread. In this work, the UAVs team follow the border region of the wildfire as it keeps expanding while simultaneously maintaining the coverage of the whole wildfire. This work utilizes potential field control for collision avoidance, and directing the robot towards of fire fronts. Another fire monitoring algorithm is proposed in [9] which proposed Variable Neighborhood Search (VNS) approach that generate the UAVs trajectories in order to observe the fire front. This approach depends on modeling the area of interest as grid of cells holding information about the fire propagation. The fire front depends on the rate of spread from one cell to another and the main propagation direction. The fire spread rate is calculated using Rothermel’s method. The planning algorithm of this work distribute the task implicitly such that the same locations are not observed by the team of UAVs concurrently.

A typical approach used in cooperative CPP is the use of Spanning Trees. A spanning tree approach is presented in [25] where a Multi-Prim’s algorithm is used to partition a graph into a forest consisting of partial trees for the purpose of inspection. The graph is generated by performing subsequent Trapezoidal decomposition (convex polygons) of the 2D environment until each single guard (sample) can cover a corresponding single convex polygon. The presented approach performs graph reduction to reduce the time required by the robot to traverse the graph. Then, a Constrained Spanning Tour (CST) method is used to build cycle on each partial tree and assign each cycle to a robot. The algorithm minimizes the redundant movements and guarantees the coverage completeness. Using this approach, robustness is also guaranteed by handling failures using supportive trees. Figure 5 illustrates the described spanning tree approach.

Fig. 5
figure 5

a A sample tree, b double-minimum spanning tree (DMST), c revised-DMST, d CST. Courtesy of IEEE [25]

Additional work presented in [85] deals with the problem of non-uniform traversable terrain coverage using multi-robot systems. Their algorithm can handle a terrain with locations that does not have a constant traversing time. In order to handle terrains with non uniform traversability, this algorithm extends the Multi-robot Forest Coverage (MFC) algorithm. The work was compared against Multi-robot Spanning Tree Coverage (MSTC) and it generated paths with shorter coverage time. The work in  [86] proposed a Multi-objective Genetic Algorithm (GA) with forest individual containing non-intersecting trees (Mofint) to tackle the time-limited complete coverage problem. It finds the least number of robots and allocate tasks to these robots optimally to finish the mission within a time limit. The environment is decomposed into regions (nodes), of specific weights, and edges representing the borders of two regions, where the weights are used to indicate the coverage completion time. An arbitrary spanning tree of the graph is divided by the proposed work to find the lower and upper bounds of number of robots. Then a time limited version of the problem is viewed as a number fixed problem (min-max Balanced Connected Partition (BCP) problem) which forms with the estimated bounds a bi-objective optimization problem (Multi Objective Optimization Problem MOP). The Mofint algorithm includes two objective functions where they focus on the number of the spanning trees (objective 1) and heaviest tree (objective 2). This work outperformed the MFC in the least number of robots used and the average completion time.

In a recent work presented in  [37], the authors proposed an algorithm that partitions the area of interest fairly among a team of robots considering their initial positions. For each robot planning, the algorithm construct a Minimum Spanning Tree (MST) for all the unblocked nodes and then Apply the ST to the original terrain and circumnavigate the robot. Their solution is considered efficient in terms of computational complexity and it guarantees covering the entire area of interest without backtracking paths. Although this algorithm tackles the problem of fair area partitioning and CPP, the approach accounts only for fixed cell sizes for area division while not all sub-areas have a uniform geometric distribution. Another work utilizing spanning tree is proposed in [41] which focuses on time synchronized coverage control of cooperative mobile robots. Given a set of Locations To Visit (LTV), the proposed work generates a Euler graph path tree to be used for coverage work. In order to have a synchronized execution time of cooperative robot coverage, time-synchronizing velocity profiles are designed for all LTV pair.

3.2.2 Geometric based approaches

Geometric based approaches utilizes visibility graphs in generating the path. The visibility graph includes a set of points and obstacles where the nodes represent the locations, and the edges are line segments that do not pass though obstacles. Geometric approaches are used in many areas such as finding shortest euclidean path, and polygonal area coverage. The most used Geometric based method in multi-robot CPP is the Voronoi Diagrams.

In  [84], a Dynamic Path-Planning approach for heterogeneous Multi-Robot Sensor-Based Coverage (DPP-MRSBC) is proposed considering energy capacities. The environment is modeled as Generalized Voronoi Diagram (GVD) where the edges of the diagram need to be covered. The proposed algorithm starts with undirected graph then generates subgraphs that are directed. These graphs are used to generate optimal paths for each robot which are then turned into arcs with costs referring to its lengths. Then, directed multi graph is used to find the shortest path. The Ulusoy’s partitioning Algorithm (UA) is modified to add energy demands (energy, coverage) and to re-plan path utilizing the remaining energy capacity. The work in [1] proposed a control algorithm that forms the sensors to a Voronoi tessellation while score function of the coverage is increasing. The proposed work utilizes the Voronoi tessellation defining a coverage score function as a measure of the quality of the surveillance attained by the sensor network.

Moreover, the work presented in [29] uses multi-objective optimization to allocate the partitioned areas to the robots whilst optimizing robot team’s objectives. The area surface is partitioned following Voronoi partitioning approach. The main optimization objectives include minimizing the overall completion time and achieving complete coverage in addition to optimizing the manipulator joint’s torque. Fotios et al. [10] proposed a coverage approach based on partitioning a coastal region for a team of heterogeneous UAVs. The proposed approach combines the strategies of graph search and computational geometry algorithms which partition the area of interest regardless of the number of UAVs or their relative capabilities and consider the sensing radius and Field of View (FOV). Initially, the area is partitioned using a growing regions approach which perform isotropic portioning based on the UAVs’ initial locations and relative capabilities. Then, the area and holes are defined by a forced edge constraints performing a Constrained Delaunay Triangulation. The described coverage approach is Antagonizing Wavefront Propagation (AWP) which is a step transition algorithm that involves an isotropic cost attribution. This algorithm starts from the initial position of each UAV, propagating towards the other UAVs or the borders of the area.

In [69], a coverage algorithm is proposed to efficiently generate a flight plan to completely cover a given area of interest (i.e. area with complex contours or must not be overflown). The first step of the proposed approach include the computation of the area of interest percentage that should be covered by each robot considering the sensor footprint of each UAV. The number of cells of the grid required for each sub-area is determined using the computed percentage values. The sub-areas are further extended using flood-fill like algorithm. The second part involves performing path planning which prioritizes the selection of long straight segments (stride) to reduce the number of turns. In order to select strides, a set of heuristics are proposed including the selection of the neighbor cells with a higher value, the ones located in the contour of the area, and the ones that lead to a longer stride in the next step.

Another type of geometric approach is the work presented in [35] which proposed a partitioning scheme that depends on creating a power diagram to cover non convex areas. The power diagram takes into account the different sensing capabilities available in each agent in addition to the visibility domain of the agents. A distributed gradient control scheme is also proposed to lead a set of heterogeneous robots to cover the specified area.

3.2.3 Reward-based approaches

The reward based approaches are employed in several recent work in multi-robot CPP due to their advantages such as nonlinear mapping, learning ability, and parallel processing. The most important used methods include Neural Network (NN), Nature Inspired methods and hybrid algorithms.

Several bio-inspired multi-robot coverage approaches have been developed based on the behaviors that exist in nature. Ranjbar-Sahraei et al. [65] presented an example where the robots avoid entering the boundaries of each other utilizing the behavior of the ants. The robots in this work move in a 2D environment in a circular motion where they deposit pheromones on their areas’ borders mimicking the ants behavior in order to reduce the intersections of borders. That is, if a pheromone is detected by a robot, it changes its motion direction and hence avoids another robot’s border. As a result, this approach facilitates spreading out the robots in the environments gradually. This approach is further extended in the paper into two extensions. The first extension include increasing the radius of the robot’s circular motion if pheromone detection likelihood is small and vice versa. The second extension facilitates the behavior change when an intruder is detected by decreasing the robots territory areas. The authors in [36] proposed an approach that minimizes the completion time and number of turns of a team of robots while trying to achieve complete coverage. The proposed work follows a grid-like decomposition approach that is based on disks. The experimental setup consists of areas of convex rectilinear polygons. A pattern based genetic algorithm is used to achieve complete coverage by utilizing eight neighbor-disk prioritization patterns used to represent rectilinear moves. The results of using two patterns is illustrated in Fig. 6. An optimized genetic algorithm combined with total coverage method is proposed in [17] for generating 3D map of large areas using multiple UAVs. The area of interest in this work is divided among the team using flood fill algorithm and game theory, then the proposed path generation algorithm is applied on each sub area. In [42], a genetic algorithm is used to plan a path that detect the entire area. Initially, this is done for one drone, then the search space is divided among the UAVs according to their position and endurance and multi-objective Integer programming model.

Fig. 6
figure 6

The sample chromosome of a solution including number of robots: 3 and number of allowed patterns: 2 is shown in (a). The chromosome decoding is shown in (b) where three shapes (diamond, circle, and square) are presented and have two representations including (i) the robot initial location if numbered 1, and (ii) shortest path’s starting and ending points related to repeated coverage motion if numbered 2 or more. Courtesy of Springer [36]

The work in  [57] proposed an optimal coverage path planning approach and coverage action controller that performs an active selection of goals. Two cost functions are proposed in order to allow robots to avoid obstacles, and to find the optimal paths to the specified goals. The method used to select the best goal considers the coverage paths and introduce the notion of safe goal.

3.2.4 NBV approaches

NBV approaches are usually used when no information about the model exists priori. NBV approaches scale better to complex real-world. Some of the NBV approaches in literature are of probabilistic characteristics which provide estimation not fixed value.

One of the recent NBV CPP approaches is described in [46] where an exploration algorithm is proposed to collect water samples by building spatially varying phenomenon over a specified region without prior knowledge about the spatial field. The built spatial varying fields provide emphasis on locations that are good for sampling. The candidate locations for the explorer are generated using two techniques including fixed-window, and Contour-based location selection methods as illustrated in Fig. 7. It includes two related subproblems including exploration algorithm to generate the phenomenon map, which concurrently facilitates collecting actual physical samples using the sampling algorithm. The exploration is performed using Gaussian Process frontier-based approach by which it measures variables to suggest sample utility. A look-back selective technique is used for sampling where the new candidates are appended to a list which is used later by the robot to look back for non-eligible candidates within the specified time period. The main aim of the proposed work is to generate a good spatial phenomenon model and to compute a path optimized for distance and time. Another approach is presented in  [52] which builds probabilistic decision maps to compute exploration paths using a grid that represents the sum of expected scores to pick and place static and dynamic objects. The main aim of this work is to minimize the combined search and action time with targets found in an environment using finite horizon plans. The Probability Density Maps (PDM) is built using reward prediction function which corresponds to the probability of finding new objects or targets. The PDM is updated through a Bayesian filtering procedure applied on the grid of the arena area where each cell represents a state.

Fig. 7
figure 7

The colormap shows the variance in the spatial representation of the field. The potential candidate locations are represented by red circles. The contours are shown in black lines. Two location selection approaches are shown including Contour-based (a) and fixed-window locations selection (b). Courtesy of IEEE [46]

Another work following NBV approach is presented [54] which aims at increasing information about uncertain areas while performing coverage. The environment is modeled using Voronoi partitioning approach where the Voronoi regions are assigned to vehicles using a locational optimization approach. The proposed distribution density function is formulated based on some unknown targets’ positions which can be detected using the appropriate sensors. The vehicles are divided into two teams including service and search vehicles. The search vehicles find the targets in order to allow the service vehicles perform coverage efficiently. The search vehicles find their path that maximizes the gathered information individually using a look-ahead dynamic programming algorithm. The objective of service vehicles is to optimally cover the terrain by spreading out over the environment of interest. Similarly, the work in [64] proposed a two layered exploration approach including coarse exploration layer performed by UGV, and fine mapping layer performed by UAVs in GPS denied environment. The UGV starts exploring the area of interest using 3D laser to create a rough 2.5D volumetric map using SLAM, which is then used by the UAV to update occupancy data of the gaps using 2D tilting laser. A frontier coverage planning approach is followed to generate a set of viewpoints which are then used to compute the path using a Fixed Start Open Traveling Salesman Problem (FSOTSP). The cost function used in FSOTSP is formulated using traveled distance and information gain. A volumetric motion planning interface is developed to support the navigation of both UGV and UAV applying Batch Informed Trees (BIT).

Vera et al. [51] proposed a variation of VRP with an insertion heuristic and a negotiation mechanism for energy resources, and a heuristic for the continuous monitoring problem with inter-depot routes and priorities (CMPIDP) that uses all available information and is fast enough to react to dynamic environmental changes.

3.2.5 Incremental random planners

The main two important sampling methods include Rapidly exploring Random Trees (RRT) and Probabilistic Road Map (PRM). The most used sampling based method is the RRT method with all its variations. The work presented in [11] proposed a receding horizon planning approach to compute an optimized exploration path. The method utilizes an occupancy map to represent the environment where a finite iteration random tree (RRT*) is grown in the free space part of the map. The best branch of the random tree is selected based on the amount of the unmapped space by which the first edge is executed at every planning step iteratively to complete the exploration.

The work in  [80] described previously in Sect. 3.1.2, utilized random planners as the second stage of the planning framework which performs belief space planning. This is performed for the vehicles individually using the Rapidly Exploring Random Belief Tree (RRBT) algorithm. This method generates paths that ensures having high image quality and improved vehicle confidence by optimizing the path cost and reducing the localization uncertainty.

This type of methods have limitations related to dynamic environments especially in multi-robot systems. If one of the robots’ paths is blocked by an obstacle or one of the robots failed, then a re-planning process need to be preformed for the entire team which is of high computational cost.

3.3 Communication and task allocation

Communication is a challenging aspect in multi-robot systems. The common assumption in literature is that communication is unlimited in range and bandwidth. Nearly all centralized systems assume that the individual robots can communicate directly with the central controller such as [44, 70], and algorithms that create maps assume global communication [53, 57]. Since communication systems are often down in the aftermath of a disaster [51, 61], achieving coverage with limited communication must be a critical aspect that must to be considered.

The actions of the robots in a decentralized system are based on the collected information about the other visible robots. These collected information include the actions and locations of other visible robots, with respect to their local coordinate system. Most robots can provide some local communication means such as wifi [21, 46] or line-of-sight (LOS) [12, 21, 54] methods, which can then be used to direct the team of robots and avoid overlapping actions. Line-Of-Sight (LOS) communication as described in [54] is based on categorization scheme by which the team is divided into search vehicles and service vehicles. The search vehicles maximize the amount of gathered information while the service vehicles spread in the environment within a specified range to cover the entire area. The work in [12] defines critical points for allocating cells based on several factors, one of them is the LOS. Teams that are involved in GPS denied or uncertain areas (disasters) utilize these kind of communication technique.

Decentralized multi-robot systems are considered fault tolerant, and scalable as the system is of distributed architecture and modular. Distributed modular systems allow detecting faults and replacing affected robots without having global control which increases the system robustness such as the work in [34]. Furthermore, using decentralized systems reduce the network overhead introduced by information exchange between robots. Several decentralized multi-robot systems have been proposed which shares information with the nearest neighbor such as [52, 62]. The work presented in [57] performed distributed Voronoi partitioning where each robot uses a relative configuration of other robots within its sensor range. The distributed partitioning is performed by incrementing pseudo sensor range in steps while the range constrained Voronoi cell gets contracted to obtain the desired region. The work in [70] proposed a hybrid decentralized multi-agent path finding framework. It combines Reinforcement Learning (RL) for planning single agent paths and Imitation learning from centralized path planner. In this work, the agents select movements that will benefit the whole team using the learned decentralized policy where the agents perform implicit coordination during the online path planning without having explicit communication among the team.

Another decentralized approach for information sharing between a team of UAVs is proposed in [40] where the UAVs performs two types of map updates at each time step: uncoordinated map update, and coordinated map merging. The first type generates an uncoordinated occupancy probability using local information only, while the second update combines the local information with the other UAVs robots in order to compute the actual probability for the map. Three types of coordinated map merging approaches are proposed including belief update, average, and modified occupancy grid map merging. The work in [34] proposed a one-to-one decentralized coordination where each pair of UAVs share their own area to survey. Taking into consideration all the one-to-one coordinations between neighboring UAVs distributes the whole team efficiently. The work in [64] performed decentralized exploration using UGV and UAV platforms where each one of them updates their map and navigation on their own then share it with the other vehicle.

3.4 Mapping

Different kinds of applications require detailed 3D models and 2D maps such as: terrain surveillance, indoor mapping, inspection, fire monitoring, and urban planning. In general, a model reconstruction and an environment mapping process involves four steps including: viewpoint planning, scanning, registering, and integration [73]. Robot localization is considered an important requirement to perform accurate reconstruction and mapping. It is performed usually as part of the most used approach in mapping which is the Simultaneous Localization and Mapping (SLAM). Some work in literature represents the workspace reconstruction as an environment mapping application and others represents it as a model reconstruction of a structure of interest.

Most of the reviewed work in literature performed area type of coverage for various kinds of environments. This type of environments include terrain, arena, indoor environment, and forests. For example, The work presented in [25, 36, 83, 84] utilized topological maps in the planning process. For providing the covered map, some presented work performed monocular Structure from Motion (SfM) and stereo Iterative Closest Point (ICP) as in [47] generating 2D map. Other work performed 3D reconstruction using Real Time Appearance Based Mapping (RTABMap) [66] generating 3D textured meshes and octomap [30] generating 3D occupancy maps as in [60, 75]. Moreover, some of the reviewed work especially the ones performed in natural environment overlay the path on the google map as illustrated in [7, 39]. Additionally, some work performs meshing as to reconstruct 3D mesh structures utilizing techniques like TSDF or triangulations as in [76, 80].

Another aspect important in mapping and information gathering is related whether the information is processed online while the planning is performed or offline after completing the coverage mission. Most of the work presented follows an offline process as described in [8, 38, 51]. Based on the type of processed information, performing the mapping online as in  [33, 53, 57] facilitates monitoring and adapting to new changes but at the same time is computational expensive and could affect the planning process.

4 Discussion and future research directions

Modeling and mapping environmental terrains and complex structures is considered an essential process for increasing the level of autonomy in wide range of application domains. Generating an efficient coverage route is a critical requirement in order to gather accurate information through the viewpoints encapsulated in the route in order to perform modeling and mapping. Utilizing a team of robots minimizes the effort required by each member to achieve the coverage task. The team of deployed robots in CPP could include various homogeneous and heterogeneous robotic platforms which facilitates the coverage and mapping tasks.

Based on the work surveyed in the literature, various research components have to be taken into consideration while developing multi-robot CPP approaches, such as: type of the environment, the dimensionality of the CPP problem, the number of sensors and agents type, and the coordination and communication technique. The CPP problem is divided into two processes, viewpoints generation and path planning. The sequence of using these processes is affected by the existence of the environment (model-based/non-model based) and the type of prior available information (2D map, 3D mesh, 3D point cloud). Based on the dimensionality of the problem, various types of information could be used during mapping and reconstruction, and different mapping techniques are utilized to generate the final map or model. Various evaluation metrics were considered in literature but the main common metrics include coverage completeness, path length, execution time, robustness, and energy consumption. The different parts of performing CPP using multi-robot system are summarized in Fig. 8.

Fig. 8
figure 8

The main components of the multi-robot CPP

Most of the presented CPP approaches in literature implement model-based viewpoints generation algorithms such as  [12, 25, 46, 56, 59]. The majority of these papers are generating grids consisting of cells, and are applied on 2D type of environment. However, grid based representations have limitations in handling partially occluded cells or cover areas close to the boundaries in continuous spaces.

Another commonly used approach for multi-robot CPP in 2D type of environments is sweep coverage as described in [7, 32, 48]. In sweep coverage, the robots move progressively through the environment and ensure every point has been seen by at least one robot. While sweep coverage requires only a single pass, it is also used for repeated coverage as explained in [24, 36, 67]. This type of coverage keeps the team small, hence easier to deploy, but still provides complete coverage, as required for search and rescue. Another common assumption is that robots have a map to direct their movement. Usually, the overall region is divided to minimize the number of sweep turns which consumes significant amount of time for the UAVs to stop, rotate and then accelerate for the following sweep. Moreover, performing Cyclic Coverage as described in [24] may not be an appropriate approach compared with the Cluster-based algorithms as in [8] especially in situations where the target area include regions with different coverage priorities or the robots have different speeds.

Heuristic based algorithms combine randomness and heuristics to drive the exploration process as in [20, 21, 59]. A good ratio between performance and cost could be provided by these type of methods especially that they do not consume much computational resources and do not require expensive sensors. However, parts of the area of interest may remain unexplored. Most of the methods surveyed in this article either follows a grid based search approach or reward based approach, hence both dominates the other described approaches. Probabilistic and spanning tree (grid based search) approaches are considered critical in performing coverage especially that it generates a continuous path. Different spanning trees implementations in literature differ regarding aspects such as computational complexity and quality of the generated model. Some of the methods in literature performed trajectory planning to generate a continuous smooth path for the robots as in [21, 54, 83]. It is considered a good property for continuous surveillance and modeling operations.

Achieving coverage completeness is the main aim of applying CPP. The work discussing multi-robot coverage of 2D regions [10, 36, 83] dominates the research on coverage of 3D structure [47, 80]. Working with simple 2D regions allows achieving coverage completeness faster. Some of the grid based search and reward based approaches achieves the coverage completeness by partitioning the region of interest and allocating the regions among the team members which is hard to be done in 3D.

Several assumptions were made in the different surveyed work in literature, especially those targeting multi-robot systems. Some previous work assumes that the robots can create maps and merge them when they regroup, but this is actually difficult to achieve in practice. Another common assumption is that communication is unlimited in range and bandwidth. Nearly all centralized systems assume that the central controller can communicate directly with all the individual robots, and algorithms that create maps assume global communication. The focus need to be on achieving complete coverage with limited communication since communication systems are often down in the aftermath of a disaster [51, 61, 69].

The surveyed articles evaluated the performance of their proposed work based on several metrics. The most important metric which is common between all the papers is the path execution time, especially that it is correlated to the path length and the energy level of the robots [32, 37, 84]. The different surveyed CPP algorithms showed that NBV and non-model based methods take much longer time than using other model-based or classical approaches. The sensing technique is considered another important aspect affecting the path execution duration which is either performed discretely where the data is gathered at each viewpoint or continuously along the path. Discrete sensing is used in most of the work presented in literature, since it allows the robot to perform scanning without missing observations by allowing it to stabilize at each viewpoint [46, 54].

The main components of the CPP process used in the recent surveyed work in this article are summarized in Table 1. Table 1 summarizes the recent surveyed research on the multi-robot CPP. In this table, each paper is summarized in a row, where the columns list the type of environment, the algorithm processing technique, viewpoints generation method, the coverage path generation method, and the evaluations metrics of the coverage method.

Table 1 Review of multi-robot CPP approaches

Based on the surveyed literature, there are numerous challenges hindering the progress of an efficient multi-robot cooperative CPP. These challenges could be classified as follows:

  1. 1.

    Heterogeneity Heterogeneity in a coverage scenario can be defined in different aspects, such as different movement or sensing capabilities of the robots or different platforms. Heterogeneity is critical in multi-robot systems to enhance the visibility in applications that require complete coverage and accurate data. Using heterogeneous sensors provides different types of data that could be utilized in providing a map of different information. One of the recent used sensors in wide applications is the event based camera which provides events instead of frames where events are generated at local intensity changes as independent asynchronous timestamped spikes. These kind of sensors can operate in different light intensities, and provide the property of low latency, and power consumption. An extensive review of all the algorithms, applications, and datasets is provided in [27]. Moreover, using heterogeneous platforms facilitates dividing complex tasks in harsh environments and enhance flexibility and mobility. For example, inspecting a bridge could be performed using a collaborative system consisting of AUV, UGV and UAV platforms providing data from underwater and on the ground. Most of the work presented in the literature utilize homogeneous type of robots and sensors such as the work presented in [28, 40, 69, 84] which limits the coverage dimensionality. Few papers utilized heterogeneous type of robots and sensors as in  [45, 48, 49, 64].

  2. 2.

    Prioritization In some applications, parts of the target area should be visited or covered sooner than others due to different priorities. Prioritization is of great significance in large areas and big structures especially for time critical tasks where it facilitates the detection of fire, and danger. Some of the work presented in this review utilized the priority in an area coverage application as in [36] where the work provided a priority index to the robots, selected patterns in the grid. In another work presented in [29], a prioritization is performed to the objectives of the optimization function based on the allocated partitioned areas. The work in [84] also prioritized the robots to avoid planning conflicts.

  3. 3.

    Robustness Robustness is another critical part in multi-robot systems since it is related to handling robot failure. There are different robustness criteria that need to be considered in the real world, such as message loss, robot action failure, and communication failure. Different robust techniques exists in literature to detect robot failures and reallocate tasks between the remaining robots including the use of more precise GPS system like DGPS, and the use of active sensing techniques to update the coverage path in real time. Robustness is considered one of the challenging problems that need to be maintained in multi-robot systems to allow the rest of the team adapt to the new changes that occur to the system online. A lot of the work in literature implemented robustness in various ways as in [38], and  [25] where robot failure is handled in different ways.

  4. 4.

    Communication modality Most of the robotic systems have limited range of communication. For example, robots transmit messages to other robots within a specific distance from it. Also, based on the cooperation method used whether it’s a centralized, distributed or decentralized, the team of robots need to maintain communication especially if the team shares information. Most of the reviewed work assumes perfect communication and utilizes centralized type of cooperation as presented in [3, 20, 44, 70] which is subject to scalability, overhead and single point of failure problems. Some of the work presented a decentralized CPP approach for multi-robot systems as presented in [8, 52, 54, 70]. The type of cooperation and communication need to be defined for the team of robots based on the application and type of information that need to be shared and processed.

  5. 5.

    Adaptability One of the main properties that a team of robots need to have is the ability to change behavior over time and react to changes in the environment in order to prevent unnecessary degradation in performance or improve the performance. Dynamic environment characterized by the presence of dynamic obstacles as in [52, 68, 84] or by the possibility of change in shape or size as in [16, 43, 46, 50] should be reacted to accordingly in a manner that still achieves the desired CPP performance. This aspect is significant in applications that involves changes in the natural environment such as fire fighting more than a static structure.

  6. 6.

    Open systems The ability of the multi-robot system to adapt to a new joining robot describes the openness feature of the system. In most CPP applications, this aspect was not mentioned although it is an important property in the multi-robot systems especially if complex large environments and structures need coverage. Adding a new robot to the team will support and enhance the efficiency of the team.

  7. 7.

    Collective intelligence generating collaborative policy for the team of robots to achieve one goal could enhance the performance of the CPP. The policy could be generated by training the agents on a set of actions or types of data which will accelerate the CPP process. Collaborative manipulation and multi-agent path planning are another two subproblems where machine learning could be used. Recent work utilized different types of machine learning such as Reinforcement learning are presented in [2, 6, 31, 43, 71, 81].

5 Conclusion

In this paper, we surveyed the various literature work related to the Coverage Path Planning (CPP) using multi-robot systems. The major components of CPP were identified and discussed. The viewpoints generation is classified based on the used exploration method into model-based and non-model based approaches. The model-based approach have deterministic characteristics, by which it utilizes the reference model of the structure or region of interest provided priori. This knowledge is used in the coverage path planning to generate a path that encapsulates a set of viewpoints that provide the maximum coverage for reconstruction and mapping. The non-model based approach is considered of randomized characteristics since it does not use priori knowledge about the structure or region and evaluates a set of candidate views based on the coverage and information gain. The non-model based approach performs a cycle of online iterative steps including: candidate viewpoints generation, viewpoints evaluation and path planning, path execution and scanning, and performing reconstruction. The CPP algorithms are further classified based on the path planning approach into grid based search methods, reward based methods, geometric methods, NBV methods, and incremental random planners. In general, performing CPP using multi-robot systems requires defining the viewpoints generation approach, path planning method, communication and task allocation method, and mapping technique. The main aim of using multi-robot systems in CPP applications is to reduce the coverage effort and distribute it among the team of robots in order to provide full high quality reconstructions and maps with the minimum energy and time.

Based on the surveyed papers, the main future application domains of multi-robot CPP include search and rescue, inspection, and agriculture. The main future research trends in this topic include heterogeneity, prioritization and robustness techniques, communication modality, system openness and adaptability, and collective intelligence.