Next Article in Journal
Sensitivity Analysis of Unmanned Aerial Vehicle Composite Wing Structural Model Regarding Material Properties and Laminate Configuration
Previous Article in Journal
NoctuDroneNet: Real-Time Semantic Segmentation of Nighttime UAV Imagery in Complex Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Efficient Coverage Path Planning for a Drone in an Urban Environment

1
The Andrew and Erna Viterbi Faculty of Electrical and Computer Engineering, Haifa 3200003, Israel
2
The Faculty of Computer Science, Technion Israel Institute of Technology, Haifa 3200003, Israel
*
Author to whom correspondence should be addressed.
Drones 2025, 9(2), 98; https://doi.org/10.3390/drones9020098
Submission received: 4 December 2024 / Revised: 13 January 2025 / Accepted: 22 January 2025 / Published: 27 January 2025

Abstract

:
Multirotor drones play an increasingly significant role in smart cities and are among the most widely discussed emerging technologies. They are expected to support various applications such as package delivery, data collection, traffic policing, surveillance, and medicine. As part of their services, future drones should be able to solve the last-mile challenge and land safely in urban areas. This paper addresses the path planning task for an autonomous drone searching for a landing place in an urban environment. Our algorithm uses a novel multi-resolution probabilistic approach in which visual information is collected by the drone at decreasing altitudes. As part of the exploration task, we present the Global Path Planning (GPP) problem, which uses probabilistic information and the camera’s field of view to plan safe trajectories that will maximize the search success by covering areas with high potential for proper landing while avoiding no-fly zones and complying with time constraints. The GPP problem is formulated as a minimization problem and then is shown to be NP-hard. As a baseline, we develop an approximation algorithm based on an exhaustive search, and then we devise a more complex yet efficient heuristic algorithm to solve the problem. Finally, we evaluate the algorithms’ performance using simulation experiments. Simulation results obtained from various scenarios show that the proposed heuristic algorithm significantly reduces computation time while keeping coverage performance close to the baseline. To the best of our knowledge, this is the first work referring to a multi-resolution approach to such search missions; further, in particular, the GPP problem has not been addressed previously.

1. Introduction

Unmanned aerial vehicles, sometimes generically called drones, are becoming increasingly popular to provide mobility solutions for congested smart cities [1,2]. Equipped with a wide range of sensors and real-time processing capabilities, drones combine the key principles of technological modernity: data processing, networking, autonomy, and mobility. In smart city environments, drones are called to play a major role in a variety of applications, including package delivery [3,4], data collection [5], traffic policing [6], surveillance [7], Search and Rescue (SAR) operations [8,9,10], and even as transportation devices [11]. The integration of drones into densely populated areas presents many challenges due to safety, security, and privacy considerations. This is especially true when considering autonomous operations with little or no human intervention.
To fulfill their intended purposes, drones must be provided with the ability to explore complex urban environments and search for mission-dependent targets. Motivated by this fact, [12] recently considered a multi-resolution probabilistic approach for searching for a landing site in an urban environment by maintaining a probability map quantifying the probability of different areas being suitable for landing. Note that in that paper, as well as in the current one, "multi-resolution” refers to the fact that information is gathered from different altitudes, giving increased spatial resolution when flying at lower altitudes. This is not to be confused with other usages of multiple-resolution, such as image processing tools (e.g., a pyramid parametrization) or employing a sequence of images as in super-resolution. These probabilities are updated based on images taken from a downward-looking camera and by re-visiting certain areas from different viewpoints. In order to do this efficiently, a trajectory planning scheme is required that selects which areas should be re-visited and then computes an efficient and safe trajectory.
In this work, we address the trajectory planning problem outlined above. Following [13], we propose a solution for the Global Path Planning (GPP) problem that aims to plan safe trajectories to explore an area at a constant altitude. Due to time and energy constraints, the trajectories are necessarily limited in length and must cover areas with a high probability of being appropriate for landing.
The remainder of this paper is organized as follows: Section 2 reviews existing work regarding well-known coverage path planning algorithms and related computational geometry problems. The formulation of the GPP problem is provided in Section 3. Section 4 presents a baseline algorithm for the GPP problem based on an exhaustive search. Section 5 introduces SST—an efficient heuristic algorithm for the GPP problem. Performance results are reported in Section 6, and Section 7 concludes the paper.

2. Related Work

The GPP problem studied in this work is related to a wide range of studies in the literature spread across several fields, from computational geometry problems to coverage and optimal trajectory planning. Indeed, the problem can be considered a variation of area coverage, initially formulated by [14] and extensively studied since then. Coverage Path Planning (CPP) can be formulated as follows: given a specified region in 2D or 3D, plan a trajectory for one or multiple robots such that every point in the region is visited while avoiding obstacles. Applications of the CPP problem are numerous and include part painting in the automobile industry, guaranteeing full floor cleaning or grass cutting, and finding people in distress in emergency areas. The survey provided by [15] provides a good introduction and pointers to the literature.
In a typical CPP formulation, the area to be visited is divided into two sub-regions: the Area of Interest (AOI) and obstacles. The AOI is sometimes divided into smaller cells, and each cell may have a deterministic or probabilistic value attached to it. Probabilistic values may help establish an order in which the cells are to be visited and are commonly used when performing search tasks. For instance, Refs. [9] and [16] calculate a discrete path for a drone by using probability maps where each cell represents the potential risk/occupancy degree. In particular, [16] develops a greedy algorithm that uses clustering to accumulate maximum probabilities and is limited by the maximum allowed length.
Another extensive survey [17] specifically considers the coverage problem using drones. Although the land and air versions of the problem are strongly related, planning a coverage path for a drone includes some additional features, including the limited endurance of the platform, its maneuverability limitations, restricted payload, obstacles that may cause occlusions, and other similar issues. The survey revises different CPP approaches, from simple geometric flight patterns for non-complex AOI to more complex grid-based solutions considering full and partial information about the AOI.
The use of drones for coverage tasks requires considering their mounted camera properties, which can only capture points with a cone-shaped Field of View (FOV). The FOV of the camera can be further reduced by obstacles like buildings and walls. To achieve complete coverage of the AOI, each point must be mapped onto the image plane at least once in a complete trajectory. This was considered, for instance, in [7,18], which introduce two-step trajectory planning algorithms for coverage missions of geometrically complex environments that consider camera sensing constraints. First, they find a set of waypoints from which the AOI can be covered fully; then, they plan a smooth trajectory along these waypoints such that the completion time is minimal. In [19], a flight path planning algorithm is proposed to find collision-free, minimum-length paths for drones’ coverage missions. The authors use a footprints’ sweeps fitting method to address this problem, considering the camera footprint as a coverage unit.
In drone coverage missions, the AOI is sometimes partitioned using a grid where the camera footprint determines the size of each cell [20]. As a result, the drone can observe an entire cell when located at its geometrical center, and the area is said to be fully covered when it visits the centers of all cells.
The GPP problem discussed in this paper consists of finding a safe path covering an AOI while meeting a time constraint—i.e., the path length is limited. As a result, it is not possible to scan the entire AOI but to choose which sub-areas have a high priority for scanning. In the case described in [5,21], a drone needs to visit several spatially distributed Points of Interest (POIs) to maximize the information collected subject to energy constraints. Similarly, [8] suggests an efficient localization solution for SAR missions. For this case, given a map indicating the importance level of each area, the planning algorithm should determine strategic waypoints at which the UAV hovers and collects data while an efficient trajectory composed of all waypoints is generated using a solution to the Traveling Salesman Problem (TSP).
The tasks of selecting a set of waypoints and optimal routing between these points are dealt with in familiar computational geometry problems. The art gallery problem [22] considers a polygonal gallery where a minimum number of guards are to be positioned such that at least one guard can see every point in the gallery; the watchman route problem [23] seeks the shortest route a watchman should take so that every point in a given space can be seen from at least one point along the route; the orienteering problem [24] aims to construct a path through a set of nodes that maximizes the total score and does not exceed a given budget; and probably the most famous one, the TSP [25]—all these problems have been proven to be NP-hard and are often solved by approximation algorithms.
One heuristic method commonly used for solving the optimization problems mentioned above is local search [26]. In a typical local search algorithm, an initial solution is first constructed, for instance, by a greedy algorithm. Then, in an iterative manner, the initial solution is modified by local operations, with a slight improvement in each iteration. Ref. [27] presents a random mixed local search method for finding an optimal solution for the Open-Loop Traveling Salesman Problem (OLTSP). Starting with some initial trajectory, the algorithm improves this method (in terms of length) by mixing in local search operators (NodeSwap, 2opt, LinkSwap).
Most of the approaches mentioned above use offline solutions computed before the mission is actually executed. Therefore, computing time is of secondary importance and is usually not a measure of the algorithm’s quality. In the case considered in this study, computation time is a significant factor. During the mission of autonomous landing, it is necessary to find a trajectory at decreasing altitudes—i.e., the GPP problem is to be solved several times in a short period. Therefore, in addition to the requirement of finding a near-optimal solution, we aim to develop an algorithm that is also efficient in terms of computation time.

3. System Model and Problem Definition

In this section, the system model and the GPP problem are introduced. The GPP problem is then formulated as an optimization problem and shown to be NP-hard.

3.1. System Model

Consider the problem of finding a landing site for a drone in an urban region A . The region A is assumed to be a plane partially occupied by structures, including buildings, traffic lights, billboards, vegetation, and similar obstacles typical of built environments. The drone, equipped with a downward-looking camera, explores the region A by following a trajectory that lies on the plane π h parallel to A at a constant altitude h. The region π h is divided into two complementary sub-regions π h = π f h π o h , where the former is the area where the drone is permitted to fly safely and securely while the latter is a no-fly zone (NFZ), i.e., an area where the drone cannot fly due to obstacles or regulations.
Throughout the flight, subsets of A are projected onto the camera image plane. Let I k = I ( w k ) and F k A denote the image taken by the camera at the waypoint w k π f h and the corresponding footprint on A . The image taken at waypoint w k will be such that its center lies at the intersection between the camera’s line of sight and the image plane. As illustrated in Figure 1, the size of the camera footprint F k is a function of the drone altitude and the FOV of the camera. The dimensions of the footprint can be calculated using the following:
L 1 = 2 · h · tan ( H F O V 2 ) L 2 = 2 · h · tan ( V F O V 2 ) r f p = min ( L 1 , L 2 ) / 2
In order to guarantee a safe landing place, A can be discretized into M × N identical grid cells c m n such that c m n = A . As shown in Figure 2, the cell dimensions are derived from the size of the body and propellers of the drone together with the flying conditions (e.g., wind). This partition is in line with discrete search theory (see, e.g., [28]) but with a different motivation.
Following this, a probability p m n , with 0 p m n 1 , is attached to each cell c m n , resulting in a probability map modeling the likelihood that each cell is suitable for landing. Then, the idea is to re-explore cells with a relatively high probability and update their values. As the level of certainty increases, the probabilities are likely to approach ‘1’ or ‘0’ until one or more probabilities exceed a certain threshold, making it possible to determine that the corresponding cell is suitable for landing. See [12] for a detailed discussion.

3.2. Initialization

The information available prior to the beginning of the landing mission is a Digital Surface Model (DSM) of the explored area, from which the locations of the obstacles at any height can be extracted. The obstacles are approximated by polygons, and their vertices are given in the world coordinate system.
According to the DSM, an initial probability map is built. As no additional information is available, the values in this probability map are ‘0’ for cells that belong to obstacles and ‘0.5’ otherwise, meaning that, at first, all cells in the free area are equal candidates for a landing site.

3.3. Global Path Planning Problem

The objective of the GPP problem is to find a safe trajectory that begins at an initial position w 0 and covers areas with a high potential of being a proper landing site. As the drone has limited energy and performs the trajectory in an urban area, the planned trajectory must comply with a time-of-flight constraint and avoid NFZ.
For a given image footprint F k , let the set of pairs of indices J k be
J k = { ( m , n ) s . t . c m n F k }
Also, given 0 < p ̲ 1 , let Γ p ̲ be the following set of pairs of indices:
Γ ( p ̲ ) = { ( m , n ) s . t . p m n p ̲ }
With this definition, we can treat p ̲ as a threshold value that separates the cells of interest from the remaining cells.
Definition 1.
The set of waypoints W h = { w 0 , w 1 , . . . , w k } , w i π h is said to be a p ̲ -Coverage (note that this definition is different from the one in [29] for k-coverage—the latter ensures each cell is covered by at least k covers) at altitude h if for all ( m , n ) Γ ( p ̲ ) there exists at least one w i such that c m n F i .
In general, a footprint contains numerous cells; therefore, p ̲ -Coverage sets are far from unique, and two different ones may have a different number of elements.
Definition 2.
A trajectory passing through  W h  is a continuous map T : [ t 0 , t e n d ] π h such that T ( 0 ) = w 0 and there exists a set of time instants { t i } i = 1 , · , k such that T ( t i ) = w i , w i W h . The trajectory is said to be p ̲ -covering if W h is a p ̲ -Coverage.
In the following, T will simply be referred to as a trajectory, since W h will be clear from the context. Note that the set of time instants in the definition is, in general, not ordered—namely, i < j t i < t j .
Definition 3.
A cell c m n is said to be visited by a trajectory T if c m n F k for some k.
Definition 4.
A trajectory is said to be safe if T ( t ) π f h for all t [ t 0 , t e n d ] .
As a standard when introducing new planning algorithms, no dynamic constraints are placed in the definition of feasible trajectories.

3.4. Exact Formulation

Define a cost function τ ( · ) over all safe trajectories T. The cost function measures a property of the trajectory that one would like to control. For definiteness, a total traveling time constraint is assumed here; hence, let τ m a x be the maximal time-of-flight allowed for the trajectory.
With these definitions, the GPP can be translated into the problem of finding the minimum value of p such that there exists a safe, p-covering trajectory for which τ ( T ) = t e n d t 0 τ m a x :
min p s . t .   f o r   s o m e   T τ ( T ) τ m a x ( m , n ) Γ ( p ) : c m , n F ( T ) T π f
The first constraint guarantees that the desired cost is not violated. For a given p, the second constraint requires T to be p-covering. Finally, the third constraint promises the safeness of T.
Notice that for p ̲ 1 , the p ̲ -coverage set W h will be relatively small, and hence, one would expect to meet the upper bound τ m a x of the cost function. As p ̲ gets smaller, the number of cells to be visited increases, and so eventually, the upper bound might not be met by any feasible trajectory. The problem, therefore, captures the desirable property of visiting as many cells as possible while concentrating on the higher probability ones.
Theorem 1.
GPP is an NP-hard problem.
Proof. 
To prove the NP-hardness of the problem, we use a known NP-hard problem, the Orienteering Problem (OP) [30], and reduce it to the GPP problem in a polynomial time. The OP is formulated as follows. Given n nodes in the Euclidean plane [ v 1 , . . , v i , . . , v n ] , each with a score s ( i ) 0 , find a route of maximum score through these nodes beginning at v 1 and ending at v n of length no greater than T M A X .
Consider an instance P of the OP. We reduce it to a GPP problem by the following operations.
  • Place the nodes on a grid such that a single cell does not contain more than one node.
  • Convert the scores to probabilities by normalizing them.
  • Generate a probability map M out of the grid by assigning the score values to cells containing nodes and 0 otherwise.
  • To ensure the selection of v N and its position at the end of the path, set p ( v N ) = and d i s t ( v N , v i ) = i .
  • Set the required initial waypoint as v 1 .
Define P as a GPP problem with a probability map M , initial position v 1 , and time constraint T M A X . With the assumption of a single-cell size footprint, the minimization of p in P is equivalent to the maximization of the total score in P . □
The optimization problem considered above provides a mathematical formulation of the GPP problem. In Section 4 and Section 5, two alternative approaches for solving the GPP problem that trade the simplicity of exhaustive search with a more complex and efficient algorithm will be discussed.

4. Baseline Algorithm

As GPP is a new problem, we have first developed a solution based on an exhaustive search to serve as a baseline. A naive approach for finding the optimal probability threshold p ̲ for the GPP problem presented in Equation (4) is to list all possible candidates for the solution and check whether each meets the problem’s requirements. This approach results in a factorial algorithm that is, in principle, computationally infeasible for large problems.
As stated before, the value of p ̲ and the size of the p ̲ -coverage set W h are inversely proportional. For instance, assume a specific probability threshold p ̲ = p 0 and define the corresponding p 0 -covering trajectory T p 0 . In case T p 0 violates the cost constraint, then the minimum p ̲ cannot be lower than p 0 . Alternatively, if T p 0 complies with the constraints, it is certain that the minimum p ̲ is lower than or equal to p 0 . Referring to this behavior, a binary search is appropriate for finding the optimal solution.
The Exhaustive Search (ES) algorithm, initially developed, iteratively searches for the minimum probability threshold for which the constraints are met. In each iteration, p ̲ is fixed, and a corresponding p ̲ -covering trajectory is found. Then, p ̲ is updated according to whether the found trajectory complies with the constraints until convergence. A detailed description is provided in Algorithm 1.
The inputs to the algorithm are a probability map and obstacle locations corresponding to the region A at flight altitude h, the required first waypoint, and mission constraints. The output of the algorithm is a trajectory covering a sub-area of A at a constant altitude that avoids obstacles and meets the time constraints of the mission.
First, a visibility graph [31] is built based on the known obstacle locations. The visibility graph allows for finding collision-free optimal paths between points in the free area π f . It is used as an auxiliary graph at a later stage when it is desirable to present the connectivity between waypoints. The visibility graph can be built efficiently using, e.g., the Plane Sweep algorithm in [32].
To determine the search boundaries, two variables m i n and m a x are initialized with the minimum and the maximum probabilities found in P . The iterative part begins with calculating the threshold p ̲ as the middle of the search boundaries. Considering the probability map, obstacle locations, and the required first waypoint, a corresponding trajectory T p ̲ is then found. Starting at w 0 , the planned trajectory is p ̲ -covering and safe. In case τ T p ̲ τ m a x , T p ̲ T since it meets all the constraints and corresponds to the minimal threshold found so far. Finally, the search range is narrowed according to the previous comparison: the upper boundary m a x is reduced to p ̲ in case the constraints are met, or the lower boundary m i n is enlarged to p ̲ if the opposite is true. The search continues until the search interval, i.e., the difference between m a x and m i n , is less than some ϵ .
Algorithm 1: Exhaustive Search
Input: Probability map P , obstacle locations O , first waypoint w 0 , mission constraints τ m a x
Output:Trajectory T
1:
VG = buildVisibilityGraph( O )
2:
m i n , m a x min_prob( P ), max_prob( P ) initialization
3:
d i f f m a x m i n
4:
while diff ε  do
5:
    p ̲ updateThreshold ( m i n , m a x )
6:
    T p ̲ planTrajectory( P , VG , w 0 , p ̲ )
7:
   if  τ ( T p ̲ ) τ m a x  then
8:
      T T p ̲
9:
      m a x p ̲ {continue the search in the lower half of the range}
10:
  else
11:
      m i n p ̲ {continue the search in the upper half of the range}
12:
  end if
13:
   d i f f m a x m i n
14:
end while
15:
return T
Inspired by [7,8], the process of planning a p ̲ -covering trajectory presented in Algorithm 2 consists of two main parts: waypoint selection and efficient waypoint arrangement. See Figure 3 for a graphical representation. For a given threshold p ̲ , the POIs are described by the set Γ ( p ̲ ) . As Equation (2) states, multiple cells are included in the camera footprint when passing through a single waypoint. It is then possible to find a minimum set of strategic waypoints W h , which is p ̲ -covering and guarantees complete and effective coverage of all the POIs. For this purpose, the POIs are clustered such that the size of each cluster does not exceed the camera footprint size. The set W h is then built by collecting the centers of the clusters so that visiting all w k W h guarantees p ̲ -coverage. Among the different clustering methods examined, the single-pass algorithm described in [33] proved to be the fastest.
Algorithm 2: planTrajectory
Input: Probability map P , visibility graph VG , first waypoint w 0 , threshold p ̲
Output: Trajectory T p ̲
1:
P O I applyThreshold( P , p ̲ )
2:
W h ClusterPOI( P O I )
3:
W h .add( w 0 )
4:
G buildeGraph( W h , VG )
5:
T p ̲ solveOLTSP(G, I, R)
6:
return  T p ̲
To construct an efficient path that visits all the waypoints, a complete graph G with vertices W h is built, with the shortest path lengths as its weights. The visibility graph guarantees that the shortest path between each pair of waypoints is collision-free. Based on the complete graph, the visiting order is determined by solving an OLTSP in which the goal is to find the shortest path that visits each waypoint exactly once without returning to the starting position. In particular, the near-optimal algorithm presented in [27] is used with the nearest-neighbor (NN) algorithm [25] as an initialization heuristic. The algorithm is based on local-search operations with two input parameters: the number of iterations I and the number of repetitions R.
The resulting algorithm generates a trajectory that complies with the entire set of constraints and corresponds to the smallest feasible probability threshold.

5. SST—An Efficient Heuristic Algorithm for the GPP Problem

The ES algorithm is memory-less in the sense that it finds a trajectory each time it is called without taking advantage of the fact that the planned trajectories for different altitudes are not entirely uncorrelated. As a result, time-consuming operations are performed repeatedly, resulting in long computation times. This section presents a heuristic algorithm that exploits the mission properties to reduce the computation times while maintaining good performance.

5.1. Overview

Together with being safe and complying with time constraints, the planned trajectory has to maximize the relevant information collected while following that information, allowing better decision-making regarding which landing spot to select. Since any point in the free area π f is an appropriate candidate for a trajectory waypoint, selecting a subset of waypoints that maximizes the information among infinitely many possibilities is a great challenge.
To tackle this problem, a pre-processing stage has been added with the aim of finding a finite, narrow set of candidate waypoints V that will serve the task of trajectory planning throughout the entire mission. Considering this set of candidate waypoints, the planning stage includes three main steps: Score–Select–Traverse (SST).
  • Score—Assign each candidate waypoint a score that represents some measure of its corresponding footprint.
  • Select—Select a subset of waypoints to form the trajectory.
  • Traverse—Determine the visiting order to minimize travel time.
The detailed algorithms for the pre-processing and planning stages are presented in Algorithms 3 and 4, respectively, and further discussed in the following sections.
Algorithm 3: SST—Pre-Processing
Input: A preliminary probability map P , the minimum flying altitude h m i n , obstacle locations in h m i n O h m i n
Output: A set of candidate waypoints V , a visibility graph VG
1:
P O I extractPOI( P , O h m i n )
2:
b a n d w i d t h calcFootprintSize( h m i n )
3:
V ClusterPOI( P O I , b a n d w i d t h )
4:
VG PlaneSweep( O h m i n )
5:
return  V , VG
Algorithm 4: SST—Planning
Input: A probability map P , first waypoint w 0 , mission constraints τ m a x , visibility graph VG
Output: A trajectory T
1:
G h scoreAndSelect( P , w 0 , τ m a x , VG )
2:
v i s i t _ o r d e r solveOLTSP( G h , I, R)
3:
T post_processing( v i s i t _ o r d e r )
4:
return T

5.2. Candidate Waypoint Set— V

As part of the planning process (SST), the second step is to select the set of waypoints W h V that will form the trajectory in order to ensure that it visits high-probability areas. In the absence of any preliminary operations, the search space is very large since any point included in the map boundaries and within the free space is valid.
In order to reduce computation times for the planning stage, the search space is narrowed down to a set of candidate waypoints V that are found in a pre-processing stage. This set of points is created by dividing the free space into clusters such that the area of each cluster is fully covered by the footprint of the drone when hovering above its center. As opposed to the ES algorithm, this time, the entire free space is clustered, regardless of the probability values. Moreover, the clustering operation occurs only once, and the footprint size considered is the one obtained at the lowest flight altitude as it increases with height. The set of candidate waypoints V is the collection of all cluster centers. With this set of waypoints as a baseline, any point in the free space can be covered by the drone footprint at any height by simply selecting the cluster center closest to that point of interest:
c m , n A , v V : c m , n F ( v )

5.3. Pre-Processing Stage

The pre-processing stage is described in Algorithm 3. This part of the solution is performed once, before the beginning of the mission, and the preliminary probability map, the value of the lowest flight altitude, and a list of obstacle vertices at this altitude are received as inputs.
To determine the smallest area the drone could cover in a single time instant during flight, its footprint size is calculated at the lowest flight altitude; see Figure 1a and Equation (1). As the orientation of the drone is unknown at the early stages of planning, the circle inscribed in the rectangle image is considered its footprint.
The set of points of interest P O I is extracted using the probability map and obstacle locations. It contains all cell coordinates in the map boundaries with a probability larger than zero and within the free space π f . P O I is then clustered with a bandwidth of r f p —the drone footprint size. The collection of all clusters’ centers creates the set of candidate waypoints V that are used as a baseline for the planning stage.
In addition to the set V , a visibility-graph VG is built as part of the pre-processing stage corresponding to the obstacles of the lowest altitude. Based on the assumption that obstacles at all altitudes are contained within obstacles at the lowest altitude, the visibility graph represents safe flight routes at all altitudes.
Note: To enable the drone to safely travel the free space while avoiding obstacles, the obstacle locations given as input are first edited such that an offset is added to each of the obstacles. This allows the drone to be treated as a point vehicle while planning the trajectory.

5.4. Planning Stage

The planning stage of the suggested SST algorithm is presented in Algorithms 4–6, as well as in Figure 4, as follows:
Algorithm 5: scoreAndSelect
Input: A probability map P , first waypoint w 0 , mission constraints τ m a x , visibility graph VG
Output: A graph G h
1:
scoreAndSort( V , P , O )
2:
VG .addVertex( w 0 )
3:
G h .addVertex( w 0 )
4:
W h w 0
5:
τ c u r r = 0 estimated time to perform current trajectory
6:
o p e n _ l i s t V
7:
while  o p e n _ l i s t Ø  do
8:
    τ r e m a i n = τ m a x τ c u r r
9:
    v * chooseNextVertex( W h , o p e n _ l i s t , r f p , τ r e m a i n )
10:
    t e m p _ G h copy( G h )
11:
    t e m p _ G h .addVertex( v * )
12:
    τ e s t i m a t e d estimatePathLength( t e m p _ G h )
13:
   if  τ e s t i m a t e d τ m a x  then
14:
      W h W h v *
15:
      G h t e m p _ G h
16:
      τ c u r r τ e s t i m a t e d
17:
   end if
18:
    o p e n _ l i s t .remove( v * )
19:
   if  W h covers entire free area π f or τ c u r r = = τ m a x  then
20:
     return  G h
21:
   end if
22:
end while
23:
return  G h
Algorithm 6: chooseNextVertex
Input:  o p e n _ l i s t sorted by scores, footprint size r f p , remaining time-of-flight τ r e m a i n
Output:  v *
1:
m a x _ d i s t τ r e m a i n · v e l o c i t y
2:
m i n _ d i s t 2 * r f p · o v e r l a p F a c t o r
3:
for v in o p e n _ l i s t  do
4:
    d i s t a n c e s E u c l i d e a n D i s t ( v , W h )
5:
    d i s t a n c e min ( d i s t a n c e s )
6:
   if  d i s t a n c e m i n _ d i s t  then
7:
     if  d i s t a n c e m a x _ d i s t  then
8:
        return v
9:
     end if
10:
 end if
11:
    o p e n _ l i s t .remove(v)
12:
end for
  • scoreAndSelect. The algorithm’s first aim is to select trajectory waypoints W h = ( w 1 , . . . , w K ) V that allow it to explore high-probability areas without exceeding the time-of-flight limit. Furthermore, to represent the connectivity between the selected waypoints, a graph G h is constructed with W h as its vertices and the shortest path lengths as its weights. This graph will later allow for establishing the shortest path visiting all selected waypoints. The procedure of selecting W h out of V and the construction of G h is presented in Algorithm.
    Each waypoint in V is assigned a score based on the probability map and the flight altitude, indicating the potential for finding a landing zone in its environment (Section 5.5.1). The candidate waypoints are then sorted according to their scores in decreasing order. The subset of waypoints W h V that will ultimately form the trajectory is chosen from V in an iterative manner. In each iteration, a waypoint v V is selected and added to a temporal copy of G h . An upper bound is then calculated for the length of the path visiting every vertex in the temporal graph, as described in Section 5.5.3. In case the path length meets the time constraint, the set W h and the graph G h are updated, as well as the value of τ c u r r presenting the current path length estimation. The process terminates in one of the following cases:
    • All candidate waypoints have been examined.
    • The waypoints in W h cover the entire free area π f .
    • The mission constraint has been met by τ c u r r .
    To determine the next waypoint v to add to W h (Algorithm 6), two parameters are considered:
    • min_dist is the minimal distance allowed between two waypoints to avoid redundancy in the data collected during the flight. Its value depends on the flight altitude (footprint size) and a parameter that defines how much overlap is allowed between footprints.
    • max_dist is the difference between the allowed trajectory length and the currently estimated trajectory length.
    v is the waypoint with the highest score that has not been examined yet where the following holds:
    m i n _ d i s t d i s t ( v ) m a x _ d i s t .
    Here, d i s t is defined as follows:
    d i s t ( v ) = min w W h d ( v , w )
    and d ( v , w ) is the Euclidean distance between the waypoints v and w.
    To build a complete graph with the shortest path lengths as its weights, adding a new vertex to the graph G h requires finding the shortest path from the new vertex to each of the existing vertices. To calculate these paths, the new vertex v is first connected to the visibility graph VG , where the shortest paths are found.
  • solveOLTSP. Given the graph G h , the final step of trajectory planning is to find the shortest path starting at w 0 and traversing all its vertices. This problem is an instance of the OLTSP and, similarly to the ES algorithm, is solved using a random mixed local search algorithm with NN as an initialization heuristic.
  • Post-Processing The local paths found during the construction of G h are optimal regarding the graph VG , i.e., according to the obstacles at the lowest altitude. Assuming obstacles at altitude h i are contained in the obstacles at h i + 1 where h i > h i + 1 , there might be redundant detours around obstacles that are not present at the current altitude. To avoid this, a post-processing procedure checks for possible shortcuts. Denote the waypoints in T that originated in W h as w k , k = 1 , . . , K . The trajectory must pass through these waypoints, which cannot be eliminated. Denote the rest of the waypoints in T as v q , q = 1 , . . . , Q . These waypoints are a part of the local paths, which are used to avoid obstacles and can be eliminated if a valid shortcut is found. A valid shortcut means eliminating a waypoint v q from T that ends with an edge connecting its adjacent waypoints in the free space π f . By editing the trajectory in this way, the safeness of T is not violated as well as the mission constraints, since the edges’ weights are the Euclidean distances and the triangle inequality holds.
It should be pointed out that the manner in which W h is constructed results in a set that does not necessarily fulfill Definition 1 and hence, cannot be determined as a p-coverage. However, it exhausts the mission constraints by covering as many cells as possible while prioritizing those with a high probability.

5.5. Heuristics and Methods

This section describes the heuristics used throughout the SST algorithm.

5.5.1. Scoring—The Information Gain

Given V as a baseline, planning a trajectory T at altitude h requires finding a subset W h V that includes the most informative waypoints for the drone to traverse. The scores attached to each candidate waypoint can be any heuristic representing its information gain. As an example, according to the probability map and flight altitude, the information gain of each point can be measured by the following two properties:
v V : m a x ( v ) = max { m , n } J ( v ) p m , n s u m ( v ) = { m , n } J ( v ) p m , n
By sorting the waypoints in V according to these properties in decreasing order (first by m a x ( · ) , then by s u m ( · ) ), the algorithm is able to choose as many waypoints as possible for W h while concentrating on those with the highest probabilities. In this manner, we will favor waypoints from which the highest probabilities can be observed, even if they are isolated, as required by the optimization problem (Equation (4)).

5.5.2. Euclidean Distance

In the presence of obstacles, the Euclidean distance is a lower bound for the length of the shortest path between two points v 1 , v 2 π f .
According to their scores, waypoints v V are added one by one to the subset W h . Prior to adding a waypoint to the subset W h , it has to meet two criteria regarding the distance from current members:
  • d i s t m i n _ d i s t —to avoid redundancy in the data collected during the flight.
  • d i s t m a x _ d i s t —as the trajectory length is restricted due to the time-of-flight constraint.
Calculating the Euclidean distance is an O ( 1 ) operation, as opposed to finding the shortest path, which requires O ( n 2 ) , where n is the number of vertices of the visibility graph VG (number of obstacle vertices). Therefore, for better performance, a heuristic based on the Euclidean distance is used to decide whether a waypoint should be further examined or not.

5.5.3. Nearest Neighbor

Nearest Neighbor Search (NNS), in the context of proximity search, is the process of finding the point in a set S that is closest to a given point q.
In this case, the NN algorithm is used both to determine an upper bound for the minimum length of a tour that visits all graph vertices and as a heuristic algorithm for OLTSP. Given the first waypoint, this algorithm chooses the nearest yet unvisited waypoint as its next move.
The time complexity of the NN algorithm is O ( n 2 ) , where n is the number of points to visit and the following is guaranteed [34]:
N N ( I ) O P T ( I ) 0.5 ( log 2 n + 1 )

6. Performance Evaluation

This section describes the experimental setting used to evaluate the performance of the proposed algorithm. Simulation results are presented to compare the baseline algorithm with variants of the SST algorithm. In addition, the impact of various parameters on the performance of the proposed algorithm is analyzed.

6.1. Experimental Setting

To develop and test the proposed algorithm, a simulation environment of a drone flying in an urban area was created using the AirSim simulator [35] built on Unreal Engine [36]. For a detailed description and visual examples of the simulator, the reader may refer to [12].
The algorithm performance analysis is based on a 3D Digital Surface Model (DSM) with an area of S = 1500 × 1500 [m2] generated by an AirSim simulation [12]. The DSM allows us to determine a priori the obstacle locations (e.g., buildings) within the 2D occupancy grid as a function of the drone’s altitude. The drone’s velocity was set to a constant value of 10 m s , and the image footprint was calculated for the down-facing camera with a FOV of 70 vertically and 50 horizontally. The flight altitude was set to 20 m, 40 m, 70 m, 100 m or 150 m, and the searching area was restricted to S , 1 2 S , 1 4 S , 1 8 S , or 1 16 S . The time constraint was set to 300 s as an estimation of the time required for a drone flying at 150 m to cover a 1000 × 1000 [m2] dense urban area, assuming 50 % of it was free space. It is worth mentioning that the suggested multi-resolution approach, with five iterations of 300 s each, requires 24 % less time than a single drone scan of the same area at 20 m.
All algorithms examined were implemented in Python and executed on a PC with a 3.0 GHz Intel Core i5 CPU (Intel Corporation, Santa Clara, CA, USA) and 8 GB RAM.

6.2. Compared Algorithms

As the GPP is a newly introduced problem, there are no algorithms available for comparison in the literature. For the examination of the suggested SST algorithm, we used the ES algorithm presented in Section 4 as a baseline. In addition, several variants of the suggested algorithm were examined, keeping the score–select–traverse structure. The variants differ in how V , the candidate waypoints set, is constructed:
  • SST—All Cells (AC)s V contains all the cells that belong to the free area.
  • SST—Cluster Every Call (CEC) V is determined at the planning stage by clustering the cells belonging to the free area according to the drone footprint size.
  • SST—K-Means Dilution (DIL—N) V is calculated as in the vanilla algorithm and is then diluted at the planning stage to a predefined size N by using the k-means algorithm [37].

6.3. Experimental Results

Seventy sub-areas of differing sizes were randomly selected from the search area to evaluate the algorithm’s performance. The scenarios described in Section 6.1 were tested at each flight altitude with a time constraint of τ m a x = 300 s. The probability maps were generated so that cells associated with obstacles were set to have probability zero, while the remaining cells’ probabilities were set by randomly positioning several Gaussian distributions over the search region so that their centers were randomized with a uniform distribution. Moreover, three internal parameters used by the algorithms were set as follows: I = 10 , 000 , R = 5 (Algorithms 2 and 4), and o v e r l a p p i n g F a c t o r = 0.375 (Algorithm 6). An example of a single instance solved by each of the seven considered algorithms is pictured in Figure 5.
The algorithm performance was measured using two metrics. The first one is coverage. As the optimization criterion (Equation (4)) describes, the goal is to maximize the covered area while concentrating on areas with high probabilities. In order to quantify the coverage obtained by each algorithm, a threshold p t h r e s h was applied to the input probability map, creating a discrete map DM ( p t h r e s h ) indicating the cells with probabilities greater than this threshold. Let VM ( T ) denote the visiting map, where cells covered by the planned trajectory are equal to 1, and 0 otherwise. The coverage of a trajectory T as a function of p t h r e s h is given by the following:
c o v e r a g e ( p t h r e s h ) = 1 { c m n VM ( T ) & c m n DM ( p t h r e s h ) } 1 { c m n DM ( p t h r e s h ) }
Results of the coverage performance are shown in Figure 6. As expected, the ES algorithm achieved the best results in terms of coverage. Its wide search space allowed positioning the trajectory waypoints such that high-probability areas were efficiently covered. Among the SST algorithms, the vanilla version produced the closest results to the ES algorithm. It can be seen that for high probabilities ( p t h r e s h 0.85 ), its average coverage ratio is similar to that achieved by ES, and as the threshold decreases, the gap grows up to 5 % for probabilities larger than 0.5 . SST-AC and SST-DIL-10,000 produced results close to SST, while SST-DIL-100 performed the worst.
The second aspect of performance is computation times. Since the GPP has to be solved several times during the mission of autonomous landing, it is crucial to keep computation times reasonable. A comparison of the average computation time of each tested algorithm is presented in Table 1. The average computation times of ES and SST-AC are the maximal obtained and are greater than one minute, which implies that these algorithms are not suitable for solving the problem discussed. For the SST variations with dilution, one can conclude that for small values of N, the dilution operation indeed decreases computation times (at the price of lower coverage); however, as N increases, it can cause an increase in computation times. Compared to ES, vanilla SST shows a 93 % reduction in average planning computation time.
In addition, we examined the impact of problem parameters on performance. The impact of the search area size was tested by varying its size from 1 16 M N to M N where M N = 1500 × 1500 [m2]. Ten probability maps were randomly generated and then trimmed to six different sizes for a total of 60 scenarios. All other parameters, including flight altitude, time constraint, initial waypoint, and obstacle locations, remained constant across all scenarios. Figure 7a shows that for ES and most SST algorithms, the computation time increases with area size. As the number of candidate waypoints is a function of the size of the free area, this is the expected result. However, for the SST variations with dilution (N = 100, 1000), the opposite is true—computation time decreases with the increase in area size. We can explain this result as follows: the dilution operation results in the candidate waypoints being farther apart in large areas compared to small areas, making it possible to include fewer waypoints in the trajectory for the same time (length) constraint. This affects the solution of OLTSP and decreases computation times. Figure 7b shows how the search area size affects the coverage performance. As expected, the coverage ratio decreases with the increase of area size since the area to be explored expands, whereas the time (length) constraint remains unchanged.
The second parameter examined was the number of obstacle vertices. For this purpose, we created a scenario including 15 obstacles randomly chosen from the original 1500 × 1500 [m2] search area, then iteratively added more obstacles, creating 13 areas with increasing number of obstacle vertices. For each search area, five different probability maps were generated for a total of 65 scenarios. In this case as well, all other parameters remained constant. Figure 8 depicts the impact of the number of obstacle vertices on the algorithms’ performance. For an increasing number of obstacle vertices, there is a moderate increase in both computation time and coverage ratio. The computation time is affected by the number of obstacles as it determines the number of vertices in the visibility graph VG and hence influences the performance of calculating the shortest path. However, the presence of obstacles can neither improve the coverage ratio—as they reduce the free space—nor worsen it, since in this case, they extend the way to cells with high probabilities.
Finally, Table 2 introduces how much each algorithm’s output trajectories exhausted the time constraint. As expected, the ES algorithm, which has the largest search space, produced trajectories that exhaust most of the time within the time limit provided. In addition to the smaller search space, there are two more reasons for the shorter trajectories produced by the SST algorithms. First, as discussed in Section 5.5.3, the upper bound given by the NN heuristic might be loose, causing early termination of the waypoints’ selection step. Secondly, the trajectory is planned according to obstacles at the lowest altitude and then is shortened using detours.

7. Conclusions and Future Work

This paper dealt with the global path planning problem that arises when considering the autonomous landing of a drone in a dense urban environment. From the overall problem formulation, searching for a landing site required planning collision-free trajectories, meeting time constraints, and performing almost real-time computations. During the planning process, a probability map of the area of interest was considered, containing the likelihood of each sub-area being suitable for landing. In addition, a DSM was used to identify obstacle locations.
We first formulated GPP as a minimization problem and showed that it belongs to the NP-hard computational geometry problem class. Then, we developed two computational algorithms: one based on exhaustive search and a family of approximating ones, generically called Score–Select–Traverse (SST). The first is easy to implement but involves a potentially exponential number of computations. The second includes a number of different variations and is the main contribution of this paper.
The algorithms in the SST family comprise two stages—pre-processing and planning. The pre-processing stage was created to perform time-consuming operations before the beginning of the mission, using only prior knowledge. The planning stage uses the information acquired throughout the search to reduce the area of interest.
The performance of the algorithms was compared using a simulation study. Not surprisingly, our experiments showed that some variations of the SST algorithm can significantly outperform the baseline heuristic in terms of computational times. Although being best in terms of coverage, ES and SST-AC were seen to be computationally expensive, making them unsuitable for almost real-time performance. On the other hand, the coverage performance of the vanilla SST algorithm was sufficiently close to that of ES, hence providing a good tradeoff between computation times and coverage.
Further work should probably be directed at deepening the way we dilute the set of candidate waypoints, in particular by considering using previously planned trajectories. To improve the exhaustion of time constraints, a fast-to-compute, tighter upper bound for the trajectory length should be developed. Lastly, since the proposed algorithm contains several parts that can be computed in parallel, the use of a GPU should be considered to reduce computation times in actual implementations.

Author Contributions

Conceptualization, J.S., B.P., E.R., and H.R.; methodology, J.S., B.P., E.R., and H.R.; software, J.S.; validation, J.S. and B.P.; formal analysis, J.S. and B.P.; investigation, J.S., B.P., and H.R.; resources, E.R.; data curation, J.S.; writing—original draft preparation, J.S., B.P., and H.R.; writing—review and editing, B.P. and H.R.; supervision, E.R. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Acknowledgments

We would like to thank Daniel Weihs, head of the Technion Autonomous System Program (TASP), for his continuous support.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Kellermann, R.; Biehle, T.; Fischer, L. Drones for parcel and passenger transportation: A literature review. Transp. Res. Interdiscip. Perspect. 2020, 4, 100088. [Google Scholar] [CrossRef]
  2. Khan, M.A.; Alvi, B.A.; Safi, E.A.; Khan, I.U. Drones for Good in Smart Cities: A Review. In Proceedings of the International Conference on Electrical, Electronics, Computers, Communication, Mechanical and Computing (EECCMC), Vaniyambadi, India, 28–29 January 2018. [Google Scholar]
  3. Choudhury, S.; Solovey, K.; Kochenderfer, M.J.; Pavone, M. Efficient Large-Scale Multi-Drone Delivery using Transit Networks. J. Artif. Intell. Res. 2021, 70, 757–788. [Google Scholar] [CrossRef]
  4. Dorling, K.; Heinrichs, J.; Messier, G.G.; Magierowski, S. Vehicle Routing Problems for Drone Delivery. IEEE Trans. Syst. Man Cybern. Syst. 2017, 47, 70–85. [Google Scholar] [CrossRef]
  5. Chen, M.; Liang, W.; Das, S.K. Data Collection Utility Maximization in Wireless Sensor Networks via Efficient Determination of UAV Hovering Locations. In Proceedings of the 2021 IEEE International Conference on Pervasive Computing and Communications (PerCom), Kassel, Germany, 22–26 March 2021; Voume 3, pp. 1–10. [Google Scholar] [CrossRef]
  6. Beg, A.; Qureshi, A.R.; Sheltami, T.; Yasar, A. UAV-enabled intelligent traffic policing and emergency response handling system for the smart city. Pers. Ubiquitous Comput. 2021, 25, 33–50. [Google Scholar] [CrossRef]
  7. Zhang, J. Occlusion-aware UAV Path Planning for Reconnaissance and Surveillance in Complex Environments. In Proceedings of the 2019 IEEE International Conference on Robotics and Biomimetics (ROBIO), Dali, China, 6–8 December 2019; pp. 1435–1440. [Google Scholar] [CrossRef]
  8. Demiane, F.; Sharafeddine, S.; Farhat, O. An optimized UAV trajectory planning for localization in disaster scenarios. Comput. Netw. 2020, 179, 107378. [Google Scholar] [CrossRef]
  9. San Juan, V.; Santos, M.; Andújar, J.M. Intelligent UAV Map Generation and Discrete Path Planning for Search and Rescue Operations. Complexity 2018, 2018, 1–17. [Google Scholar] [CrossRef]
  10. Mittal, M.; Mohan, R.; Burgard, W.; Valada, A. Vision-Based Autonomous UAV Navigation and Landing for Urban Search and Rescue. arXiv 2019, arXiv:1906.01304. [Google Scholar]
  11. Choi, J.S.; Hwang, H.W. A study on the development status and economic impacts of drone taxis. J. Korean Soc. Aviat. Aeronaut. 2020, 28, 132–140. [Google Scholar] [CrossRef]
  12. Pinkovich, B.; Matalon, B.; Rivlin, E.; Rotstein, H. Finding a Landing Site in an Urban Area: A Multi-Resolution Probabilistic Approach. Sensors 2022, 22, 9807. [Google Scholar] [CrossRef]
  13. Rösmann, C.; Hoffmann, F.; Bertram, T. Integrated online trajectory planning and optimization in distinctive topologies. Robot. Auton. Syst. 2017, 88, 142–153. [Google Scholar] [CrossRef]
  14. Zelinsky, A.; Jarvis, R.A.; Byrne, J.C.; Yuta, S. Planning Paths of Complete Coverage of an Unstructured Environment by a Mobile Robot. In Proceedings of the International Conference on Advanced Robotics, Yokohama, Japan, 26–30 July 1993; Volume 13, pp. 533–538. [Google Scholar]
  15. Galceran, E.; Carreras, M. A survey on coverage path planning for robotics. Robot. Auton. Syst. 2013, 61, 1258–1276. [Google Scholar] [CrossRef]
  16. Fedorov, A. Path planning for UAV search using growing area algorithm and clustering. In Proceedings of the Fourth Conference on Software Engineering and Information Management (SEIM-2019) (Full Papers), Saint Petersburg, Russia, 13 April 2019; p. 20. [Google Scholar]
  17. Cabreira, T.; Brisolara, L.; Ferreira, P.R., Jr. Survey on Coverage Path Planning with Unmanned Aerial Vehicles. Drones 2019, 3, 4. [Google Scholar] [CrossRef]
  18. Jakob, M.; Semsch, E.; Pavlícek, D.; Pˇechoucek, M. Occlusion-aware multi-uav surveillance of multiple urban areas. In Proceedings of the 6th Workshop on Agents in Traffic and Transportation (ATT 2010), Toronto, ON, Canada, 11 May 2010; pp. 59–66. [Google Scholar]
  19. Majeed, A.; Lee, S. A New Coverage Flight Path Planning Algorithm Based on Footprint Sweep Fitting for Unmanned Aerial Vehicle Navigation in Urban Environments. Appl. Sci. 2019, 9, 1470. [Google Scholar] [CrossRef]
  20. Ochoa, C.A.; Atkins, E.M. Fail-Safe Navigation for Autonomous Urban Multicopter Flight. In Proceedings of the AIAA Information Systems-AIAA Infotech @ Aerospace, Reston, VA, USA, 9–13 January 2017; p. 0222. [Google Scholar] [CrossRef]
  21. Liang, Y.; Xu, W.; Liang, W.; Peng, J.; Jia, X.; Zhou, Y.; Duan, L. Nonredundant Information Collection in Rescue Applications via an Energy-Constrained UAV. IEEE Internet Things J. 2019, 6, 2945–2958. [Google Scholar] [CrossRef]
  22. Savkin, A.; Huang, H. Proactive Deployment of Aerial Drones for Coverage over Very Uneven Terrains: A Version of the 3D Art Gallery Problem. Sensors 2019, 19, 1438. [Google Scholar] [CrossRef]
  23. Seiref, S.; Jaffey, T.; Lopatin, M.; Felner, A. Solving the Watchman Route Problem on a Grid with Heuristic Search. In Proceedings of the International Conference on Automated Planning and Scheduling, Nancy, France, 26–30 October 2020; Volume 30, pp. 249–257. [Google Scholar]
  24. Gunawan, A.; Lau, H.C.; Vansteenwegen, P. Orienteering Problem: A survey of recent variants, solution approaches and applications. Eur. J. Oper. Res. 2016, 255, 315–332. [Google Scholar] [CrossRef]
  25. Johnson, D.S.; Mcgeoch, L.A. The Traveling Salesman Problem: A Case Study. Local Search Comb. Optim. 1997, 1, 215–310. [Google Scholar] [CrossRef]
  26. Johnson, D.S.; Papadimitriou, C.H. How Easy Is Local Search? J. Comput. Syst. Sci. 1988, 37, 79–100. [Google Scholar] [CrossRef]
  27. Sengupta, L.; Mariescu-Istodor, R.; Fränti, P. Which Local Search Operator Works Best for the Open-Loop TSP? Appl. Sci. 2019, 9, 3985. [Google Scholar] [CrossRef]
  28. Chew, M.C. Optimal Stopping in a Discrete Search Problem. Oper. Res. 1973, 21, 741–747. [Google Scholar] [CrossRef]
  29. Tripathy, S.P.; Biswas, A.; Pal, T. A multi-objective Covering Salesman Problem with 2-coverage. Appl. Soft Comput. 2021, 113, 108024. [Google Scholar] [CrossRef]
  30. Golden, B.L.; Levy, L.; Vohra, R. The Orienteering Problem. Nav. Res. Logist. (NRL) 1987, 34, 307–318. [Google Scholar] [CrossRef]
  31. de Berg, M.; van Kreveld, M.; Overmars, M.; Schwarzkopf, O.; Algorithms, C.G. Computational Geometry; Springer: Berlin/Heidelberg, Germany, 1997; pp. 1–17. [Google Scholar] [CrossRef]
  32. Patel, V.B. Visualization of a Plane Sweep Algorithm for Construction of the Visibility Graph for Robot Path Planning. Ph.D. Thesis, University of Nevada, Las Vegas, NV, USA, 1989. [Google Scholar] [CrossRef]
  33. Mahoro Ntwari, D.; Gutierrez-Reina, D.; Toral Marín, S.L.; Tawfik, H. Time Efficient Unmanned Aircraft Systems Deployment in Disaster Scenarios Using Clustering Methods and a Set Cover Approach. Electronics 2021, 10, 422. [Google Scholar] [CrossRef]
  34. Rosenkrantz, D.J.; Stearns, R.E.; Lewis, P.M., II. An Analysis of Several Heuristics for the Traveling Salesman Problem. SIAM J. Comput. 1977, 6, 563–581. [Google Scholar] [CrossRef]
  35. Shah, S.; Dey, D.; Lovett, C.; Kapoor, A. Airsim: High-fidelity visual and physical simulation for autonomous vehicles. In Field and Service Robotics: Results of the 11th International Conference; Springer: Cham, Switzerland, 2018; pp. 621–635. [Google Scholar]
  36. Epic Games. Unreal Engine. 2021. Available online: https://www.unrealengine.com (accessed on 3 March 2021).
  37. Sculley, D. Web-scale k-means clustering. In Proceedings of the 19th International Conference on World Wide Web—WWW ’10, Raleigh, NC, USA, 26–30 April 2010; pp. 1177–1178. [Google Scholar] [CrossRef]
Figure 1. (a) The properties define the camera footprint size. As the orientation of the drone is unknown at the early stages of planning, the circle inscribed in the rectangle image is considered as its footprint. (b) The position of the drone. (c) The image captured by the drone camera.
Figure 1. (a) The properties define the camera footprint size. As the orientation of the drone is unknown at the early stages of planning, the circle inscribed in the rectangle image is considered as its footprint. (b) The position of the drone. (c) The image captured by the drone camera.
Drones 09 00098 g001
Figure 2. Area grid decomposition where each cell is of appropriate size for drone landing.
Figure 2. Area grid decomposition where each cell is of appropriate size for drone landing.
Drones 09 00098 g002
Figure 3. Exhaustive search—a single iteration. (a) Probability map together with obstacles (black). The radius of each circle is proportional to its probability. (b) The discrete map was obtained by applying the threshold and the cluster centers (orange) are surrounded by a footprint-size circle. (c) The complete graph and the trajectory visiting all cluster centers. Green vertices represent the initial position, and gray vertices belong to the visibility graph.
Figure 3. Exhaustive search—a single iteration. (a) Probability map together with obstacles (black). The radius of each circle is proportional to its probability. (b) The discrete map was obtained by applying the threshold and the cluster centers (orange) are surrounded by a footprint-size circle. (c) The complete graph and the trajectory visiting all cluster centers. Green vertices represent the initial position, and gray vertices belong to the visibility graph.
Drones 09 00098 g003
Figure 4. SST—planning stage. (a) The set V of candidate waypoints. (b) Score and select. The radius of the blue and red circles represents their probability and score, respectively. Selected waypoints are in orange. (c) The complete graph and the trajectory visiting all selected waypoints. Green vertices represent the initial position, and gray vertices belong to the visibility graph.
Figure 4. SST—planning stage. (a) The set V of candidate waypoints. (b) Score and select. The radius of the blue and red circles represents their probability and score, respectively. Selected waypoints are in orange. (c) The complete graph and the trajectory visiting all selected waypoints. Green vertices represent the initial position, and gray vertices belong to the visibility graph.
Drones 09 00098 g004
Figure 5. The planned trajectories solved by each of the examined algorithms. The size of the map is 770 m × 770 m, and the flight altitude is 150 m. Green and red areas are of high and low probabilities, respectively; black areas represent NFZ.
Figure 5. The planned trajectories solved by each of the examined algorithms. The size of the map is 770 m × 770 m, and the flight altitude is 150 m. Green and red areas are of high and low probabilities, respectively; black areas represent NFZ.
Drones 09 00098 g005
Figure 6. Average coverage ratio vs. threshold, calculated according to Equation (10).
Figure 6. Average coverage ratio vs. threshold, calculated according to Equation (10).
Drones 09 00098 g006
Figure 7. Algorithm performance for varying map sizes. (a) Computation time as function of the map size. (b) Coverage as a function of the map size.
Figure 7. Algorithm performance for varying map sizes. (a) Computation time as function of the map size. (b) Coverage as a function of the map size.
Drones 09 00098 g007
Figure 8. Algorithm performance for varying numbers of obstacle vertices. (a) Computation time as function of the number of obstacle vertices. (b) Coverage as a function of the number of obstacle vertices.
Figure 8. Algorithm performance for varying numbers of obstacle vertices. (a) Computation time as function of the number of obstacle vertices. (b) Coverage as a function of the number of obstacle vertices.
Drones 09 00098 g008
Table 1. Planning stage average computation time [s].
Table 1. Planning stage average computation time [s].
Algorithms20 m40 m70 m100 m150 mAvg.
ES1049.0404.1218.1149.8151.2394.4
SST41.429.122.419.717.025.9
SST-AC425.6386.2385.3383.6378.4391.8
SST-CEC120.755.347.246.947.963.6
SST-DIL-1007.97.77.36.85.97.1
SST-DIL-100027.723.818.514.110.919.0
SST-DIL-10,00081.464.540.529.824.148.1
Table 2. Exhaustion of time constraints [%].
Table 2. Exhaustion of time constraints [%].
ESSSTSST_ACSST_CEC
96.188.288.185.2
SST_DIL_100SST_DIL_1000SST_DIL_10,000
88.288.087.3
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Sabag, J.; Pinkovich, B.; Rivlin, E.; Rotstein, H. Efficient Coverage Path Planning for a Drone in an Urban Environment. Drones 2025, 9, 98. https://doi.org/10.3390/drones9020098

AMA Style

Sabag J, Pinkovich B, Rivlin E, Rotstein H. Efficient Coverage Path Planning for a Drone in an Urban Environment. Drones. 2025; 9(2):98. https://doi.org/10.3390/drones9020098

Chicago/Turabian Style

Sabag, Joanne, Barak Pinkovich, Ehud Rivlin, and Hector Rotstein. 2025. "Efficient Coverage Path Planning for a Drone in an Urban Environment" Drones 9, no. 2: 98. https://doi.org/10.3390/drones9020098

APA Style

Sabag, J., Pinkovich, B., Rivlin, E., & Rotstein, H. (2025). Efficient Coverage Path Planning for a Drone in an Urban Environment. Drones, 9(2), 98. https://doi.org/10.3390/drones9020098

Article Metrics

Back to TopTop