Content uploaded by Fotios Balampanis
Author content
All content in this area was uploaded by Fotios Balampanis on Oct 24, 2017
Content may be subject to copyright.
Area Decomposition, Partition and Coverage with Multiple Remotely Piloted
Aircraft Systems Operating in Coastal Regions
Fotios Balampanis, Ivan Maza and Anibal Ollero
Abstract— Several approaches can be identified in the liter-
ature for area decomposition: Grid based methods, Cellular
decomposition and Boustrophedon (or Morse) decomposition.
This paper proposes a novel discretization method for the
area based on computational geometry approaches. By using
aConstrained Delaunay Triangulation, a complex area is seg-
mented in cells which have the size of the projected field of
view of the RPAS (UAS) on-board sensor. In addition, costs
are associated to each of these cells for both partitioning
the area among several RPAS and full covering each sub-
area. Simulation results show that this approach manages to
optimally decompose and partition a complex area, and also
produces a graph that can be used for different cost-based
path planning methods.
Index Terms— Area decomposition, Area partition, Coverage
planning, Constrained Delaunay triangulation
I. INTRODUCTION
Area decomposition for path planning in robotics is a
widely researched subject in coverage and tracking tasks,
by formulating a path formation strategy in a given area. As
in many motion planning algorithms, two approaches can
be found: discrete and continuous search algorithms. Each
of these cases has trade-offs; complexity and optimality to
name a few. In discrete search domain, most of the research
divides the problem in two parts: Area segmentation and path
traversing through the segmented areas. This might look as
a simplistic description as there are numerous studies that
take into consideration variables such as energy consumption
[1], belief maps [2] or uncertainties in motion [3]. Still, this
reductionism is valid as all these variables are actually parts
of either the aforementioned processes. In our case and for
the reasons discussed below, a discrete, grid-like algorithm
for area segregation, and known algorithms combination for
path planning have been chosen.
The paper is organized as follows. A short introduction
including related work is presented in Sect. II, presenting
decomposition strategies and algorithms for path planning for
single or multiple RPAS. Section III introduces the reasons
for the approach followed in this paper, indicating coastal
area specific attributes. Section IV presents the computa-
tional geometry tools which are used for area segregation.
This work is partially supported by the MarineUAS Project funded by
the European Union’s Horizon 2020 research and innovation programme,
under the Marie Sklodowska-Curie grant agreement No 642153 and the
AEROMAIN DPI2014-C2-1-R Spanish project.
Fotios Balampanis, Ivan Maza and Anibal Ollero are with the Robotics,
Vision and Control Group, University of Seville, Avda. de los Descubrim-
ientos s/n, 41092, Sevilla, Spain. Email: fbalampanis@us.es, imaza@us.es,
aollero@us.es
Section V describes the cost/weight attribution algorithms
that are used for path related information propagation. In
Sect. VI, the two main tasks of full coverage and shortest
path are studied. Section VII presents the qualitative results
of the paper and Section VIII closes the paper with the
conclusions and future steps of our approach.
II. REL ATED WO RK
Most of the current approaches divide the path planning
problem in two parts. Initially an area decomposition strategy
is performed, reducing the complexity of the configuration
space or simplifying the area to be visited. In that manner,
the robotic agent has discrete states that can be reached by
choosing different actions. Different decisions are required
for tasks such as coverage or tracking, and cost-based path
planning algorithms can be applied for reaching each state.
Numerous studies have extended these algorithms for multi-
ple robots, swarms or distributed systems.
A. Area Decomposition
Regarding the decomposition process, the following ap-
proaches can be identified in the literature: Grid based meth-
ods, Cellular decomposition and Boustrophedon (or Morse)
decomposition.
In grid based methods, which are also referred as “reso-
lution complete methods” [4], the area partitioning is per-
formed by applying a grid overlay on top of the area. In that
way there is a discrete configuration space, where if all the
cells are visited, then a complete coverage is assumed. The
decomposition problem is somehow bypassed, as for areas
that are partially covered by the cells, the vehicle might not
cover them at all in order to avoid collisions, or will go over
them, ignoring the fact that they are obstacles (see Fig. 1).
The latter can be seen in [2], [5], where the RPAS flies over
cells that are partially inside the area of interest.
In [6] even though triangles are used for the area de-
composition as in the current study, the same problem is
still present. Changing the shape of the cells but arranging
them regardless of the area to be decomposed, the problem
of having cells which are partially outside the domain of
interest still remains. In general, all grid based methods tend
to “pixelate” the area, a strategy that does not properly solve
real world scenarios; areas do not have rectangular borders,
neither do their obstacles and no-fly zones. Galceran et al.
states in [4] that this problem can be solved by, locally
or globally, increasing the resolution of the grid, creating
smaller cells. This actually does not solve the problem in
Fig. 1. Problematic setup for grid decomposition methods. Should most
of the cells in the borders be visited? This can also occur with polygonal
borders.
Fig. 2. Complete coverage is not possible applying lawnmower motions.
Path is represented in black, the covered area in green and the areas out of
the field of view are shown in gray.
our case, since the size of the projected field of view of the
RPAS sensor should be considered. An exact decomposition
in cells which the vehicle can visit, increases computational
efficiency and ensures full coverage. If the cells are to
be smaller, there is no guarantee that a feasible path for
complete coverage can be produced.
In cellular decomposition, a non-convex polygon area is
decomposed into a collection of convex polygons. Even
though it manages to decompose complex areas, it does not
consider obstacles [7] within the area or it assumes that the
resulting cells will be covered by simple and coherent back
and forth lawnmower motion. This is not always the case as
it can be seen in Fig. 2.
In Boustrophedon decomposition [8] the problem of only
producing many convex polygons without holes has been
addressed. In this strategy and its derivatives, critical points
in the area are found and are used as crucial points in
order to divide the area in cells. Even though this method is
widely used, it still does not address the problem of covering
the whole area, as simple boustrophedon movements of the
vehicles might not be able to cover complex spaces, as it
was shown before in Fig. 2.
In almost all of the above cases, it can be noticed that the
surrounding area is rectangular and fairly simple. Also in
most of them a coverage by lawnmower paths is considered,
assuming that the vehicles will always be able to compensate
uncertainties in motion or external factors like wind drifts for
aerial vehicles, or surface anomalies for ground vehicles. As
it can be seen in Fig. 3, coastal areas are usually far from
simple, convex polygons.
B. Path Planning
Two main types of path planning algorithms can be found
in the literature: Those that perform complete coverage and
others that try to find the shortest path to fulfill a specific
goal. Another type is intended to create a path in order to
discover a target, but this can be considered as a combination
of the full coverage along with a weighted shortest path
case. In all these types, both continuous and the discrete
approaches can be found.
In order to cover an area, usually a back and forth motion
strategy is applied. This is either referred as “lawnmower
path”, “zigzag” or boustrophedon motion. Several derivatives
exist, including the minimization of turns [7], [9] and other
elaborated algorithms, especially when using grid segregated
areas. A musical Harmony approach [5] and fractal trajecto-
ries (using Hilbert curves) [10] are to name a few. There have
also been efforts for sensor-driven paths [11] in order for
the agent to increase the information gain from its sensors,
instead of trying to preplan a solution.
Many known algorithms have contributed to the shortest
path problem. Every cell of a segmented space is considered
as a node in a, usually, undirected graph [5]. The vertices
between these nodes might or might not have weights, which
describe the transition cost. In literature, cost or weights are
applied depending on e.g. the distance from the target or
from the information gain that might have [12].
C. Multiple vehicles
In this context, efforts have been made to extend the
solutions for multiple vehicles. Increase in computational
capabilities and simultaneous decrease of cost have allowed
the use of multi-vehicle systems to distribute the aforemen-
tioned computational burden. Acevedo et al. in [13]–[15]
have introduced a decentralized algorithm for surveillance
tasks which manages to propagate all task related information
between agents, considering the communication constrains
between them. Kassir et al. in [12] also takes into account
the communication resources that each of the agent has in
order to increase the information gain of the whole system.
Finally, in [2] Berger et al. propose a mixed-integer linear
programming formulation for discrete target searching for
multiple robots.
III. COAS TAL AR EAS
Applying algorithms in real world situations often means
that the application will highlight problems that have to
be globally addressed by the method. Instead of trying to
generalize a simple shape decomposition algorithm, in our
work it is assumed that coastal areas are complex. Their
borders have few straight lines, in many cases no-fly zones
exist (e.g. residential or commercial zones) and, as it is clear
Fig. 3. Salamina area in Greece. Numerous residential, commercial and
military regions in a 12 Km x 12 Km area. A complex shape is defined to
segment and cover.
in Fig. 3, it is requested to deal with non-convex polygons,
and numerous no-fly zones.
Coastal areas have distinguishable properties that permit
the use of additional constraints in the algorithmic formu-
lation. As starting point, in scenarios involving flights over
the sea, it is safe to assume that except obstacles and no-
fly zones, the remaining area is flat, having zero altitude.
Moreover, flying over the sea means that maintaining a
constant altitude, the field of view of a camera or in general
the footprint of a sensor, is always relatively stable. This
allows the segmentation of the area in a least sum of
footprint-sized cells to have a complete coverage.
IV. ARE A DECOMPOSITION
The aforementioned issues of complex areas and optimal
decomposition have been addressed in our work by applying
a refined constrained Delaunay polygon triangulation, creat-
ing a mesh of triangles, each one having its sides equal to
the size of the footprint of the RPAS. In that way, there is
no segmentation outside the area of interest and by visiting
all triangles it can be greedily assumed that the whole area
has been visited. From the implementation point of view, the
Constrained Delaunay Triangulation and mesh generation of
the CGAL library [16] have been used, introducing a top
limit of vertex side of each triangle: the footprint of the
RPAS(s) as in Fig. 4. As the triangles should be as much
homogeneous as possible, a lesser angle of 35 degrees is
tested.
A. Constrained Delaunay triangulation
Basic triangulation has no control on the resulting shape
[17] and produces skinny triangles having extreme angles. In
contrast, a Delaunay triangulation DT (P) is a collection of
triangles in which all points P={p1,p2, . . . , pm−1,pm}that
belong to Pare not inside the circumcircle of any triangle in
this set. This method, tends to maximize the minimum angle
of all the triangles in the triangulation, thus providing more
Fig. 4. Projected field of view of the sensor on-board. The largest side
is labelled as d, whereas wpdenotes the computed waypoint. Dashed line
shows the cell generated by the triangulation.
homogeneous triangles. Moreover, connecting the centers of
the circumcircles, produces a geometric dual of a Voronoi
diagram. A Constrained Delaunay Triangulation CDT (P)
introduces forced edge constraints which are part of the
input, and are useful in this paper as they actually define the
boundaries of the polygonal area. This can also be applied
for holes inside the polygon. By using this method a mesh
(grid) of regions of attribute is created.
B. Mesh
A mesh is a partition of an area into shapes which satisfy
several criteria. The mesh is defined as a graph of vertices
that can either be disjoint or share an edge. These vertices
can either be part of the boundary of an area or internal
constraints of the meshed region. In the CGAL library used
in the implementation, the user can define seed points that
either mark regions to be meshed or regions not to be
meshed. In the latter case, the whole constrained region is
initially triangulated but not meshed. The applied meshing
algorithm constantly inserts new vertices to the Delaunay
Triangulation as far as possible from the other vertices, and
stops when the refinement criteria are met. The algorithm
is guaranteed to terminate satisfying the requested criteria
“if all angles between incident segments of the input planar
straight line graph are greater than 60 degrees and if the
bound on the circumradius/edge ratio is greater than √2”
[18].
In order to perform these operations on the polygo-
nal coastal area, the Triangulation data structure along
with the Constrained Delaunay Triangulation operation, pro-
duce the Constrained Delaunay Triangulation Data structure
(C DTD S). It includes a collection of all the edges and
vertices of the triangulation as well as user defined attributes.
The Delaunay mesher (CDT M) of the CGAL library is
responsible for the refinement of the triangulation in order
for the mesh to be produced. Moreover, each produced facet
(cell) has also attributes, e.g its neighbors. It is possible to
include additional properties such as weights related to the
Fig. 5. Antagonizing wavefront propagation, partitioning an area as an
undirected graph. Starting from initial positions, numbered as 1, in each
iteration of the algorithm each node gets an agent ID (color coded) and a
step cost. Numbers indicate the absolute distance from the initial position
of the agent.
information gain, distance costs, etc. that are discussed in
the next section.
V. CO ST ATTRIBUTION
As it was previously stated, the whole region C, including
obstacles, is treated as a two dimensional configuration space
such that C=R2, where Cob s is the obstacles region and
Cf r e e =C\Cobs is the region where the vehicle can actually
move. By segregating Cf r ee for Mvehicles in a sum of cells
(ψ) such that
Cf r e e =
M
X
i=1
N
X
j=1
ψi j ,(1)
the motion planning problem can be reduced to a graph
search problem of Nnodes organized in the Constrained
Delaunay Triangulation Mesh (CDT M ). In each of the cells
of the segregated free space, it is possible to associate several
information attributes, also referred as weights or costs, that
are task specific, such as information gain, transition cost,
distance from the target, remaining fuel for the vehicle, etc.
In that manner, each node of the graph will contain area
and agent related information. By reducing the search space
of the input (cel l -sized information) and of the output (N
cells), computational complexity is also reduced. Moreover,
matching the vehicle’s footprint with the resolution chosen
for the area, a tight coupling is achieved between the position
of information in the configuration space C DT M and the
capabilities of the RPAS. Weight or cost depends on the
initial positions of the vehicles, the morphology of the area
as well as several information attributes that one might want
to include depending on the task to be executed by the RPAS.
In an initial step, a hop and transition cost computation
algorithm is applied. This algorithm is actually an antago-
nizing wavefront propagation implementation for calculat-
ing the number of steps from the initial positions Z=
{z1,z2, . . . , zM}of Mvehicles, to the borders of the con-
figuration space, getting from every current ψcell to all its
unvisited neighbors Qψ={qψ1,qψ2,qψ3}. A neighbor qof
a cell, is considered every cell that is adjacent to one of its
sides. As so, every cell has three neighbors. Antagonizing
Algorithm 1: Triangulation and hop cost algorithm. ψ
represents a cell, qdenotes a neighbor and Dcis the
current depth placeholder.
Data:C DT DS Constrained Delaunay Triangulated
Data Structure, C DT M ∈ Cf r ee Constrained
Delaunay Triangulation Mesh, ψZinitial
positions of agents
Result:C DT M with hop depth cost information,
SMconfiguration space for Magent,
Dhψhop depth information for each cell ψ,
Aψagent id for each cell ψ,
Bψbranch agent id for each cell ψ
initialization;
i←0;
Dc←1;
foreach ψZdo
Aψ←i;
Dhψ←Dc;
i←i+1;
end
i←0;
foreach q∈ψZdo
Bq←i;
i←i+1;
end
while all ψ∈C DT M are not visited do
Dc←Dc+1;
foreach ψ∈CDT D S do
if ψ∈C DT M AND ψha s De p t h =tr ue AND
Dhψ,DcAND ψi sV is it e d =f alse then
ψi sV is it e d ←true;
foreach q∈ψdo
if q∈C DT M AND qha s De p t h =f al se
then
Dhq ←Dc;
qha s De p t h ←tr ue;
qA←Aψ;
qB←Bψ;
end
end
end
end
end
means that each step of the cost-to-go operation is performed
breadth-first, resulting in partitioning the whole area in
separate configuration spaces for each RPAS. Consider the
sum of triangulated cells as an undirected graph, where every
cell has at most three child nodes; it’s neighbors. Then, each
RPAS is assigned a node as a starting position. In each step
of the algorithm, the children of the nodes visited in the
previous step, are given a increasing step cost (also referred
as hop cost) and are assigned the ID of the RPAS. Since a
node cannot be reassigned a RPAS ID or a new transition
cost, the whole area is partitioned in a uniform manner (see
Fig. 5). In this manner, each vehicle is assigned its own
configuration space S ⊂ Cf r e e such that for the M-th RPAS
SM=
N
X
j=1
ψM j +zM,(2)
which is distance-optimal to the rest. This operation also
facilitates coverage tasks as it segregates the whole space in
relatively equal partitions between the agents. This hop depth
cost Dhattribution is performed by using Algorithm 1, which
makes the depth assignment for Mactive vehicles, while it’s
iterations resemble a breadth-first search pattern.
Moreover, another step is performed to ease path planning
for shortest path to the targets. In the initial phase of the
algorithm, each of the three neighbors of the Zstarting cells,
is assigned a branch agent identifier Bso that for every
agent there are three qzneighbors of the initial position
zwith distinct identifiers. These identifiers are propagated
for each of the hops of the algorithm. Then, every cell in
the configuration space also includes an origin information
which acts as a kind of feedback planning. In that way, the
state space is limited for the next steps, when the search for
a goal facet is performed, as it will be described in the next
section.
Finally, in order to facilitate complete coverage of the area,
another algorithm is performed after the triangulation. A cell
ψNmight be adjacent to the borders of the area or to other
vehicles’ area. Thus, some of its Qψneighbors are either
outside of the domain or belong to another vehicle. For every
qψ<CDT M ∪SM, cell ψis given a large coverage depth cost
Dc. Every other cell that is adjacent to those ψcells, is given
a smaller cost and so on. In that way, a watershed information
schema is created by which all cells of the M-th RPAS in its
configuration space SMwill be visited, from the borders to
the core (see Fig. 6). Moreover, this cost attribution enables
the partitioning of the whole region, as the cells which have
the specific border cost indicate either borders of the area of
interest or borders between the vehicles. This computation
is described in Algorithm 2.
VI. PATH PLANNING
As it was mentioned before, two main path planning cases
can be distinguished. Covering the whole area and reaching
(or searching) a goal cell ψG. In order for the vehicles
to perform these actions, the centroid of each triangle is
considered as a waypoint for the path LM. By applying
discrete space path planning strategies, depending on the
cost/weight attributes of the mesh, a path is created. It
should be noticed that using this decomposition strategy and
cost attribution for path generation, RPAS kinematics and
waypoint to waypoint trajectory planning are not considered;
they are handled by the autopilot software and hardware,
as described in Section VII. The proposed solution assumes
complete coverage but not optimality in trajectory planning.
A. Coverage path planning
By using this kind of segmentation, complete coverage is
performed when every centroid of the configuration space
Algorithm 2: Complete coverage algorithm. ψrepresents
a cell and qdenotes a neighbor. On the other hand, Di
is the coverage depth iterator, Dsrepresents the smallest
coverage depth placeholder and Dgis the greatest cover-
age depth placeholder. A Vector is populated by the cells
closest to current one. Procedure sort sorts the items of
the vector, smallest (closest) first. Procedure pop returns
the first item in the vector.
Data:C DT DS Constrained Delaunay Triangulation
Data Structure, C DT M Constrained Delaunay
Triangulation mesh,
SMconfiguration space for M-th RPAS,
ψZinitial position of RPAS
Result:Dcψcoverage depth cost,
LMpath of the M-th RPAS
initialization;
Dg← ∞;
Di←Dg;
LM←ψZM;
foreach ψ∈CDT M do
if qψ<CDT M OR qψ<SMthen
Dcψ←Di
end
end
while all ψ∈C DT M are not visited do
foreach ψ∈CDT M do
if Dcqψ=Dithen
Dcψ←Di−1
end
end
Di←Di−1
end
Ds←Di
Di←Dg;
ψcu r r e nt ←ψZM;
while Di>Dsdo
foreach ψ∈CDT M do
if Dcψ=Dithen
dist ance ←calcDistance(ψ,ψc u r r en t )
pair ←makePair(ψ, di st ance)
V ect orcl o s e s tψ←pair
f ound ←true
end
end
sort(V ect orcl o s est ψ)
ψcu r r e nt ←pop(V ec torc l o ses t ψ)
LM←ψcu r r e nt
if f ound =f al se then
Di←Di−1
end
end
Fig. 6. Triangulation and mesh for three agents. White cells are the initial
positions for the vehicles. Red lines indicate the partitioned configuration
space for each agent. The green line indicates the coverage path for one
of them; it’s computed by taking advantage of the border-to-center cost,
indicated in different color shades.
of an agent is visited. Naturally, trying to find a path
where all the points are visited exactly once resembles
the travelling salesman problem. Taking advantage of the
watershed algorithm of the previous section, where every
cell that is close to a border is given a high coverage cost
whereas the cost is reduced for the internal cells, a graph of
distance cost from the edges of the domain and the other
vehicles is created. Starting from the initial cell ψZand
traversing to the nearest border cell, in every iteration of
the algorithm, all cells that have a specific depth cost are
visited and then the depth to be visited is decreased by
one. In each of these iterations, each next step is chosen
based on the distance from the current one and the closest
is selected, resembling a nearest neighbor algorithm (see
Algorithm 2). These iterations manage to create an inward
spiral path that covers the partitioned area (see Fig. 6),
creating relatively smooth trajectories, minimizing turns and
sudden heading changes. Once again, this procedure does not
guarantee optimality but complete coverage.
B. Cost based path planning
In a first step, the mesh is preprocessed without knowing
the target cell. Applying the hop cost attribution in every
facet of the triangulation permits the system to know which
initial branch of the graph has managed to reach the goal
cell, working as a kind of feedback planning. Each facet
has a reverse cost-to-go value, starting from the goal and
reaching the initial position. As it was stated before in the
jump cost part of the initial algorithm, a propagation of the
branch agent is performed. By decreasing the depth search
one step at a time, while remaining in the same branch
agent, the shortest cost-to-go path is found. Let us consider a
potential function φ(x) that tries to reduce the potential from
any cell to the goal cell inside the state space. In this case
this function tries to choose the action u(move to neighbor)
u=arg min
u∈U(x){φ(f(x,u))}(3)
of the current cell which is closer to the target and has the
same branch agent identifier. Since from every cell of this
branching agent, the goal is reachable, this potential function
is actually a navigation function. It is φ(x)=∞for every x
that belongs to another branch agent and for every state x∈
X/XGthe algorithm produces a state x0for which φ(x0)<
φ(x). This method is described in detail in Algorithm 3.
Algorithm 3: Shortest path algorithm. ψdenotes a cell
and qis a neighbor. On the other hand, Birepresents
the branch agent placeholder and Diis the hop depth
placeholder.
Data:C DT DS Constrained Delaunay Triangulation
Data Structure, C DT M Constrained Delaunay
Triangulation mesh,
ψZinitial position of the RPAS,
Dhψhop depth cost from Algorithm 1,
ψG M goal cell for the M-th RPAS,
Bψbranch agent id for each cell ψas in Algorithm 1.
Result:LMpath of the M-th RPAS
initialization;
Bi←BψGM
Di←DhψGM
ψcu r r e nt ←ψG M
LM←ψcu r r e nt
while Di>0do
Di←Di−1
foreach q∈ψcur r e n t do
if q∈C DT M AND Bq=BiAND Dhq =Di
then
dist ance ←calcDistance(q, ψZ)
pair ←makePair(q,dist ance)
V ect orcl o s e s tψ←pair
end
end
sort(V ect orcl o s est ψ)
ψcu r r e nt ←pop(V ec torc l o ses t ψ)
LM←ψcu r r e nt
end
VII. RES ULT S
In order to validate the algorithms and compare them with
other approaches for area segmentation and path planning, a
setup based on a SITL (Software In The Loop) simulation
environment has been used. The algorithms are implemented
in a ROS1(Robot Operating System) listener which visual-
izes the given area, the segmentation, the area of interest
for each RPAS and applies a color coding for visualizing
the depth information as well as the generated paths. The
1http://www.ros.org/
Fig. 7. System Architecture. Based on ROS, the system is highly modular
and can be integrated with current and future applications.
latter are transmitted in a form of a waypoint list at the SITL
instance of each of the vehicles, and each flight is monitored
by using a ground control station (qgroundcontrol2) which
receives emulated data from the Arduplane3autopilot soft-
ware. Arduplane is a fixed wing simulation instance of the
ardupilot software, emulating kinematics of a small RPAS
and physics of the environment.
A. System Configuration and Architecture
The system consists of an Intel Core i5-5200U@2.20GHz
CPU having 8GB of RAM and using the kUbuntu 14.04
distribution of the Linux OS. The latest CGAL library (4.7)
[19], ROS Indigo [20] (along with the rviz package for
visualization), Arduplane SITL and qgroundcontrol for the
qualitative validation of the flight have been used in our
implementation. Figure 7 shows the system architecture.
B. Qualitative results
A thorough testing of CGALs algorithm has been per-
formed, iterating through angle bound constrains for the
produced cells. Resulting meshes have been examined, ob-
taining information about triangle homogeneity. Regarding
path planning, two scenarios of coverage and shortest path
have been tested in order to obtain information about the
produced trajectories.
Area decomposition: A non concave polygon with an
internal no fly zone was used as it can be seen in Fig. 6. The
simulated shape is a 5km x 5km area, scaled down by a 1/10
factor for visualization and notation purposes. In most cases,
CGALs implementation of the triangulation has managed
to produce a mesh consisting of homogeneous triangles.
The triangulation and meshing functions were tested by
giving several input constrain criteria for the lesser angle
bound constrain of the produced triangles, as described in
2http://qgroundcontrol.org/
3http://ardupilot.com/
TABLE I
CONSTRAINED DEL AUNAY TRIANGULATION PERF OR MA NC E BAS ED O N
LOWER ANGLE BOUND CONSTRAINT.
Angle
bound (deg)
Vertices Cells Min edge
length (m)
Min angle
(deg)
0.011-8.88 304 476 10 25
9.16-10.02 305 478 10 25
12.31 313 488 10 29
15.29 321 500 9.43 31
16.15 325 508 8.24 32
17.01 357 568 6.32 32
18.16 377 597 6.32 34
Section IV. Produced vertices, total cells, minimum resulting
edge and minimum resulting angle are presented in Table I.
In all trials, the input criteria for the edge size has remained
the same; a predefined size for the RPASs footprint, as
defined in Fig. 4, of 25 meters (250 meters in the actual
area). It is noted that the sizes in these simulated shapes are
merely indicative and are chosen for visualization purposes
in the rviz node. It is also noted that reaching the upper angle
constrain limits of the Delaunay triangulation, an increased
number of sub-optimal cells were produced near the no fly
zone. Moreover, the algorithm could not proceed further than
the angle bound constraint of 18.9 degrees, a size which
is consistent to the one being referred to CGAL notes.
Nevertheless the footprint criteria is always met, as in all
produced triangles at least one side has the edge size input
constrain.
Coverage: Figure 6 shows the area to be segmented
by three agents. The path shown is the full coverage path
for the selected agent. Initially the shape has 21 vertices.
Performing the initial Delaunay triangulation, the shape was
segregated using 52 vertices. After the Constrained Delaunay
Triangulation, 305 vertices are present, forming 477 cells
(both inside and outside the domain of interest). The size of
the footprint for every RPAS, that was set as a constrain to
the input of the triangulation algorithm, was once again set
to 25 meters. For the RPAS shown, the area consisted of 153
cells with a biggest hop depth of 26 cells and 7 separate full
coverage depth zones. The computational time for the sum
of operations was 0.23 seconds.
Shortest Path: The same area and restrictions were
assumed for the shortest path task. The footprint input for
the triangulation was decreased to 20 meters (200 meters
in actual size) and the starter and goal cells were picked
at random but had not to be visible from each other (see
Fig. 8). Using the feedback planning strategy, the algorithm
managed not to reach a dead-end state. For the depicted
result, a slightly different approach was used. Every iteration
of the algorithm, considers part of the path every fourth
cell during computation. In that manner, a slightly smoother
trajectory is produced. For the path shown, the hop depth
was 44 cells whereas the target cell was in hop depth 41.
The computational time for the sum of operations was 0.19
seconds.
Fig. 8. Shortest path, pruning waypoints to produce a smoother trajectory.
White cell is the initial position of the RPAS whereas ’x’ marks the target
cell. In every four cells of the calculation, a new waypoint is introduced.
Coloring indicates the increasing distance to the target, depicting the
distance cost attributed by Algorithm 1. Figure also shows all the waypoints
produced by the triangulation algorithm.
TABLE II
SQUA RE G RI D AN D CONSTRAINED DEL AUNAY TRIANGULATION
DECOMPOSITION METHODS COMPARISON.
Footprint
Size (m)
Total cells
(square)
Total cells
(CDT)
Partial
coverage
(square)
15 331 1395 125
20 211 784 99
25 138 476 73
30 104 352 64
Comparison with other methods: The same shape that
was used for the simulated experiments has been segmented
by using a simple square grid decomposition strategy as in
the works that have been presented in [4]. A footprint size of
15, 20, 25 and 30 meters has been tested in order to observe
the amount of cells that partially cover the region of interest
by that method. Note that using the strategy presented by this
paper, there are no cells that partially cover an area, and the
waypoints produced are always in a path inside the domain.
Results in Fig. 9 show that even though this method manages
to produce a lesser amount of cells, it’s performance is highly
dependent on the shape of the area, the restricted zones as
also as the resolution of the footprint. Comparison of the
two methods in the 25 meters sized footprint as presented
in Table II, show that half of the produced cells share a
region outside the domain of interest, raising questions on
the restrictions that have to be applied in order to either visit
or not those specific cells.
VIII. CONCLUSIONS AND FUTURE WORK
A novel way of segmenting an area into cells that are
consistent with the capabilities of a system with multiple
RPAS has been presented. This segregation of the state
Fig. 9. Grid decomposition performance. In the 25 meters footprint case,
out of the 138 total cells that cover the area, 73 cells are partially inside
the domain of interest.
space can manage to decrease the complexity of information
propagation among several aircraft. In this architecture the
grid serves the role of a two dimensional information cloud,
containing attributes of the task to be performed.
Regarding kinematics, it is clear that this strategy can be
applied for holonomic vehicles that are able to turn instantly
and have the ability to hover, like multi-rotors. On the other
hand, non-holonomic vehicles like fixed wing RPASs have
some restrictions which depend on the speed of the RPAS
and the distance between the waypoints. There is a lower
limit in distance between waypoints for a non-holonomic
vehicle that can be reduced considering a waypoint visited
if the RPAS passed by an acceptable distance from it.
Nevertheless this is an application specific solution that is
not generic; in this study, these kind of strategies are dealt
by the autopilot software. Once again the goal of this paper is
to provide an optimal decomposition for complete coverage,
not to produce an optimal path and waypoint to waypoint
flight dynamics.
There are still numerous issues to be addressed and several
features to be introduced. At first, optimization techniques,
e.g Lloyd’s algorithm, can manage to produce even more
homogeneous meshes. Moreover, addition of ability-aware
segregation of space in order to reconfigure the domain
size of each vehicle is needed. This can be performed by
exchanging border cells between agents. Path planning issues
like segments produced outside the domain have to be solved
by tagging those cells beforehand and producing a path that
manages to either address them during the initial pass or
in the end. Moreover, several shortest path algorithms have
to be tested in order to improve the produced trajectories,
as current realization even though guarantees a non dead-
end path there is no pruning of states/waypoints to produce
smaller paths. Dynamic replanning in case a new obstacle is
present or information exchange between the RPAS are also
issues to be addressed. Finally, the proposed method will be
compared with several other segmentation methods, in order
to produce some performance metrics.
In the next research steps, real world experiments by
using fixed-wing vehicles will be executed. Ideally, the
system will be able to perform computations on-board each
aircraft. Moreover, introduction of uncertainty analysis for
flight trajectories and testing on how to compensate with
additional measures that either belong to known factors or
unexpected ones should be considered. Finally, our research
will introduce a proposal of a complete mixed discrete-
continuous decision architecture for heterogeneous systems
that are able to perform in coastal areas with minimal
supervision.
REFERENCES
[1] C. D. Franco and G. Buttazzo, “Energy-Aware Coverage Path
Planning of UAVs,” 2015 IEEE International Conference on
Autonomous Robot Systems and Competitions, pp. 111–117, 2015.
[Online]. Available: http://ieeexplore.ieee.org/lpdocs/epic03/wrapper.
htm?arnumber=7101619
[2] J. Berger and N. Lo, “An innovative multi-agent search-and-rescue
path planning approach,” Computers & Operations Research, vol. 53,
pp. 24–31, 2015. [Online]. Available: http://linkinghub.elsevier.com/
retrieve/pii/S0305054814001749
[3] S. Gade and A. Joshi, “Heterogeneous UAV swarm system for target
search in adversarial environment,” 2013 International Conference on
Control Communication and Computing, ICCC 2013, no. Iccc, pp.
358–363, 2013.
[4] E. Galceran and M. Carreras, “A survey on coverage path planning
for robotics,” Robotics and Autonomous Systems, vol. 61, no. 12,
pp. 1258–1276, 2013. [Online]. Available: http://dx.doi.org/10.1016/j.
robot.2013.09.004
[5] J. Valente, J. D. Cerro, A. Barrientos, and D. Sanz, “Aerial coverage
optimization in precision agriculture management: A musical harmony
inspired approach,” Computers and Electronics in Agriculture, vol. 99,
pp. 153–159, 2013.
[6] J. S. Oh, Y. H. Choi, J. B. Park, and Y. F. Zheng, “Complete coverage
navigation of cleaning robots using triangular-cell-based map,” IEEE
Transactions on Industrial Electronics, vol. 51, no. 3, pp. 718–726,
2004.
[7] Y. Li, H. Chen, M. Joo Er, and X. Wang, “Coverage path planning
for UAVs based on enhanced exact cellular decomposition method,”
Mechatronics, vol. 21, no. 5, pp. 876–885, 2011.
[8] H. Choset and P. Pignon, “Coverage Path Planning : The Boustrophe-
don Cellular Decomposition,” Autonomous Robots, vol. 9, no. 3, pp.
247–253, 1997.
[9] I. Maza and A. Ollero, Multiple UAV cooperative searching operation
using polygon area decomposition and efficient coverage algorithms,
ser. Distributed Autonomous Robotic Systems. Springer Verlag, 2007,
vol. 6, pp. 221–230. [Online]. Available: http://www.springerlink.
com/content/978-4- 431-35869- 5#section=288931&page=1&locus=0
[10] S. A. Sadat, J. Wawerla, and R. Vaughan, “Fractal Trajectories for
Online Non-Uniform Aerial Coverage,” pp. 2971–2976, 2015.
[11] L. Paull, C. Thibault, A. Nagaty, M. Seto, and H. Li, “Sensor-Driven
Area Coverage for an Autonomous Fixed-Wing Unmanned Aerial
Vehicle,” IEEE Transactions on Cybernetics, vol. PP, no. 99,
pp. 1–1, 2014. [Online]. Available: http://ieeexplore.ieee.org/lpdocs/
epic03/wrapper.htm?arnumber=6671976
[12] A. Kassir, R. Fitch, and S. Sukkarieh, “Communication-aware
information gathering with dynamic information flow,” International
Journal of Robotics Research, vol. 34, no. 2, pp. 173–200, 2015.
[Online]. Available: <GotoISI> ://WOS:000349144800003
[13] J. J. Acevedo, B. C. Arrue, J. M. Diaz-Bañez, I. Ventura, I. Maza,
and A. Ollero, “One-to-one coordination algorithm for decentralized
area partition in surveillance missions with a team of aerial robots,”
Journal of Intelligent and Robotic Systems: Theory and Applications,
vol. 74, no. 1-2, pp. 269–285, 2014.
[14] J. Acevedo, B. Arrue, J. Diaz-Banez, I. Ventura, I. Maza, and
A. Ollero, “Decentralized strategy to ensure information propagation
in area monitoring missions with a team of UAVs under limited
communications,” in Proceedings of the International Conference
on Unmanned Aircraft Systems (ICUAS 2013), 2013, pp. 565–574.
[Online]. Available: http://dx.doi.org/10.1109/ICUAS.2013.6564734
[15] J. Acevedo, B. Arrue, I. Maza, and A. Ollero, “Cooperative perimeter
surveillance with a team of mobile robots under communication
constraints,” in Proceedings of the IEEE/RSJ International Conference
on Intelligent Robots and Systems, Tokyo, Japan, 2013, pp. 5067–5072.
[Online]. Available: http://dx.doi.org/10.1109/IROS.2013.6697089
[16] L. Rineau, “2D conforming triangulations and meshes,” in CGAL
User and Reference Manual, 4.7 ed. CGAL Editorial Board,
2015. [Online]. Available: http://doc.cgal.org/4.7/Manual/packages.
html#PkgMesh2Summary
[17] J.-d. Boissonnat, O. Devillers, S. Pion, M. Teillaud, and M. Yvinec,
“Triangulations in CGAL,” Computational Geometry, vol. 22, no.
1-3, pp. 5–19, may 2002. [Online]. Available: http://linkinghub.
elsevier.com/retrieve/pii/S0925772101000542
[18] J. R. Shewchuk, “Delaunay refinement algorithms for triangular mesh
generation,” Computational Geometry, vol. 22, no. 1-3, pp. 21–
74, 2002. [Online]. Available: http://www.sciencedirect.com/science/
article/pii/S0925772101000475
[19] The CGAL Project, CGAL User and Reference Manual, 4.7 ed.
CGAL Editorial Board, 2015. [Online]. Available: http://doc.cgal.org/
4.7/Manual/packages.html
[20] M. Quigley, K. Conley, B. P. Gerkey, J. Faust, T. Foote, J. Leibs,
R. Wheeler, and A. Y. Ng, “ROS: an open-source Robot Operating
System,” in ICRA Workshop on Open Source Software, 2009.