Conference PaperPDF Available

Area decomposition, partition and coverage with multiple remotely piloted aircraft systems operating in coastal regions

Authors:

Abstract and Figures

Several approaches can be identified in the literature 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 a Constrained Delaunay Triangulation, a complex area is segmented 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 subarea. 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.
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, . . . , pm1,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;
i0;
Dc1;
foreach ψZdo
Aψi;
DhψDc;
ii+1;
end
i0;
foreach qψZdo
Bqi;
ii+1;
end
while all ψC DT M are not visited do
DcDc+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 qC DT M AND qha s De p t h =f al se
then
Dhq Dc;
qha s De p t h tr ue;
qAAψ;
qBBψ;
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← ∞;
DiDg;
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ψDi1
end
end
DiDi1
end
DsDi
DiDg;
ψ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
DiDi1
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
uU(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;
BiBψGM
DiDhψGM
ψcu r r e nt ψG M
LMψcu r r e nt
while Di>0do
DiDi1
foreach qψcur r e n t do
if qC 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.
... Some authors have already optimized path planning for general purposes (Balampanis et al., 2016(Balampanis et al., , 2017Raptis et al., 2023;Valente et al., 2013). However, they focus on nadir flights, which have some limitations in agricultural purposes such as disease monitoring and bunch detection. ...
Article
Full-text available
Grapevine phenotyping is the process of determining the physical properties (e.g., size, shape, and number) of grape bunches and berries. Grapevine phenotyping information provides valuable characteristics to monitor the sanitary status of the vine. Knowing the number and dimensions of bunches and berries at an early stage of development provides relevant information to the winegrowers about the yield to be harvested. However, the process of counting and measuring is usually done manually, which is laborious and time-consuming. Previous studies have attempted to implement bunch detection on red bunches in vineyards with leaf removal and surveys have been done using ground vehicles and handled cameras. However, Unmanned Aerial Vehicles (UAV) mounted with RGB cameras, along with computer vision techniques offer a cheap, robust, and timesaving alternative. Therefore, Multi-object tracking and segmentation (MOTS) is utilized in this study to determine the traits of individual white grape bunches and berries from RGB videos obtained from a UAV acquired over a commercial vineyard with a high density of leaves. To achieve this goal two datasets with labelled images and phenotyping measurements were created and made available in a public repository. PointTrack algorithm was used for detecting and tracking the grape bunches, and two instance segmentation algorithms - YOLACT and Spatial Embeddings - have been compared for finding the most suitable approach to detect berries. It was found that the detection performs adequately for cluster detection with a MODSA of 93.85. For tracking, the results were not sufficient when trained with 679 frames.This study provides an automated pipeline for the extraction of several grape phenotyping traits described by the International Organization of Vine and Wine (OIV) descriptors. The selected OIV descriptors are the bunch length, width, and shape (codes 202, 203, and 208, respectively) and the berry length, width, and shape (codes 220, 221, and 223, respectively). Lastly, the comparison regarding the number of detected berries per bunch indicated that Spatial Embeddings assessed berry counting more accurately (79.5%) than YOLACT (44.6%).
... Motion patterns such as back-and-forth [29], spiral or circular motions [30] are used to cover the area efficiently while considering factors such as energy consumption, time and distance, camera resolution and field of view to minimize overlap and recurrences. Some studies have used multiple UAVs [31,32] or mathematical probabilistic principles through integer linear programming [33] to optimize results and reduce completion time. ...
Article
Full-text available
This article presents a comprehensive review of the state-of-the-art applications and methodologies related to the use of unmanned aerial vehicles (UAVs) in the healthcare sector, with a particular focus on path planning. UAVs have gained remarkable attention in healthcare during the outbreak of COVID-19, and this study explores their potential as a viable option for medical transportation. The survey categorizes existing studies by mission type, challenges addressed, and performance metrics to provide a clearer picture of the path planning problems and potential directions for future research. It highlights the importance of addressing the path planning problem and the challenges that UAVs may face during their missions, including the UAV delivery range limitation, and discusses recent solutions in this field. The study concludes by encouraging researchers to conduct their studies in a realistic environment to reveal UAVs’ real potential, usability, and feasibility in the healthcare domain.
Article
Перспектива совмещения морской и железнодорожной инфраструктуры в прибрежной зоне Российской Арктики путем формирования универсальных перегрузочных комплексов на базе крупных морских портов Северного морского пути требует адекватного масштаба исследований экологических факторов, одним из которых является шумовое загрязнение прибрежной зоны. Суть проблемы заключается в сложности оценки параметров шумоизлучения, распространяемого действующими перегрузочными комплексами. Такая сложность обусловлена разнородностью шумоизлучения (совмещение потоков постоянного, переменного, импульсного и инфразвукового шума), неоднородностью и большой площадью шумового фона, что делает невозможным использование существующих методик оценки и нормирования шумозагрязнения. В этой связи возможным решением проблемы может стать структурная оптимизация шумоизлучения универсальных перегрузочных комплексов с разработкой программ локализации зон шумоизлучения для каждого конкретного случая на предварительных этапах проектирования. То есть, выбор лучшего с позиций близости к естественному уровню шума варианта структурного построения перегрузочного комплекса и исключения из рассмотрения экологически опасных вариантов. Авторами предложен подход к формализации механизма структурной оптимизации шумоизлучения универсальных перегрузочных комплексов на основе представления его в виде модели однокритериальной задачи выбора. The prospect of combining marine and railway infrastructure in the coastal zone of the Russian Arctic by forming universal transshipment complexes based on large seaports of the Northern Sea Route requires an adequate scale of research on environmental factors, one of which is noise pollution of the coastal zone. The essence of the problem lies in the complexity of estimating the parameters of noise emission propagated by operating overload complexes. This complexity is due to the heterogeneity of noise emission (the combination of streams of constant, alternating, pulsed and infrasound noise), heterogeneity and a large area of noise background, which makes it impossible to use existing methods for assessing and normalizing noise pollution. In this regard, a possible solution to the problem may be the structural optimization of noise emission of universal overload complexes with the development of programs for localization of noise emission zones for each specific case at the preliminary design stages. That is, the choice of the best option for the structural construction of the transshipment complex from the standpoint of proximity to the natural noise level and exclusion from consideration of environmentally hazardous options. The authors propose an approach to formalizing the mechanism of structural optimization of noise emission of universal overload complexes based on its representation as a model of a single-criteria selection problem.
Article
Выполнен анализ существующих методов исследования металлов в морской воде, включающий патентный поиск. Для проведения потенциостатических исследований зависимости потенциала судостроительных сталей от условий морской среды разработан комплекс для исследования электрохимического потенциала поверхностного слоя стали в условиях непрерывного погружения в модельный раствор морской воды и в районе переменной ватерлинии при катодной поляризации. Результаты эксперимента, проведенного с помощью разработанного комплекса, показали стабильность значения потенциала судостроительной стали вне зависимости от условий проведения опыта – в модельном растворе или во влажной среде с использованием пиафлора. Авторами были предложены основные технологические аспекты экспериментального исследования зависимости потенциала судостроительных сталей при катодной поляризации от различных условий морской среды (постоянное погружение, район переменной ватерлинии). An analysis of existing methods for researching metals in seawater was carried out, including a patent search. To conduct potentiostatic researches of the dependence of the potential of shipbuilding steels on the conditions of the marine environment, a complex was developed to study the electrochemical potential of the steel surface layer under conditions of continuous immersion in a model solution of seawater and in the area of the variable waterline during cathodic polarization. The results of the experiment conducted using the developed complex showed the stability of the value of the potential of shipbuilding steel regardless of the conditions of the experiment - in a model solution or in a humid environment using a piaflor. The authors proposed the main provisions of the methodology for researching the dependence of the shipbuilding steels potential under cathodic polarization on various conditions of the marine environment (constant immersion, variable waterline area).
Article
В статье показаны основные сложности борьбы с авариями и представлены основные пользователи системы поддержки принятия решения. Рассмотрены основные этапы, на которых программное обеспечение интеллектуальной системы поддержки принятия решения должно вырабатывать рекомендации при борьбе за живучесть судна, а также основные требования, которым оно должно удовлетворять. Представлено архитектурно-конструктивное построение судна для программного обеспечения и основные вопросы при тестировании программного обеспечения. Показан состав основных документов, необходимых для правильного функционирования программного обеспечения интеллектуальной системы поддержки принятия решения. Рассмотрены основные концептуальные модели, заложенные в программное обеспечение, такие как модели организационной системы, модели технических средств и средств борьбы за живучесть судна, модели объемно-пространственных сооружений, модели структурных элементов помещения и модели структурных элементов ограждающих конструкций. Показаны основные направления использования программного обеспечения. Приведен возможный перечень алгоритмов при борьбе с пожаром, при борьбе с водой и при борьбе за живучесть технических средств. The article shows the main difficulties in dealing with accidents while ensuring the operability of equipment complexes. The main users of the decision support system are presented. The main stages at which the software of the intelligent support and decision-making system should develop recommendations in the fight for the survivability of the vessel, as well as the main requirements that it must satisfy, are considered. The architectural and constructive construction of the vessel for software and the main issues in software testing are presented. The composition of the main documents necessary for the correct functioning of the system is shown, which contains the software of the intelligent support and decision-making system. The main conceptual models embedded in the software, such as models of the organizational system, models of technical means and means of fighting for the survivability of the vessel, models of three-dimensional structures, models of structural elements of the premises and models of structural elements of enclosing structures, are considered. The main directions of using the software are shown. A possible list of algorithms for fighting fire, fighting water and fighting for the damage of technical means is given.
Article
В работе рассматриваются вопросы построения системы мультиагентной сети автономного судовождения в порту Новороссийск. В исследовании решается задача безэкипажного судовождения и буксирного обеспечения в порту на основе мультиагентного подхода. В статье описывается система, состоящая из интеллектуального агента (швартуемое судно), группы смышлёных агентов, которыми являются статические навигационные точки, привязанные к причалу и существующим маякам и действительно интеллектуальных агентов – это буксиры-автоматы, которые имеют интеллектуальную управляющую систему. В состав интеллектуальной управляющей системы входят: сервер, инерциальная навигационная система, система спутниковой навигации и лазерная дальномерная система, обеспечивающая точное позиционирование каждого из буксиров относительно интеллектуального агента. Мультиагентная сеть решает задачу позиции каждого из участвующих в процессе автономного судовождения агентов (смышлёных, интеллектуальных, действительно интеллектуальных) по критериям минимума ошибок определения расстояний с триангуляцией по координатам спутниковой навигационной системы, с уточнением по счислениям лазерной дальномерной системы действительно интеллектуальных агентов. Учёт расстояний сближения между агентами и прохождение по заранее рассчитанной траектории производится в непрерывном режиме с коррекцией команд управления автономной навигационной системой. Критериями триангуляции принят алгоритм триангуляция Делоне, с проверкой соответствия противолежащих углов смежных треугольников. Целью исследования является разработка мультиагентной сети управления группой автономных морских подвижных объектов, которая определяет позиции других агентов относительно стационарных точек с использованием триангуляции Делоне в системе полярных координат. In the paper deals with the issues of building a multi-agent network of autonomous navigation in the port of Novorossiysk. A group of intelligent agents are static navigation points tied to the tip of the berths and existing lighthouses. By an intelligent agent we mean a moored vessel, controlled in the traditional way, on which there is a crew. Truly intelligent agents we consider automatic tugs that have a control system that includes a server, an inertial navigation system, a satellite navigation system and a laser ranging system that provides accurate positioning of each of the tugs relative to the intelligent agent. The autonomous navigation system considers the positions of each of the agents participating in the process of autonomous navigation (smart, intelligent, really intelligent) according to the criteria for the minimum errors in determining distances according to the calculated coordinates of the satellite navigation system, with refinement according to the reckoning of the laser ranging system of truly intelligent agents. Accounting for approach distances between agents, passing along a pre-calculated trajectory is carried out in a continuous mode with correction of commands to control the autonomous navigation system. Triangulation criteria adopted Delaunay triangulation, with checking the correspondence of opposite angles of adjacent triangles. Operational control of a multi-agent system occurs in a local polar coordinate system built on a network of intelligent agents. The aim of the study is to develop a methodology for a multi-agent control network for a group of autonomous marine mobile objects, which determines the positions of other agents relative to stationary points using Delaunay triangulation in the polar coordinate system.
Article
В статье рассмотрена проблема выбора узла автоматизированного швартовного устройства при внедрении МАНС во время выполнения морских операций. Описано преимущество электромагнитных решений перед вакуумными устройствами, путём построения графика зависимостей тягового усилия, от общего коэффициента усилия, благодаря которому было выявлено, что при относительно равных исходных данных тяговое усилие в магнитных системах на 200-300% эффективней вакуумных устройств. Были разработаны в виртуальной среде моделирования экспериментальные модели для оценки конструктивных особенностей как единично, так и в рамках пластины, на которой размещено 12-ть узлов. Модели были испытаны разными значениями нагрузок с имитацией оттяжки и прижима для получения спектральных карт с целью анализа распределения напряжения, тепла и прочих физических параметров. По результатам имитационного моделирования установлено, что узел с электрически-управляемым постоянным магнитом (ЭУПМ) а также с электромагнитом являются необходимым решением для выполнения задач швартовки. Проведено исследование прочности пластины, итогом которого стал вывод, что основную нагрузку на себе несет конструкция швартовного устройства. The article considers the problem of choosing a node of an automated mooring device when introducing MASS during offshore operations. The advantage of electromagnetic solutions over vacuum devices is described by plotting the dependence of traction force on the total force coefficient, due to which it was found that with relatively equal initial data, traction force in magnetic systems is 200-300% more efficient than vacuum devices. Experimental models were developed in a virtual simulation environment to evaluate design features both individually and within a plate on which 12 nodes are placed. The models were tested with different load values, simulating pulling and pressing, to obtain spectral maps in order to analyze the distribution of stress, heat and other physical parameters. According to the results of simulation modeling, it was found that an assembly with an electrically controlled permanent magnet (ECPM) as well as an electromagnet is a necessary solution for performing mooring tasks. A study of the strength of the section was carried out, the result of which was the conclusion that the main load is borne by the design of the mooring device.
Article
В статье обоснована необходимость дополнительного учета требований жизненного цикла проектируемых систем разработчиками продукции в дополнение к традиционным параметрам контроля. На сегодняшний день актуальной является задача создания автономной, информационной системы проектирования и технического обслуживания судовых установок, в рамках которой можно было бы собирать, систематизировать, анализировать и управлять всей информацией о моделируемых системах, особенностях их эксплуатации для поддержки принятия решений. В статье рассмотрены особенности построения распределенных информационных систем с нечеткой кластеризацией для проектирования и контроля за эксплуатацией судового двигателя. Для формализации этого процесса необходимо разработать распределенную информационную систему судового двигателя, узлы которой смогут одновременно функционировать в пределах рабочего пространства, - так называемого, подхода нечеткой кластеризации относительно способа проектирования, с нахождением нового знания о двигателе с высокоэффективными показателями эксплуатации. Основу этой системы составляет блочно-модульный принцип построения. Модули системы будут опираться на математические модели разного уровня сложности и иерархии. Отдельный акцент сделан на необходимости использования блочно-модульного принципа построения информационных систем и применения математических моделей, которые должны удовлетворять критериям дивергенции, трансформации и конвергенции. The article substantiates the need for additional consideration of the requirements of the life cycle of designed systems by product developers in addition to the traditional control parameters. To date, the task of creating an autonomous, information system for the design and maintenance of ship installations, within which it would be possible to collect, systematize, analyze and manage all information about the simulated systems, the features of their operation to support decision making, is relevant. The article discusses the features of building distributed information systems with fuzzy clustering for designing and monitoring the operation of a marine engine. To formalize this process, it is necessary to develop a distributed information system of a marine engine, the nodes of which can simultaneously operate within the working space, the so-called fuzzy clustering approach regarding the design method, with finding new knowledge about the engine with highly efficient operation indicators. The basis of this system is the block-modular construction principle. The modules of the system will be based on mathematical models of different levels of complexity and hierarchy. A separate emphasis is placed on the need to use the block-modular principle of building information systems and the use of mathematical models that must meet the criteria of divergence, transformation and convergence.
Article
В статье рассматриваются вопросы обеспечения эксплуатационной надёжности серверного комплекса судовой автоматической навигационной системы в аспекте внедрения концепции a-Navigation. Предложена математическая модель оценки влияния качества контроля технического состояния рассматриваемого оборудования на комплексный показатель его эксплуатационной надежности (коэффициент готовности), с учетом структурного резервирования и неидеальности функционирования средств контроля. Разработан граф состояний рассматриваемой сложной технической системы, предложена аналитическая модель оценивания показателей готовности отказоустойчивой вычислительной системы автономного судна и c применением программной среды MathCAD построены зависимости коэффициента готовности резервированной системы от метрологических характеристик (ошибок контроля первого и второго рада) применяемых средств контроля технического состояния. Также показано существенное влияние качества функционирования встроенных систем контроля оборудования МАНС на его надежность и безопасность мореплавания в целом. The article deals with the issues of ensuring the operational reliability of the server complex of the ship's automatic navigation system in the aspect of the implementation of the a-Navigation concept. A mathematical model is proposed for assessing the influence of the quality of monitoring the technical condition of the equipment under consideration on a complex indicator of its operational reliability (availability factor), taking into account structural redundancy and non-ideal functioning of control facilities. A graph of the states of the considered complex technical system has been developed, an analytical model for estimating the readiness indicators of a fault-tolerant computing system of an autonomous vessel has been proposed, and using the MathCAD software environment, dependences of the redundant system availability factor on the metrological characteristics (control errors of the first and second range) of the technical condition control means used have been constructed. It also shows a significant impact of the quality of functioning of the built-in control systems of the MASS equipment on its reliability and safety of navigation in general.
Article
В данной работе рассматривается автоматический обнаружитель шумового сигнала движущегося источника шумоизлучения, работающий непрерывно во времени и переходящий в режим обнаружения, когда источник входит в телесный угол главного максимума характеристики направленности приемной антенны. Обнаружитель содержит индикаторное устройство, состоящее из двух последовательно включенных селекторов сигнала: первого – по уровню, второго – по длительности. Получена вероятностная характеристика обнаружения сигнала в виде зависимости вероятности обнаружения от отношения сигнал/помеха на выходе приёмного тракта. Выполнен анализ влияния движения источника сигнала на параметры вероятностной характеристики и обосновано упрощение её выражения при обнаружении слабого сигнала. Введено понятие "аппаратная" чувствительность обнаружителя как пороговое отношение сигнал/помеха по мощности на выходе приёмного тракта. Введён количественный критерий режима обнаружения слабого сигнала и предложена упрощённая методика оценки аппаратной чувствительности в этом случае. Показана прямая зависимость аппаратной чувствительности от эквивалентной относительной длительности проходной характеристики источника по выходу приёмного тракта. This article considers an automatic detector of a noise signal from a moving source, which operates continuously in time and switches to the detection mode when the source enters to the solid angle of the main directivity beam of the receiver’s antenna. The detector contains an indicator block consisting of two signal selectors connected one after another: the first one by level, the second one by time. The probabilistic characteristic of detection signal from a moving noise source in the form depended on the detection probability and the signal-to-noise ratio at the receiver’s output is proposed. Also we have done the influence analysis of the signal source motion on the probabilistic characteristic parameters, and as particular result the simplification is proposed for the weak signals case. The concept of detector’s "system" sensitivity is introduced as a threshold signal-to-noise ratio in terms of power at the receiver’s output. A quantitative criterion of the weak signal detection mode is introduced and a simplified method for evaluating system sensitivity for this case is proposed. The direct dependence of the system sensitivity on the equivalent relative duration of the receiver’s transmission characteristic is shown.
Conference Paper
Full-text available
Coverage path planning is the operation of finding a path that covers all the points of a specific area. Thanks to the recent advances of hardware technology, Unmanned Aerial Vehicles (UAVs) are starting to be used for photogrammetric sensing of large areas in several application domains, such as agriculture, rescuing, and surveillance. However, most of the research focused on finding the optimal path taking only geometrical constraints into account, without considering the peculiar features of the robot, like available energy, weight, maximum speed, sensor resolution, etc. This paper proposes an energy-aware path planning algorithm that minimizes energy consumption while satisfying a set of other requirements, such as coverage and resolution. The algorithm is based on an energy model derived from real measurements. Finally, the proposed approach is validated through a set of experiments.
Article
We propose a novel method for non-uniform terrain coverage using Unmanned aerial vehicles (UAVs). The existing methods for coverage path planning consider a uniformly interesting target area and hence all the regions are covered with high resolution. However in many real world applications items of interest are not uniformly distributed but form patches of locally high interest. Therefore, with sparse sampling of uninteresting sections of the environment and high resolution sampling of interesting patches, the trajectory of the robot can become shorter. In this paper, we present a novel coverage strategy based on Space-Filling Curves that can accomplish non-uniform coverage of regions in the target area. Simulations and real robot experiments indicate that with the new strategy, travel time / cost of the task can be (almost) always less than a regular 'lawnmower' coverage pattern.
Article
Delaunay refinement is a technique for generating unstructured meshes of triangles for use in interpolation, the finite element method, and the finite volume method. In theory and practice, meshes produced by Delaunay refinement satisfy guaranteed bounds on angles, edge lengths, the number of triangles, and the grading of triangles from small to large sizes. This article presents an intuitive framework for analyzing Delaunay refinement algorithms that unifies the pioneering mesh generation algorithms of L. Paul Chew and Jim Ruppert, improves the algorithms in several minor ways, and most importantly, helps to solve the difficult problem of meshing nonmanifold domains with small angles. Although small angles inherent in the input geometry cannot be removed, one would like to triangulate a domain without creating any new small angles. Unfortunately, this problem is not always soluble. A compromise is necessary. A Delaunay refinement algorithm is presented that can create a mesh in which most angles are 30° or greater and no angle is smaller than arcsin[(V3/2) sin(</>/2)] ~ (\/3/4)0, where (p , 60° is the smallest angle separating two segments of the input domain. New angles smaller than 30° appear only near input angles smaller j than 60°. In practice, the algorithm's performance is better than these bounds suggest. ! Another new result is that Ruppert's analysis technique can be used to reanalyze one of Chew's algorithms. Chew proved that his algorithm produces no angle smaller than 30° (barring small input angles), but without ; any guarantees on grading or number of triangles. He conjectures that his algorithm offers such guarantees. His j conjecture is conditionally confirmed here: if the angle bound is relaxed to less than 26.5°, Chew's algorithm produces meshes (of domains without small input angles) that are nicely graded and size-optimal.
Article
We are interested in the problem of how to improve estimation in multi-robot information gathering systems by actively controlling the rate of communication between robots. Communication is essential in such systems for decentralized data fusion and decision-making, but wireless networks impose capacity constraints that are frequently overlooked. In order to make efficient use of available capacity, it is necessary to consider a fundamental trade-off between communication cost, computation cost and information value. We introduce a new problem, dynamic information flow, that formalizes this trade-off in terms of decentralized constrained optimization. We propose algorithms that dynamically adjust the data rate of each communication link to maximize an information gain metric subject to constraints on communication and computation resources. The metric is balanced against the communication resources required to transmit data and the computation cost of processing sensor data to form observations. The optimization process selectively routes raw sensor data or processed observation data to zero, one or many robots. Our algorithms therefore allow large systems with many different types of sensors and computational resources to maximize information gain performance while satisfying realistic communication constraints. We also present experimental results with multiple ground robots and multiple sensor types that demonstrate the benefit of dynamic information flow in comparison to simpler bandwidth-limiting methods.
Conference Paper
Unmanned Aerial Systems (UAS) have great potential to aid in search and situation assessment. Here, we present a UAV swarm system performing target search in adversarial environment. It utilizes a Ant-Colony (ACO) and Artificial Potential Function (APF) based decentralised target search strategy. ACO meta-heuristic forms the higher level guidance algorithm and APF provide global and local path planning. Uncertainty maps are used to represent probable target locations. The algorithm is scalable and is shown to be robust to agent loss. Its distributed nature makes it ideal for applications in large scale search operations. Trajectory estimates are factored into prioritization resulting into better target selection and faster search.
Article
Search and rescue path planning is known to be computationally hard, and most techniques developed to solve practical size problems have been unsuccessful to estimate an optimality gap. A mixed-integer linear programming (MIP) formulation is proposed to optimally solve the multi-agent discrete search and rescue (SAR) path planning problem, maximizing cumulative probability of success in detecting a target. It extends a single agent decision model to a multi-agent setting capturing anticipated feedback information resulting from possible observation outcomes during projected path execution while expanding possible agent actions to all possible neighboring move directions, considerably augmenting computational complexity. A network representation is further exploited to alleviate problem modeling, constraint specification, and speed-up computation. The proposed MIP approach uses CPLEX problem-solving technology in promptly providing near-optimal solutions for realistic problems, while offering a robust upper bound derived from Lagrangean integrality constraint relaxation. Modeling extension to a closed-loop environment to incorporate real-time action outcomes over a receding time horizon can even be envisioned given acceptable run-time performance. A generalized parameter-driven objective function is then proposed and discussed to suitably define a variety of user-defined objectives. Computational results reporting the performance of the approach clearly show its value.
Article
Area coverage with an onboard sensor is an important task for an unmanned aerial vehicle (UAV) with many applications. Autonomous fixed-wing UAVs are more appropriate for larger scale area surveying since they can cover ground more quickly. However, their non-holonomic dynamics and susceptibility to disturbances make sensor coverage a challenging task. Most previous approaches to area coverage planning are offline and assume that the UAV can follow the planned trajectory exactly. In this paper, this restriction is removed as the aircraft maintains a coverage map based on its actual pose trajectory and makes control decisions based on that map. The aircraft is able to plan paths in situ based on sensor data and an accurate model of the on-board camera used for coverage. An information theoretic approach is used that selects desired headings that maximize the expected information gain over the coverage map. In addition, the branch entropy concept previously developed for autonomous underwater vehicles is extended to UAVs and ensures that the vehicle is able to achieve its global coverage mission. The coverage map over the workspace uses the projective camera model and compares the expected area of the target on the ground and the actual area covered on the ground by each pixel in the image. The camera is mounted on a two-axis gimbal and can either be stabilized or optimized for maximal coverage. Hardware-in-the-loop simulation results and real hardware implementation on a fixed-wing UAV show the effectiveness of the approach. By including the already developed automatic takeoff and landing capabilities, we now have a fully automated and robust platform for performing aerial imagery surveys.
Conference Paper
This paper presents the decentralized strategy followed to ensure information propagation in area monitoring missions with a fleet of heterogeneous UAVs with limited communication range. The goal of the team is to detect pollution sources over a large area as soon as possible. Hence the elapsed time between two consecutive visits should be minimized. On the other hand, in order to exploit the capabilities derived from having a fleet of UAVs, an efficient area partition is performed in a distributed manner using a one-to-one coordination schema according to the limited communication ranges. Another requirement is to have the whole team informed about the location of the new pollution sources detected. This requirement is challenging because the communication range of the vehicles is small compared to the area covered in the mission. Sufficient and necessary conditions are provided to guarantee one-to-one UAV communication in grid-shape area partitions, allowing to share any new information among all the members of the team, even under strong communication constraints. The proposed decentralized strategy has been simulated to confirm that fulfils all the goals and requirements and has been also compared to other patrolling strategies.
Conference Paper
This paper presents the perimeter surveillance problem using a set of cooperative robots with heterogeneous speed capabilities under communication constraints. The problem is solved using a frequency-based approach. In the proposed path-partition strategy, the robots patrol a segment length related to their own capabilities and interchanges information with its neighbors periodically. An efficient decentralized algorithm is applied to coordinate the robots from local information and decisions. Finally, simulation and experimental results are presented to illustrate the convergence and the robustness of the solution.