Next Article in Journal
The Enigma of the Muon and Tau Solved by Emergent Quantum Mechanics?
Next Article in Special Issue
Smart Obstacle Avoidance Using a Danger Index for a Dynamic Environment
Previous Article in Journal
A Radiological Approach to Evaluate Bone Graft Integration in Reconstructive Surgeries
Previous Article in Special Issue
Integrating a Path Planner and an Adaptive Motion Controller for Navigation in Dynamic Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A New Coverage Flight Path Planning Algorithm Based on Footprint Sweep Fitting for Unmanned Aerial Vehicle Navigation in Urban Environments

School of Information and Electronics Engineering, Korea Aerospace University, Deogyang-gu, Goyang-si, Gyeonggi-do 412-791, Korea
*
Author to whom correspondence should be addressed.
Appl. Sci. 2019, 9(7), 1470; https://doi.org/10.3390/app9071470
Submission received: 11 March 2019 / Revised: 3 April 2019 / Accepted: 4 April 2019 / Published: 8 April 2019
(This article belongs to the Special Issue Mobile Robots Navigation)

Abstract

:
This paper presents a new coverage flight path planning algorithm that finds collision-free, minimum length and flyable paths for unmanned aerial vehicle (UAV) navigation in three-dimensional (3D) urban environments with fixed obstacles for coverage missions. The proposed algorithm significantly reduces computational time, number of turns, and path overlapping while finding a path that passes over all reachable points of an area or volume of interest by using sensor footprints’ sweeps fitting and a sparse waypoint graph in the pathfinding process. We devise a novel footprints’ sweep fitting method considering UAV sensor footprint as coverage unit in the free spaces to achieve maximal coverage with fewer and longer footprints’ sweeps. After footprints’ sweeps fitting, the proposed algorithm determines the visiting sequence of footprints’ sweeps by formulating it as travelling salesman problem (TSP), and ant colony optimization (ACO) algorithm is employed to solve the TSP. Furthermore, we generate a sparse waypoint graph by connecting footprints’ sweeps’ endpoints to obtain a complete coverage flight path. The simulation results obtained from various scenarios fortify the effectiveness of the proposed algorithm and verify the aforementioned claims.

1. Introduction

Unmanned aerial vehicles (UAVs) are achieving ground-breaking success in many application areas such as temporary infrastructure, monitoring and tracking, data collection and surveying, and delivery of goods [1]. The modern UAVs have the ability to carry a variety of payloads’ equipment to perform desired missions with realtime processing. The UAV market in experiencing an exponential growth due to the wide range of the practical applications in hazardous, uncertain and threatening areas [2]. Recently, due to the integration of internet of things and cloud technologies with the UAV the application scenarios of UAVs are becoming more and more advance [3]. The civilian real-life economic applications of UAVs such as traffic monitoring [4], air quality monitoring [5], disaster management [6], communication relays [7], and infrastructure inspection [8], among others, are more attractive applications. Despite having many promising applications in each sector, UAV usage without human control imposes several challenges that need to be resolved. Apart from the physical challenges, in many applications, a UAV needs the ability to compute a path between two pre-determined locations while avoiding various obstacles or to find a path which covers every reachable point of a certain area or volume of interest which is called coverage path planning (CPP). In this work, our focus is on the CPP for UAV’s navigation in 3D urban environments with fixed obstacles for coverage missions.
CPP is classified as subtopic of the path planning in robotics where it is necessary to obtain a low cost path that covers the entire free space of a certain area or volume of interest with minimum overlapping [9]. CPP is a non-deterministic polynomial time hard (NP-hard) optimization problem. Due to the extensive use of UAVs in many fields for complex missions, the problem of CPP for single and multiple UAVs has been a very active area of research, especially during the last decade [10,11]. Depending upon the type of information available for the UAV workspace, the CPP are divided into two major categories global and local. Several CPP algorithms have been proposed for covering a regular or irregular shaped area of interest (AOI) with visual sensor and thermal sensor, etc. mounted on the UAV [12,13,14]. The basic approach adopted by most of the offline CPP algorithm is the area decomposition into non-overlapping subregions, determining the visiting sequence of the subregions, and covering decomposed regions individually in a back and forth manner to obtain a complete coverage path. Decomposition-based methods are promising in achieving the complete coverage of the target area. Classical exact cellular decomposition [15], morse based decomposition [16], landmark based topological coverage [17], grid-based methods [18], contact sensor-based coverage [19], and graph based methods [20] are well-known decomposition-based coverage methods.
Most of the existing CPP algorithms for UAVs do not provide thorough insight into complete coverage of the AOI by considering sensor footprints as coverage unit particularly regarding the efficient and complete coverage of the AOI with footprints’ sweeps fitting in complex 3D urban environments. The authors of [21] have explained that most of the existing algorithms employ the same sweep direction in all subareas which may not be able to obtain optimal results. Recently, various approaches have been proposed to compute a low cost coverage path such as mirror mapping method [22], viewpoints sampling [23], in-field obstacles classification [24], optimal polygon decomposition [25], and context-aware UAV mobility [26]. Despite the success of such techniques, in most cases, either many locations of the target area are covered repeatedly, or computing time degrades [27]. In addition, most of the algorithms have limited applicability in relation with the shape of the target area [21,28]. When the shape of AOI is changed, the algorithm performance is no longer feasible. Furthermore, the majority of the algorithms do not consider the decomposition of the AOI with relation to the camera/sensor footprints which can significantly increase the number of turns in the path. To overcome the aforementioned limitations, this study proposes a new coverage flight path planning algorithm that fulfil the multiple objectives of CPP.
The rest of the paper is organized as follows; Section 2 explains the background and related work regarding well-known coverage path planning algorithms. Section 3 presents the proposed coverage flight path planning algorithm and explains its principal steps. Section 4 discusses the experiments and simulation results. Finally, conclusions and future directions are offered in Section 5.

2. Background and Related Work

This section presents the background and related work regarding the AOI decomposition techniques used for UAV CPP, coverage types, different types of the AOI used for coverage missions, geometric flight patterns, path optimization algorithms and application specific CPP methods. Cao et al. [29] defined the six requirements for coverage scenarios. In complex environments, it is not always possible to satisfy all six requirements. Therefore, in some cases, the priority is given to the mission completion with sacrifice on some of the requirements [30]. Prior research classified the CPP methods into two major categories: heuristic and cell decomposition-based methods. Heuristic based methods define procedures that should be followed during CPP [31,32]. In cell decomposition, the AOI is decomposed into non-overlapping cells of varying shapes and sizes. There exist several kinds of the AOI decomposition techniques in literature [30]. Boustrophedon decomposition [33] and trapezoidal decomposition [34] are two well-known exact cellular decomposition techniques that are widely used for coverage applications. Morse-based cellular decomposition is an advance form of the boustrophedon decomposition which is based on critical points of Morse functions [35]. The approximate cellular decomposition techniques divide the AOI into a set of regular cells. Grid-based methods are used over approximate areas to generate coverage paths for the UAVs [36]. Convex decomposition transforms the irregular shaped AOI into regular shaped cells in order to reduce the number of turns [37]. Each decomposition method varies regarding the cell sizes, cell shapes, degree of computational complexity, and path quality. A pictorial overview of the most widely used AOI decomposition techniques is given in Figure 1.
There are two types of coverage: simple and continuous. The shape of the AOI can be a rectangle, square, convex polygon, non-convex polygon, 3D cubes (i.e., buildings) or irregular for coverage missions. The most widely used geometric flight patterns for CPP are back and forth (BF), spiral (SP), zamboni, and hybrid patterns. Andersen et al. [38] compared different types of the geometric flight patterns in his work. The flight patterns are employed considering the UAV mobility constraints, shape of the AOI, coverage type, and application requirements. For example, the BF pattern is suitable when the AOI is rectangular and large in size. Jiao et al. [39] proposed an exact cellular decomposition based approach for concave area coverage. Initially, the concave shaped AOI is decomposed into the convex subareas using the minimum width sum approach [40], and then the BF motion pattern is applied to completely sweep the AOI. Xu et al. [41] proposed an optimal CPP approach for fixed wing UAVs with minimum overlapping and coverage guarantees. The proposed algorithm employs the boustrophedon decomposition to decompose the AOI into a set of cells. Later, the adjacency graph is constructed from the cells, and cells are swept using the BF motion patterns. The order of the cells visit follows the Eulerian circuit having start and end at the same vertex. The proposed approach is able to achieve the complete coverage of the AOI. However, in some cases, it will perform additional sweeps by not considering the sensor’s footprint that will significantly affect the solution quality in the presence of complex geometry obstacles. Öst [42] proposed a CPP approach for concave shape AOI with sharp edges without sacrificing the guarantees on complete coverage.
In some scenarios, a UAV needs to visit several spatially distributed points of interests (POIs) in the target area to either collect data or provide wireless charging during the mission. In such cases, the CPP problem is divided into several small start-to-goal subproblems, where UAV needs to visit each POI only once while avoiding collision with the obstacles present in the AOI.Some authors considered the special cases of CPP in which AOI contains many interesting and non-interesting zones [43,44]. The interesting zones need careful coverage with higher resolution, so UAV covers such zones with low altitudes and vice versa.A new CPP approach for the aerial remote sensing in agriculture was proposed by Barrientos et al. [45]. The proposed approach decomposes the AOI based on the vehicle’s capabilities. UAV has to fly at a certain constant height in order to ensure a specific resolution and CPP is performed using a wavefront planner [46]. The existing studies used several path optimization algorithms for UAV CPP. The ant colony optimization (ACO) [47], Genetic algorithm (GA) [48], wavefront algorithm [49], A* algorithm [50], theta* algorithm [51], particle swarm optimization (PSO) [52], and their improved versions, among other, are the most widely used path optimization algorithms for CPP.
A number of studies have explored a closely related method used for UAV CPP with coverage guarantees, the boustrophedon cellular decomposition based hierarchal CPP approach (BCDH-CPP) [53], and the related coverage alternatives-based CPP (CA-CPP) algorithm [54]. The BCDH-CPP [53] is a cellular decomposition based CPP approach for the UAVs and it is a promising method for CPP in known environments inhabiting arbitrary obstacles. The proposed approach decomposes the AOI into cells, compute a Eulerian circuit traversing through these cells, and finally joins each cell in using seed spreader motion pattern to find a coverage path. The proposed approach determines the coverage path with excessive overlapping in some parts by not considering the UAV sensor/camera footprints as coverage unit. CA-CPP algorithm [54] introduced the four coverage alternatives to perform efficient coverage in both convex and non-convex areas. The proposed approach can reduce the number of turns and path length considering the appropriate directions and optimal line sweep. The proposed approach has very high computational cost. Meanwhile, the authors devised a method to reduce the overheads by enforcing adjacencies. However, due to extensive evaluation of various permutations, the proposed algorithm complexity varies exponentially with problem size. Furthermore, the decomposition-based CPP approaches discard the useful global information about the free spaces geometry which can lead to the excessive number of turns in the path.
The contributions of this research in the field of UAV global CPP can be summarized as follows: (i) it proposes a new coverage flight path planning algorithm that has potentials to obtain the minimum length path that ensures the perfect coverage of the target area with reduced computational time, number of turns, and path overlapping; (ii) it evaluates and selects the best coverage direction(s) by analyzing the span of the AOI, and exploiting free spaces geometry information to reduce the number of turns in the path; (iii) it introduces a novel footprints’ sweeps fitting method in which an entire free space of a certain AOI can be swept with fewer and longer sensor/camera footprints’ sweeps; (iv) it determines the visiting sequence of the footprints’ sweeps in the form of closed path to reduce the global path length; (v) it generates a sparse waypoint graph by connecting the footprint sweeps’ endpoints with neighbours’ sweeps by taking into account their visiting sequence, UAV maneuverability constraints, and obstacles effect; (vi) it finds a coverage path that fully scan the desired area located in 3D urban environments.

3. The Proposed Coverage Flight Path Planning Algorithm

This section explains the conceptual overview of the proposed CPP algorithm and outlines its procedural steps. Figure 2 shows the conceptual overview of our proposed global CPP algorithm.
To find a path that covers an entire free space of a certain region of interest Q of a 3D urban environment of known geometry, we used the seven principle steps. Brief discussion about each principle step with the equations, procedures and examples are explained below.

3.1. Modelling of the UAV Operating Environment

After getting the coverage mission specification, the proposed algorithm models the UAV operating environment. Environment modelling usually refers to the classification of free spaces ( Q f r e e ) and obstacles regions ( Q o b s t a c l e s ) . Q o b s t a c l e s refers to the parts of the AOI Q where the UAV cannot fly due to the presence of obstacles. In contrast, Q f r e e refers to those parts of Q where UAV can operate without collision with obstacles. The obstacles’ regions are represented with the geometrical shapes (i.e., squares, cubes, circles, and cylinder, etc.). In this work, we model the UAV operating environment from the raw environment containing the elevation data about the urban environment buildings and apartments, etc. with a set of 3D convex obstacles by calculating the convex hull. Each obstacle has random width, length and altitudes depending upon the real environment geometry. Each obstacle has eight vertices and six faces. The obstacle vertices u in the modelled environment can be represented with three co-ordinates values, u = ( x , y , z ) . All eight vertices of the i t h obstacle along with their numerical values can be mathematically expressed as following matrix.
O i = x m i n y m i n z m i n ; x m i n y m i n z m a x x m i n y m a x z m i n ; x m i n y m a x z m a x x m a x y m i n z m i n ; x m a x y m i n z m a x x m a x y m a x z m i n ; x m a x y m a x z m a x = 874 909 0 ; 874 909 252 874 1008 0 ; 874 1008 252 954 909 0 ; 954 909 252 954 1008 0 ; 954 1008 252 .
The source location is represented with a 3D point p, where p = ( x s , y s , z s ) and destination location is represented with a point q, where q = ( x t , y t , z t ) . In some coverage mission, the source p and destination q are the same because the UAV returns to the starting location after completing the mission. The objective of the proposed algorithm is to find a coverage path ζ that guarantees the perfect coverage of Q. The path ζ consists of nodes set which can be defined as, ζ Q f r e e and ζ Q o b s t a c l e s = Ø .

3.2. Locating Area of Interest on the Modelled Map and Extracting Free Spaces Geometry

This subsection briefly explains about locating the AOI on the modelled map and extracting free spaces geometry from the AOI for coverage mission.

3.2.1. Locating Area of Interest on the 3D Modelled Map

The AOI can be represented with the sequence of n vertices { v 1 , v 2 , v 3 , , v n } . Each vertex v i has three co-ordinates values ( v x ( i ) , v y ( i ) , v z ( i ) ) . Considering v i as the first vertex of the AOI, the next vertex to v i will be v n e x t ( i ) , where n e x t ( i ) = i ( m o d   n ) + 1 . The edge e i connecting two vertices v i and v n e x t ( i ) has length l i , where l i = v i v n e x t ( i ) . The AOI can contain many obstacles and no-Fly Zones (NFZ) of varying geometries. The AOI boundary is set of collision free vertices and edges. In some cases, the AOI vertices, edges or both can intersect with obstacles as shown in Figure 3.

3.2.2. Extracting Free Spaces Geometry

After locating the AOI in an enclosed form on the map, we extract free spaces geometry from the AOI. To do so, we first perform the obstacles’ existence checks in the AOI. With the help of these checks, the AOI can be classified into three categories such as obstacles-free environment, obstacles inhibiting environment and area boundary obstacles only. We simplify the AOI boundary by considering the obstacles that intersect with the AOI edges or vertices and lying in close proximity of the AOI edges by shrinking the AOI inward considering the UAV size.
Those obstacles which are on the boundary of the AOI or in close proximity that can impact the UAV safety are removed and configuration space (CS) is simplified for mission. Later, we draw a line from one vertices of the AOI to its nearest adjacent vertices and rotate it to all n vertices to determine the obstacles’ existence. If no obstacles intersect with the line, then the AOI can be regarded as the obstacle-free. Meanwhile, if the obstacles exist, the proposed algorithm determines whether the obstacles are part of the area boundary obstacles only or in-field obstacles. In the former case, the proposed algorithm performs the coverage in simplified CS where the AOI is obstacle-free. In the latter case, the obstacles’ enlargement (i.e., pushing the intersections by a D s a f e out of obstacles.) and clustering are carried out to extract the free spaces geometry from the AOI. We enlarge the obstacles by safe distance D s a f e and cluster the nearby obstacles which overlap each other due to D s a f e addition or become so close to each other that UAV can collide. D s a f e is an integer number whose value can be adjusted considering the UAV size, operating environment and obstacles shape. A pictorial overview of the enlarged obstacle by D s a f e addition is shown in Figure 4b.
We apply the minimum UAV altitude limits H m i n to discard the obstacles that fall below the H m i n and UAV can go over safely. Through the above-mentioned process, the AOI can be classified into traversable and non-traversable parts. In the traversal parts, we fit UAV sensor footprints’ sweeps considering the appropriate coverage direction for the coverage missions.

3.3. Selecting the Best Coverage Direction (s) by Analyzing the Span of the Area of Interest and Exploiting Free Spaces Geometry Information

Selecting the best coverage direction is extremely important to reduce the number of turns in the flight path to preserve the UAV resources. The turns are costly in terms of the energy, mission time, and path length because the UAV has to reduce the speed, perform turn, and increase speed again. Figure 5 presents the overview of the coverage path obtained from the same AOI with two different directions. The path on the left has only three turns and the path on the right has eleven turns.
In this work, we select the best coverage direction (s) by analyzing the span D of the AOI and exploiting free spaces’ geometry information. We compute the horizontal span H s and vertical span V s of the AOI for the best coverage direction selection for regular shaped AOI. Additionally, we exploit the free spaces’ geometry knowledge to select the appropriate coverage direction (s). The coverage direction is chosen parallel to the maximal span axis and considering the free spaces tendency. We employ either one or multiple coverage directions depending upon the AOI complexity to reduce the number of turns. For the irregular shaped AOI, we compute the convex-hull and transform it to some approximate regular shape for the span calculation and best coverage direction selection. When both spans of the AOI are equal, the appropriate coverage direction is chosen considering the obstacles placement and free spaces tendency. By utilizing the global information about the AOI and following the procedure explained above, the best coverage direction can be selected which yields a smaller number of turns in the path. The proposed method utilizes the cumulative knowledge of the several parts of the AOI to find the best coverage direction which reduces the number of turns significantly.

3.4. Sensor Footprints Sweeps Fitting in Free Spaces of the Area of Interest

UAV carries a specific tool to cover the AOI in coverage missions. The tool can be a visual sensor, transmitter, digital camera, or spray tank depending upon the mission. In this work, we assume that UAV carries a visual sensor to cover the AOI during coverage. The attached tool has different sensing characteristics and varying footprint sizes depending upon the UAV height. If the UAV altitude is low, the footprint size is small and image resolution is high. In contrast, when the UAV altitude is high, the footprint size is bigger, and resolution is low. The sensing parameters are adjusted and usually taken at the start of the mission to achieve the desired objectives. UAV generally flies at constant altitude in coverage missions. However, in some cases, it pays attention to the priority of regions. The important regions are covered with low altitudes and vice versa. The sensor footprint F is of rectangular shape with fixed length F l and width F w , respectively. However, the size of the footprint keeps changing with the UAV altitude during the mission. After determining the sensor footprint size on the ground as shown in Figure 6a, we fit N sensor footprints’ sweeps in such a way that maximal coverage can be achieved with fewer footprints’ sweeps.
The N sensor footprints fitted in the AOI can be mathematically expressed as a set as shown in Equation (1):
R = { F 1 , F 2 , F 3 , , F N } .
Each footprint sweep has two parts: one is on the ground (i.e., 2D in rectangular form) and the other is from a certain height (i.e., 3D in a line segment form) similar to the sample shown in Figure 6b. The 3D one passes from the middle of the ground one and it is used as an actual path on which UAV moves during the mission. Considering the footprint as line segment, the start point a i and endpoint b i of footprint i are given as:
F i = ( a i , b i ) = ( ( x a i , y a i , z a i ) , ( x b i , y b i , z b i ) ) .
After fitting the footprints’ sweeps, we find the midpoint of each footprint line segment part utilizing a and b values to find the visiting sequence of footprints’ sweeps. The midpoint m i of the i t h footprint F i can be computed using the a i and b i co-ordinates values. A pictorial overview of a footprint in rectangle form and sensor footprint sweep is shown in Figure 6b.

3.5. Determining the Footprints’ Sweeps Visiting Sequence

After fitting the footprints’ sweeps, the next step is to determine the sequence in which the footprints’ sweeps will be visited to ensure the complete coverage. To find the low cost footprints’ sweeps visiting sequence, we formulate it as a travelling salesman problem (TSP), and the ant colony optimization algorithm is employed to solve the TSP. Given M points set originally calculated from the footprint sweeps, endpoints are used to calculate a close path that visits each point exactly once. We specify the basic parameters of ACO according to problem size. After the parameter setting, the distance and sight matrix are computed between points. Then, l ants are deployed on random points and the computation is carried out for the pre-defined n i t r iterations. During the computation, each ant calculates the tour by remembering the vertices which have already been explored and choosing the nearby points from their current position based on action choice rule. The probability that point j will be visited by an ant k which is currently at point i can be computed from Equation (3):
p i j k = [ τ i j ] α [ η i j ] β s a l l o w e d k [ τ i j ] α [ η i j ] β , j a l l o w e d k , 0 ,        o t h e r w i s e ,
where τ i j represents the intensity of the pheromones trial between point i and j, α is a parameter used to regulate the influence of τ i j , the variable η i j represents the visibility between point j and i, which is computed as 1 / d i j (where d i j is the Euclidian distance between two points), β is a parameter used to regulate the influence of η i j and a l l o w e d k represents the points that have not been visited by an ant k yet, respectively.
At the start, l ants are deployed to the m points randomly. Later, each ant makes the decision to choose the next point based on the transition probability p i j k given by Equation (3). After n i t r of this whole process, every ant computes a complete tour by visiting each point once. It is desirable to reinforce good solutions and the ant with the shortest tour should deposit more pheromones to find the low cost solution compared to other ants. Thus, the trail levels are updated, and each ant leaves a quantity of pheromones given by K / L k , where K is a constant and L k is the length of the tour. Meanwhile, the pheromones’ quantity will decrease as time goes by. Therefore, the update rule of the τ i j can be written as follows:
τ i j ( t + 1 ) = ( 1 ρ ) τ i j ( t ) + Δ τ i j ,
Δ τ i j = k = 1 l Δ τ i j k ,
Δ τ i j k = K / L k i f   a n t   k   t r a v e l s   o n   e d g e   ( i . j ) , 0 ,        , o t h e r w i s e ,
where variable t represents the iteration counter, ρ is the parameter to regulate the influence of τ i j , Δ τ i j represents the total increase of trial level on a particular edge ( i , j ) , and Δ τ i j k represents the increase of trial level on the two respective edges ( i , j ) caused by an ant k. While determining the visiting sequence, we do not consider the obstacles’ effect to find the minimum length global path. We consider the obstacles ’effect in the waypoint graph construction stage. With the help of ACO, we can get the set S, where S = { ( F 1 , n 1 ) , ( F 2 , n 2 ) , , ( F n , n n ) } of footprint sweeps’ visiting sequence that will be used for graph construction. In set S, the n i refers to the visiting sequence of a particular sweep.

3.6. Waypoints Graph Generation by Connecting Footprints’ Sweeps

The waypoint graph (WG) is constructed by connecting the footprint sweeps’ endpoints for the pathfinding. Mathematically, WG is a double edge graph Γ of inter-reachable locations: Γ = { W , E } , where W represents the nodes set and E represents the edge set. The nodes of the Γ are the footprints’ sweeps endpoints, while edges are straight lines for each sweep and connection from one sweep to another. Each footprint sweep is a line segment with the two endpoints a and b (i.e., F i = a b ¯ ) as shown in Figure 6b. We connect the footprints’ sweeps endpoint with the coincident (i.e., neighbours) sweeps endpoints to form a WG. Furthermore, in the WG construction process, we consider the obstacles’ effect, UAV manoeuvrability constraints and footprints sweep visiting sequence to form the connected Γ . We devise a strategy to avoid obstacles by applying three avoidance options (i.e., left, right, top) in footprints’ sweeps inter-connection. Given N footprints’ sweeps in the form of line segments, we compute the collision-free connections between footprints’ sweeps. While constructing the WG, the proposed algorithm evaluates and selects the best obstacles’ avoidance option from the candidate options. For the appropriate options selection, the distance is computed between two sweeps by introducing the two points on three sides of the obstacles. The selection of the appropriate obstacle’s avoidance option A O A O for an obstacle O i is carried out on the basis of following equation:
A O A O i = m i n { d l e f t , d r i g h t , d t o p } ,
where d l e f t , d r i g h t and d t o p represent the minimum distance required to avoid an obstacle i from left, right, and top, respectively. The value of d for each option can be computed between two sweeps with the help of two intermediate points. For example, the distance required to find the collision-free connection between two footprints’ sweeps F i and F i + 1 is the sum of the three individual distances (i.e., d { ( a , b ) , c ) , ( c , d ) , ( d , ( a , b ) ) } . The value of each option can be calculated with the help of following equation:
d l e f t = j = 1 3 d j ,
where d j represents the minimum distance needed to connect two footprints’ sweeps by bypassing an obstacle safely from left. Similarly, the distance values for the other two options are calculated and evaluated for the low cost connection formation. Meanwhile, if no obstacle exists between the footprints’ sweeps, and collision can be avoided, then footprints’ sweeps are connected with each other via straight lines. The waypoint graph Γ obtained from the AOI possess all properties of a roadmap. A pictorial overview of the waypoint graph Γ obtained by connecting endpoints of the N footprints’ sweeps from the AOI having size 1500 × 1500 × 400 is shown in Figure 7a.
In Figure 7a, the yellow lines represent the footprints’ sweeps and blue lines represent the collision-free connection between sweeps. Meanwhile, the black colour represents the area scanned by sensor footprints’ sweeps. The proposed approach is applicable for both types of the UAVs, rotary-wing and fixed-wing. The rotary-wing UAVs present maneuverability advantages when making turns during the flight compared to the fixed wing UAVs. The WG produced by connecting the footprints’ sweeps endpoints is directly usable for the rotary-wing UAV. Meanwhile, the fixed-wing UAV has strong maneuverability restrictions, demanding a bigger space to make turns. Therefore, the back-and-forth/zamboni flight pattern can be adopted to generate the WG, where the sweeps will be connected as shown in Figure 7b. In the BF/Zamboni flight pattern, the adjacent sweeps can be connected with the gap g of two or three depending upon the complexity of the AOI and sweeps placements. The suggested pattern can simplify the turn and UAV doesn’t need to slow down while making the turn. However, the BF/Zamboni flight pattern can lead to the excessive path overlapping in the complex scenarios. The proposed approach simplifies the turns to the extent possible for the easier adoption using both types of the UAVs. The proposed approach generates a sparse WG with minimum nodes and edges to reduce the computational complexity of pathfinding process. The complete pseudo-code used to generate a waypoint graph from AOI is given in Algorithm 1. In Algorithm 1, the AOI Q containing N number of obstacles, footprint sweeps set R, footprint sweeps visiting sequence set S, and footprint connection gap g are provided as an input. Waypoint graph Γ , where ( Γ = { W , E } ) is obtained as an output. Line 2 implements the finding of appropriate footprint sweep to be connected with footprint sweep F i out of N 1 candidates based on optimized visiting sequence and sweeps connection gap. Line 3 implements the identification of the relevant endpoint’s pairs through which two sweeps F i and F j will be connected with each other. Line 4 performs the check for the obstacle(s) existence between two sweeps to form the collision-free connection C i . Lines 5–6 implement the connection formation in the presence of obstacle(s) between two sweeps while avoiding the obstacle with low cost option. Line 8 implements the connection formation if no obstacles exist between two sweeps. Furthermore, the same process continues until the complete waypoints is constructed. Finally, waypoint graph Γ of footprints’ sweeps connection is returned as an output (line 11).
Algorithm 1: Waypoint graph generation from the AOI located in a 3D map.
Input   :(1) AOI Q containing N number of obstacles, where N = { o 1 , o 2 , o 3 , , o n } .
      (2) Set R of footprints’ sweeps, where R = { F 1 , F 2 , , F n } and F i = ( a i , b i ) .
      (3) Sweeps visitng sequence set S, where S = { ( F 1 , n 1 ) , ( F 2 , n 2 ) , , ( F n , n n ) } .
      (4) Sweeps connection gap (g).
Output   :Way point graph Γ
Procedure: 
  for each footprint sweep F i , where F i = F 1 to F n R do
   Find next footprint sweep F j considering the g value and optimized visiting sequence.
   Identify the relevant endpoint pair using ( a i , a j , b i , b j ) for connection C i
   if INTERSECTS( C i , o i ) then
    Evaluate and select the appropriate obstacle o i avoidance option using Equation (7).
    Connect the footprints’ sweeps F i and F j with the relevant endpoints.
   else
    Connect the footprints’ sweeps F i and F j with the relevant endpoints.
   End if
  End for
return Γ

3.7. Path Searching on the Waypoints Graph

After constructing the WG, the path searching is carried out to find the complete coverage path from the pre-determined location of the UAV. The source point p represents the point from where the UAV starts the mission and point q represents the endpoint of the mission. Once the complete graph is constructed, the pathfinding process starts from the point p and continues until the complete coverage is achieved. We used the ACO algorithm generated order for the collision-free pathfinding over WG with minimum overlapping and informed search. The proposed algorithm keeps track of the locations to be visited along the path by using the order generated for footprints’ sweeps visits and their connections. We assume that UAV is able to take turns with sufficient accuracy while switching from one sweep to another during the mission. The proposed approach is able to find the minimum length path with less path overlapping, less number of turns, and reduced computation time compared to the existing methods in most scenarios.

4. Simulation Results and Discussion

This section presents the simulation results and key findings about the proposed concept. The improvements of the proposed algorithm were compared using four criteria; the improvements in computation time, path lengths, path overlapping, and number of turns with the existing closely related algorithms. To benchmark the proposed algorithm, we compared the proposed algorithm results with decomposition-based CPP methods, BCDH-CPP [53] and CA-CPP algorithm [54]. The simulation results were produced and compared on a PC running Windows 10, with a CPU Intel Core i5 of 2.6 GHz and 8.00 GB of RAM, using MATLAB version 9.4.0.81 (R2018a). In simulations of the proposed CPP algorithm, we consider a 25-kg UAV similar to our previous study [55]. We considered both global constraints that are related to the UAV operating environment and local constraints that are related to the UAV. The numerical values related to the local constraints are: maximum steering angle: p/6 radius and wing span: 1 m. We assumed a zero-wind scenario in our simulations and assumed that there exists no external inference that can impact the established path. We assumed that a UAV has sufficient power to finish the mission successfully in one round. The minimum and maximum UAV flight height limits are 25 m and 150 m ( h m i n = 25 m, h m a x = 150 m). The safe distance value for collision avoidance with obstacles is set to 10 m ( D s a f e = 10 m). The ACO parameters were specified considering the problem size (i.e., no. of sweeps). The sensor footprint sweep width is set to 20 m ( F w = 20 m) and footprint sweep length is set to 30 m ( F l = 30 m). We present the overview of the 3D maps used in the experiments and two exemplary coverage path results visually in Figure 8a,b. We compared the proposed algorithm results with the existing methods on two grounds: the varying obstacles densities and shape of the AOI. The relevant details about AOI sizes, obstacles’ densities, and the shape of the AOI used in experiments are explained in Section 4.1 and Section 4.2.

4.1. Comparisons with the Existing Algorithms Based on Obstacles’ Densities

The number of obstacles and their placement in the AOI significantly impact the performance of any CPP algorithm. To validate the proposed algorithm feasibility for coverage missions in 3D urban environments, we compared the proposed algorithm path lengths, computing time and path overlapping results with existing methods using five maps with varying obstacles’ densities. For the evaluation, we compared the proposed algorithm results using three obstacles’ density values (low, medium and high) on regular shaped AOI. All obstacles were placed randomly in the AOI in all cases. The low density obstacles’ AOI has less number of obstacles and most parts of the area are traversable. In such areas, the most parts can be covered with fewer and longer sensor footprints’ sweeps. In contrast, the high density obstacles AOI has less traversable parts and the path overlapping can increase due to complex obstacle geometry. The medium density obstacles areas have uniform distribution of obstacles and almost half of the spaces can be covered with the sweeps. The complete description about the AOI sizes used in experiments, and average running time and path length results’ comparisons of the proposed CPP algorithm are shown in Table 1. The computing time, path length, and path overlapping results are the average of five runs in Table 1, Table 2 and Table 3.
From the results, it can be observed that both computing time and path length increase with an increase in size of the AOI and obstacles’ densities. Meanwhile, the proposed algorithm shows 11.2% and 19.7% reduction in computing time compared to the closely related algorithms. From the path length point of view, the proposed algorithm shows 9.1% and 4% reduction as compared to BCDH-CPP and CA-CPP method, respectively. When the environment complexity is low and AOI size is small (i.e., the first two cases), the CA-CPP algorithm yields shortest length path compared to proposed algorithm. Meanwhile, as the AOI size and obstacle densities grow, the performance of the proposed algorithm improves on both metrics (i.e., path lengths and computing time). Apart from the path lengths and computing time comparisons, we compared the proposed algorithm path overlapping results with the two closely related algorithms in each map (listed in Table 1). The proposed algorithm path overlapping results in average and its comparison with the existing methods are shown in Table 2.
The proposed algorithm on average gives 9.98 % improvements compared to the existing algorithms on five different maps of varying AOI size and obstacles densities. Furthermore, in all cases, the proposed algorithm gives the coverage ratio C r a t i o of 1.0 that represents the perfect coverage (i.e., 100%). The proposed approach can be applied in indoor and outdoor environments for a variety of applications specifically for the aerial inspection in urban environments. In the proposed algorithm, the footprints’ sweeps fitting and final paths are calculated offline. Meanwhile, the proposed algorithm can be applied in two phases: offline and online. The sweeps can be fitted in an offline phase and path searching can be done in an online phase.

4.2. Comparisons with the Existing Algorithms Based on the Shape of the Area of Interest

Apart from the obstacle’s densities, the shape of the area of intreat is also a relevant factor that can significantly impact the CPP algorithm performance. CPP over the regular shaped AOI is relatively easy compared to the irregular shaped AOI. The regular shaped AOI coverage can be obtained with the simple BF pattern. Meanwhile, the irregular shaped AOI coverage requires the concavities modification and hybrid motion patterns to achieve the full coverage. The CPP complexity varies with the shape of the target area and it requires obstacles’ geometry knowledge to find the low cost solution for the coverage missions. To address this concern, we compared the proposed algorithm performance with the existing methods over five different types of the AOI to support generality. We performed rigorous experiments to verify the algorithm performance in relation with the shape of the AOI. The average computation time, path length and path overlapping are shown in Table 3.
Through simulations and comparison with the two existing algorithms using five different shapes of the AOI, on average, our proposed algorithm reduces the computing time of pathfinding by 21.34%. From a path length point of view, it reduces path length by 8.98%. Additionally, the proposed algorithm has less path overlapping compared to the existing algorithms. We further compare our approach results of turning maneuvers with two existing methods in ten representative scenarios. Figure 9 shows the number of turns’ comparisons between proposed and two existing algorithms. The proposed method shows 12.1% and 7.03% improvements in the number of turns as compared to BCDH-CPP and CA-CPP algorithm, respectively.
Apart from the numerical result, the proposed algorithm uses less number of sweeps compared to the decomposition based methods. Figure 10 shows the number of sweeps used by the proposed algorithm and decomposition based methods for the coverage of three cells (i.e., 5 to 7) of the AOI.
From the results, it can be observed that when the cell size is small and sufficient attention has not been paid to sensor/camera footprints size in area decomposition, the BCDH-CPP [53] and CA-CPP [54] algorithms (Figure 10b) need more sweeps compared to the proposed algorithm which can increase the path length in complex scenarios. In contrast, the proposed algorithm (Figure 10c) considers the sensor footprint as a coverage unit in the CPP and uses less sweeps to guarantee the perfect coverage.

5. Conclusions and Future Work

In this paper, we proposed a new coverage flight path planning algorithm based on footprints’ sweeps fitting and a sparse waypoint graph for unmanned aerial vehicles’ (UAVs) navigation in three-dimensional (3D) urban environments with fixed convex obstacles. The main goals of the proposed algorithm are to reduce the computational time, number of turns, and path overlapping while finding a minimum length path that passes over all reachable points of an area or volume of interest for UAVs flying at low-altitudes in 3D urban environments. We devised a novel footprints’ sweeps fitting method by considering the UAV sensor footprint as a coverage unit that guarantees complete coverage of the AOI with fewer and longer sensor footprints’ sweeps. Furthermore, we generate a sparse waypoint graph by connecting footprints’ sweeps endpoints by considering footprints’ sweeps visiting sequence, obstacles’ effect, and maneuverability constraints to obtain a complete coverage flight path. Simulation results have shown that the proposed algorithm can achieve better performance compared to the closely related global coverage flight path planning algorithms. It finds a feasible path from the urban environments inhabiting substantial number of obstacles without sacrificing the guarantees on computing time, number of turns, perfect coverage, path overlapping, and path length. The proposed CPP algorithm is practical, effective, feasible, and it has important significance in UAV practical application in urban environments. In addition, the proposed algorithm is directly inspired by the real-life applications of UAVs, and it is applicable for various coverage related applications in 3D urban environments with fixed obstacles. In future work, we are planning to enhance the proposed CPP algorithm for spatially distributed regions coverage.

Author Contributions

Conceptualization, S.L.; Data curation, A.M.; Investigation, A.M. and S.L.; Methodology, A.M.; Project administration, S.L.; Software, A.M.; Supervision, S.L.; Validation, A.M. and S.L.; Visualization, A.M.; Writing—original draft, A.M.; Writing—review & editing, S.L.

Funding

This work was supported by Institute for Information & Communications Technology Promotion (IITP) grant funded by the Korean Government (MSIT) (No. 2015-0-00893, Technology Development of DMM-based Obstacle Avoidance and Vehicle Control System for a Small UAV).

Conflicts of Interest

The authors declare no conflict of interest regarding the publication of this manuscript.

References

  1. Kyrkou, C.; Timotheou, S.; Kolios, P.; Theocharides, T.; Panayiotou, C. Drones: Augmenting Our Quality of Life. IEEE Potentials 2019, 38, 30–36. [Google Scholar]
  2. Wong, C.; Yang, E.; Yan, X.T.; Gu, D. Autonomous robots for harsh environments: A holistic overview of current solutions and ongoing challenges. Syst. Sci. Control Eng. 2018, 6, 213–219. [Google Scholar] [CrossRef]
  3. Pinto, M.F.; Marcato, A.L.; Melo, A.G.; Honório, L.M.; Urdiales, C. A Framework for Analyzing Fog-Cloud Computing Cooperation Applied to Information Processing of UAVs. Wirel. Commun. Mob. Comput. 2019. [Google Scholar] [CrossRef]
  4. Karaduman, M.; Çınar, A.; Eren, H. UAV Traffic Patrolling via Road Detection and Tracking in Anonymous Aerial Video Frames. J. Intell. Robot. Syst. 2019, 1–16. [Google Scholar] [CrossRef]
  5. Wang, Y.C. Mobile Solutions to Air Quality Monitoring. In Mobile Solutions and Their Usefulness in Everyday Life; Springer: Cham, Switzerland, 2019; pp. 225–249. [Google Scholar]
  6. Luo, C.; Miao, W.; Ullah, H.; McClean, S.; Parr, G.; Min, G. Unmanned Aerial Vehicles for Disaster Management. In Geological Disaster Monitoring Based on Sensor Networks; Springer: Singapore, 2019; pp. 83–107. [Google Scholar]
  7. Ullah, S.; Kim, K.I.; Kim, K.H.; Imran, M.; Khan, P.; Tovar, E.; Ali, F. UAV-enabled healthcare architecture: Issues and challenges. Future Gener. Comput. Syst. 2019, 97, 425–432. [Google Scholar] [CrossRef]
  8. Long, D.; Rehm, P.J.; Ferguson, S. Benefits and challenges of using unmanned aerial systems in the monitoring of electrical distribution systems. Electr. J. 2018, 31, 26–32. [Google Scholar] [CrossRef]
  9. Choset, H. Coverage for robotics—A survey of recent results. Ann. Math. Artif. Intell. 2001, 31, 113–126. [Google Scholar] [CrossRef]
  10. Dai, R.; Fotedar, S.; Radmanesh, M.; Kumar, M. Quality-aware UAV coverage and path planning in geometrically complex environments. Ad Hoc Netw. 2018, 73, 95–105. [Google Scholar] [CrossRef]
  11. Yao, P.; Cai, Y.; Zhu, Q. Time-optimal trajectory generation for aerial coverage of urban building. Aerosp. Sci. Technol. 2019, 84, 387–398. [Google Scholar] [CrossRef]
  12. Kim, D.; Liu, M.; Lee, S.; Kamat, V.R. Remote proximity monitoring between mobile construction resources using camera-mounted UAVs. Autom. Constr. 2019, 99, 168–182. [Google Scholar]
  13. Oliveira, R.A.; Tommaselli, A.M.; Honkavaara, E. Generating a hyperspectral digital surface model using a hyperspectral 2D frame camera. ISPRS J. Photogramm. Remote Sens. 2019, 147, 345–360. [Google Scholar] [CrossRef]
  14. Díaz-Delgado, R.; Ónodi, G.; Kröel-Dulay, G.; Kertész, M. Enhancement of Ecological Field Experimental Research by Means of UAV Multispectral Sensing. Drones 2019, 3, 7. [Google Scholar] [CrossRef]
  15. Lingelbach, F. Path planning using probabilistic cell decomposition. In Proceedings of the 2004 IEEE International Conference on Robotics and Automation, ICRA’04, New Orleans, LA, USA, 26 April–1 May 2004; Volume 1, pp. 467–472. [Google Scholar]
  16. Acar, E.U.; Choset, H.; Rizzi, A.A.; Atkar, P.N.; Hull, D. Morse decompositions for coverage tasks. Int. J. Robot. Res. 2002, 21, 331–344. [Google Scholar] [CrossRef]
  17. Wong, S. Qualitative Topological Coverage of Unknown Environments by Mobile Robots. Doctoral Dissertation, The University of Auckland, Auckland, New Zealand, 2006. [Google Scholar]
  18. Shivashankar, V.; Jain, R.; Kuter, U.; Nau, D.S. Real-Time Planning for Covering an Initially-Unknown Spatial Environment. In Proceedings of the Twenty-Fourth International Florida Artificial Intelligence Research Society Conference, Palm Beach, FL, USA, 18–20 May 2011. [Google Scholar]
  19. Butler, Z.J.; Rizzi, A.A.; Hollis, R.L. Contact sensor-based coverage of rectilinear environments. In Proceedings of the 1999 IEEE International Symposium on Intelligent Control/Intelligent Systems and Semiotics, Cambridge, MA, USA, 17 September 1999; pp. 266–271. [Google Scholar]
  20. Xu, L. Graph Planning for Environmental Coverage. Ph.D. Thesis, Robotics Institute, Carnegie Mellon University, Pittsburgh, PA, USA, August 2011. [Google Scholar]
  21. Li, Y.; Chen, H.; Er, M.J.; Wang, X. Coverage path planning for UAVs based on enhanced exact cellular decomposition method. Mechatronics 2011, 21, 876–885. [Google Scholar] [CrossRef]
  22. Nasr, S.; Mekki, H.; Bouallegue, K. A multi-scroll chaotic system for a higher coverage path planning of a mobile robot using flatness controller. Chaos Solitons Fractals 2019, 118, 366–375. [Google Scholar] [CrossRef]
  23. Morgenthal, G.; Hallermann, N.; Kersten, J.; Taraben, J.; Debus, P.; Helmrich, M.; Rodehorst, V. Framework for automated UAS-based structural condition assessment of bridges. Autom. Constr. 2019, 97, 77–95. [Google Scholar] [CrossRef]
  24. Zhou, K.; Jensen, A.L.; Sørensen, C.G.; Busato, P.; Bothtis, D.D. Agricultural operations planning in fields with multiple obstacle areas. Comput. Electron. Agric. 2014, 109, 12–22. [Google Scholar] [CrossRef]
  25. Coombes, M.; Fletcher, T.; Chen, W.H.; Liu, C. Optimal polygon decomposition for UAV survey coverage path planning in wind. Sensors 2018, 18, 2132. [Google Scholar] [CrossRef]
  26. Montanari, A.; Kringberg, F.; Valentini, A.; Mascolo, C.; Prorok, A. Surveying Areas in Developing Regions Through Context Aware Drone Mobility. In Proceedings of the 4th ACM Workshop on Micro Aerial Vehicle Networks, Systems, and Applications, Munich, Germany, 10–15 June 2018; ACM: New York, NY, USA, 2018; pp. 27–32. [Google Scholar]
  27. Valente, J.; Del Cerro, J.; Barrientos, A.; Sanz, D. Aerial coverage optimization in precision agriculture management: A musical harmony inspired approach. Comput. Electron. Agric. 2013, 99, 153–159. [Google Scholar] [CrossRef]
  28. Cabreira, T.; Brisolara, L.; Ferreira, P.R. Survey on Coverage Path Planning with Unmanned Aerial Vehicles. Drones 2019, 3, 4. [Google Scholar] [CrossRef]
  29. Cao, Z.L.; Huang, Y.; Hall, E.L. Region filling operations with random obstacle avoidance for mobile robots. J. Robot. Syst. 1988, 5, 87–102. [Google Scholar] [CrossRef]
  30. Galceran, E.; Carreras, M. A survey on coverage path planning for robotics. Robot. Auton. Syst. 2013, 61, 1258–1276. [Google Scholar] [CrossRef]
  31. Lee, T.K.; Baek, S.H.; Choi, Y.H.; Oh, S.Y. Smooth coverage path planning and control of mobile robots based on high-resolution grid map representation. Robot. Auton. Syst. 2011, 59, 801–812. [Google Scholar] [CrossRef]
  32. Lin, L.; Goodrich, M.A. Hierarchical heuristic search using a Gaussian Mixture Model for UAV coverage planning. IEEE Trans. Cybern. 2014, 44, 2532–2544. [Google Scholar] [CrossRef] [PubMed]
  33. Choset, H. Coverage of known spaces: The boustrophedon cellular decomposition. Auton. Robots 2000, 9, 247–253. [Google Scholar] [CrossRef]
  34. Choset, H.M.; Hutchinson, S.; Lynch, K.M.; Kantor, G.; Burgard, W.; Kavraki, L.E.; Thrun, S. Principles of Robot Motion: Theory, Algorithms, and Implementation; MIT Press: Cambridge, MA, USA, 2005. [Google Scholar]
  35. Milnor, J.W.; Spivak, M.; Wells, R.; Wells, R. Morse Theory; Princeton University Press: Princeton, NJ, USA, 1963. [Google Scholar]
  36. Nam, L.H.; Huang, L.; Li, X.J.; Xu, J.F. An approach for coverage path planning for UAVs. In Proceedings of the 2016 IEEE 14th International Workshop on Advanced Motion Control (AMC), Auckland, New Zealand, 22–24 April 2016; pp. 411–416. [Google Scholar]
  37. Bochkarev, S.; Smith, S.L. On minimizing turns in robot coverage path planning. In Proceedings of the 2016 IEEE International Conference on Automation Science and Engineering (CASE), Fort Worth, TX, USA, 21–25 August 2016; pp. 1237–1242. [Google Scholar]
  38. Andersen, H.L. Path Planning for Search and Rescue Mission Using Multicopters. Master’s Thesis, Institutt for Teknisk Kybernetikk, Trondheim, Norway, 2014. [Google Scholar]
  39. Jiao, Y.S.; Wang, X.M.; Chen, H.; Li, Y. Research on the coverage path planning of uavs for polygon areas. In Proceedings of the 2010 5th IEEE Conference on Industrial Electronics and Applications (ICIEA), Taichung, Taiwan, 15–17 June 2010; pp. 1467–1472. [Google Scholar]
  40. Levcopoulos, C.; Krznaric, D. Quasi-Greedy Triangulations Approximating the Minimum Weight Triangulation. In Proceedings of the Seventh Annual ACM-SIAM Symposium on Discrete Algorithms, Atlanta, GA, USA, 28–30 January 1996; pp. 392–401. [Google Scholar]
  41. Xu, A.; Viriyasuthee, C.; Rekleitis, I. Optimal complete terrain coverage using an unmanned aerial vehicle. In Proceedings of the 2011 IEEE International Conference On Robotics and automation (ICRA), Shanghai, China, 9–13 May 2011; pp. 2513–2519. [Google Scholar]
  42. Öst, G. Search Path Generation With UAV Applications Using Approximate Convex Decomposition. Master Thesis, Linkoping University, Linkoping, Sweden, 2012. [Google Scholar]
  43. Sadat, S.A.; Wawerla, J.; Vaughan, R.T. Recursive non-uniform coverage of unknown terrains for uavs. In Proceedings of the 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2014), Chicago, IL, USA, 14–18 September 2014; pp. 1742–1747. [Google Scholar]
  44. Sadat, S.A.; Wawerla, J.; Vaughan, R. Fractal trajectories for online non-uniform aerial coverage. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 2971–2976. [Google Scholar]
  45. Barrientos, A.; Colorado, J.; Cerro, J.D.; Martinez, A.; Rossi, C.; Sanz, D.; Valente, J. Aerial remote sensing in agriculture: A practical approach to area coverage and path planning for fleets of mini aerial robots. J. Field Robot. 2011, 28, 667–689. [Google Scholar] [CrossRef]
  46. LaValle, S.M. Planning Algorithms; Cambridge University Press: Cambridge, UK, 2006. [Google Scholar]
  47. Dorigo, M.; Maniezzo, V.; Colorni, A. Ant system: Optimization by a colony of cooperating agents. IEEE Trans. Syst. Man Cybern. Part B (Cybern.) 1996, 26, 29–41. [Google Scholar] [CrossRef]
  48. Larranaga, P.; Kuijpers, C.M.H.; Murga, R.H.; Inza, I.; Dizdarevic, S. Genetic algorithms for the travelling salesman problem: A review of representations and operators. Artif. Intell. Rev. 1999, 13, 129–170. [Google Scholar] [CrossRef]
  49. 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, Tsukuba, Japan, 8–9 November 1993; Volume 13, pp. 533–538. [Google Scholar]
  50. Hart, P.E.; Nilsson, N.J.; Raphael, B. A formal basis for the heuristic determination of minimum cost paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  51. Nash, A.; Daniel, K.; Koenig, S.; Felner, A. Theta*: Any-Angle Path Planning on Grids. In Proceedings of the AAAI Conference on Artificial Intelligence, Vancouver, BC, Canada, 22–26 July 2007; pp. 1177–1183. [Google Scholar]
  52. Fu, Y.; Ding, M.; Zhou, C.; Hu, H. Route planning for unmanned aerial vehicle (UAV) on the sea using hybrid differential evolution and quantum-behaved particle swarm optimization. IEEE Trans. Syst. Man Cybern. Syst. 2013, 43, 1451–1465. [Google Scholar] [CrossRef]
  53. Xu, A.; Viriyasuthee, C.; Rekleitis, I. Efficient complete coverage of a known arbitrary environment with applications to aerial operations. Auton. Robots 2014, 36, 365–381. [Google Scholar] [CrossRef]
  54. Torres, M.; Pelta, D.A.; Verdegay, J.L.; Torres, J.C. Coverage path planning with unmanned aerial vehicles for 3D terrain reconstruction. Expert Syst. Appl. 2016, 55, 441–451. [Google Scholar] [CrossRef]
  55. Majeed, A.; Lee, S. A Fast Global Flight Path Planning Algorithm Based on Space Circumscription and Sparse Visibility Graph for Unmanned Aerial Vehicle. Electronics 2018, 7, 375. [Google Scholar] [CrossRef]
Figure 1. Most widely used areas of interest decomposition techniques for coverage path planning.
Figure 1. Most widely used areas of interest decomposition techniques for coverage path planning.
Applsci 09 01470 g001
Figure 2. Conceptual overview of the proposed coverage flight path planning algorithm.
Figure 2. Conceptual overview of the proposed coverage flight path planning algorithm.
Applsci 09 01470 g002
Figure 3. Different obstacles’ intersections with the area of interest boundary.
Figure 3. Different obstacles’ intersections with the area of interest boundary.
Applsci 09 01470 g003
Figure 4. Overview of the enlarged obstacle by D s a f e value.
Figure 4. Overview of the enlarged obstacle by D s a f e value.
Applsci 09 01470 g004
Figure 5. Overview of the coverage path obatined through two different sweep directions.
Figure 5. Overview of the coverage path obatined through two different sweep directions.
Applsci 09 01470 g005
Figure 6. Overview of the sensor footprint on ground and footprint sweep in the AOI.
Figure 6. Overview of the sensor footprint on ground and footprint sweep in the AOI.
Applsci 09 01470 g006
Figure 7. Pictorial overview of the waypoint graph and Back and forth/Zamboni flight pattern.
Figure 7. Pictorial overview of the waypoint graph and Back and forth/Zamboni flight pattern.
Applsci 09 01470 g007
Figure 8. Coverage path planning results from two different types of the area of interest.
Figure 8. Coverage path planning results from two different types of the area of interest.
Applsci 09 01470 g008
Figure 9. Turns comparisons: proposed algorithm versus BCDH-CPP and CA-CPP algorithms.
Figure 9. Turns comparisons: proposed algorithm versus BCDH-CPP and CA-CPP algorithms.
Applsci 09 01470 g009
Figure 10. Footprints sweeps’ comparisons with existing algorithms.
Figure 10. Footprints sweeps’ comparisons with existing algorithms.
Applsci 09 01470 g010
Table 1. Proposed coverage path planning algorithm performance comparisons with the two existing algorithms.
Table 1. Proposed coverage path planning algorithm performance comparisons with the two existing algorithms.
Area of Intrest SizeBCDH-CPP Algorithm CA-CPP Algorithm Proposed-CPP Algorithm
Avg. Time (s)Avg. Length (m)Avg. Time (s)Avg. Length (m)Avg. Time (s)Avg. Length (m)
500 × 600 × 30013.538910.34 17.947901.12 10.548201.56
1000 × 1200 × 30018.4035,997.1122.8934,807.4515.6435,417.67
12,000 × 1400 × 30023.1955,920.1928.8155,429.1218.2953,120.09
1500 × 1500 × 40027.1372,995.2233.0972,810.2124.5471,030.42
2000 × 2000 × 40031.21124,991.1039.19123,951.1026.75122,367.15
Table 2. Path overlapping comparison between three algorithms for the same area of interest.
Table 2. Path overlapping comparison between three algorithms for the same area of interest.
AlgorithmsEvaluation CriteriaMaps Id
12345
CA-CPPAvg. path overlapping (m)129.59289.37990.451258.982039.51
BCDH-CPPAvg. path overlapping (m)209.21330.891023.071455.452237.98
ProposedAvg. path overlapping (m)171.09301.12810.951125.121927.45
Table 3. Proposed algorithm performance comparisons with varying shapes of the area of interest.
Table 3. Proposed algorithm performance comparisons with varying shapes of the area of interest.
AlgorithmsEvaluation CriteriaShape of the Area of Interest
SquareRectanglePolygon (Convex)Polygon (Non-Convex)Irregular
CA-CPPAvg. computing time (s)
Avg. path length (m)
Avg. path overlapping (m)
31.59
70,810.21
1153.40
15.84
8193.11
169.19
24.98
51,900.12
671.65
36.51
55,723.41
755.35
23.88
48,611.16
976.51
BCDH-CPPAvg. computing time (s)
Avg. path length (m)
Avg. path overlapping (m)
25.13
70,998.52
1365.23
11.85
8710.24
189.31
19.08
52,100.32
698.12
27.91
55,925.41
795.35
18.53
48,914.09
1001.31
ProposedAvg. computing time (s)
Avg. path length (m)
Avg. path overlapping (m)
19.55
68,730.42
1025.12
8.17
8001.96
161.99
14.78
50,300.32
621.34
18.91
54,605.21
705.15
13.43
47,410.89
954.21

Share and Cite

MDPI and ACS Style

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. https://doi.org/10.3390/app9071470

AMA Style

Majeed A, Lee S. A New Coverage Flight Path Planning Algorithm Based on Footprint Sweep Fitting for Unmanned Aerial Vehicle Navigation in Urban Environments. Applied Sciences. 2019; 9(7):1470. https://doi.org/10.3390/app9071470

Chicago/Turabian Style

Majeed, Abdul, and Sungchang Lee. 2019. "A New Coverage Flight Path Planning Algorithm Based on Footprint Sweep Fitting for Unmanned Aerial Vehicle Navigation in Urban Environments" Applied Sciences 9, no. 7: 1470. https://doi.org/10.3390/app9071470

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop