Download PDF - WordPress.com

Survey
yes no Was this document useful for you?
   Thank you for your participation!

* Your assessment is very important for improving the workof artificial intelligence, which forms the content of this project

Document related concepts

Computational phylogenetics wikipedia , lookup

Corecursion wikipedia , lookup

Artificial intelligence wikipedia , lookup

Algorithm characterizations wikipedia , lookup

Factorization of polynomials over finite fields wikipedia , lookup

Algorithm wikipedia , lookup

Travelling salesman problem wikipedia , lookup

Signal-flow graph wikipedia , lookup

Transcript
MULTI-ROBOT COVERAGE PATH PLANNING FOR SEARCH AND
SECURE PROBLEM IN A POLYGONAL ENVIRONMENT
Saad Shaikh1 and Dr. Kunwar Faraz Ahmad Khan2
Mechatronics Engineering Department, College of EME, National University of Sciences and
Technology (NUST), Islamabad, Pakistan.
1
ssaad.shaikh87@gmail.com
2
kfaraz@gmail.com
Abstract
In this paper, we study the visibility-based search and secure problem, in which multiple robots move
through a simply connected and known polygonal environment such that they guarantee the detection
of all contaminants or intruders within, that can move arbitrarily fast. Our objective is to investigate
the usefulness of the GRAPH-CLEAR methodology for analytical modeling of this problem and
develop a strategy for an uncoordinated search to accomplish this task, targeting application domains
such as securing buildings for surveillance and security purposes. The aim is neither to take care of
the actual control system of the robots, nor to handle the actual detection of an intruder (through video
or image processing); rather introduce an effective coverage path planning strategy to identify the
paths the robots are required to follow. To this end, we present an algorithm to compute the strategy
required, using the concept of searcher and blocker robots/agents. The algorithm models the given
environment in the form of a connectivity graph and then converts it into a tree, calculating the
number of robots and the trajectories these robots have to follow in order to secure the complete
environment. We show how the strategy devised by this algorithm is more time and cost efficient by
performing simulations and comparing the results against methods already being used, giving
examples of different computed trajectories. For a particular case study, the results of the algorithm
show an approximately 1/4th increase in time efficiency along with a 1/3rd reduction in the robot
resources required.
Keywords: search and secure, graph-clear, coverage path planning, searchers and blockers
1. Introduction
Search and surveillance of large areas such as banks, airports etc is a major field of application and a
renowned research area in multi-robot systems. As the security concerns of the world are growing, so
are the advancements in multi-robot search systems. Teams of multiple robots are often required to
survey vast environments, and even though sensor networks are more often deployed in real world
applications, multi-robot teams are paramount for searching and securing an area previously not
equipped with sensors. Furthermore, mobile robots offer moving sensing capability, which has its
advantages over deploying static sensor networks. In this paper, we investigate a technique of
effectively deploying a team of such robots to detect any and all intruders or contaminants present in a
known environment.
The objective is to develop an improved strategy to accomplish the search and secure task identifying
the paths or trajectories of multiple robots for an uncoordinated search to clear large search areas. The
GRAPH-CLEAR graph theoretic problem is used for this purpose, which primarily requires finding
the minimum number of robots required to detect all possible intruders in an environment modeled as
a graph (Kolling & Carpin, 2007). The GRAPH-CLEAR methodology was selected because it is NPcomplete and can be solved with linear complexity on trees formed from undirected graphs (Kolling
& Carpin, 2007). It is simpler and flexible regarding the strategies used in different steps of the
algorithm and an efficient strategy for solving the search and secure problem.
In order to search an environment that consists of obstacles and free area, it is divided into triangles
using Delaunay Triangulation, which are then merged to form convex regions that form a connectivity
graph. The number of robots required are calculated to search this graph and each robot is assigned a
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
54
particular role i.e. either a robot is declared a searcher robot or a blocker robot. The concept of
searcher and blocker robots discussed by Katsilieris (2009) identifies blocker robots as agents that are
used to break the cyclic paths in any graph, thus converting it into a tree, and searcher robots are
agents that search the tree for multiple intruders.
2. Related Research
Visibility-based search and patrol problems have been targeted by a large section of the robotics
community, developing and refining different strategies for area coverage. Search techniques such as
the cyclic strategy is discussed by Elmaliach, Agmon and Kaminka (2007) which involves identifying
the whole area to be explored and obstacles present in it as a set of vertices. The search path formed
by joining the vertices is termed as "Hamilton Path", and if a cyclic patrol is established, the cycle is
known as "Hamilton Cycle" (Bondy & Monty, 1976). But this technique is viable only for static
object searching, securing, and patrolling, but does not have the requisite properties to serve as a
search, secure, and decontaminate technique for a dynamic intelligent intruder. Marker-based
strategies are aimed at exploration and employ deployment of tags to identify areas which have
already been explored by one of the robots in the team, as identified by Batalin and Sukhatme (2002):
"A robot explores as long as there are open regions left. If all the regions are explored, then the robot
picks the direction which was least recently explored". In this case, an intelligent dynamic intruder
may easily observe the navigation path of the robots and find a pattern to identify unobserved regions
in the area at any given time, using them to avoid detection. Communication based strategies such as
goal sharing and state sharing are discussed by Sgorbissa & Arkin (2003) but they require
communication between robots and as such are more complex. Partitioning strategies are based on
resolving the known area of a map into independent segments, which are then assigned to different
robots for exploration and monitoring. This has been observed to reduce the exploration time for
unknown areas of the map significantly (Wurm, Stachniss & Burgard, 2008). Hence, the partitioning
based strategy is followed for segmentation of the environment into smaller regions and then using
blocker and searcher robots to secure those regions.
The blocker and searcher placement algorithm is based on furthering the partitioning strategy. A
popular segmentation technique is triangulation, and the environment is partitioned using Delaunay
Triangulation. Combining triangulated regions to form convex polygons, and then joining the centers
of adjacent regions results in the Voronoi diagram (Portugal, 2009). This diagram is used to identify
cycles present in the graph and locate suitable blockers positions and searcher paths. Optimal
partitioning and merging techniques are being developed (Kolling & Carpin, 2007), which are the
focus of this paper as well, since an improved partitioning strategy results in a simpler search tree and
reduced number of robots.
The algorithm discussed by Katsilieris (2009) forwards this method to develop a strategy for
deploying searcher and blocker robots. In this strategy, all robots are mutually independent and the
search is uncoordinated. The environment is segmented using Delaunay triangulation since it avoids
formation of triangles with very acute angles. These triangles are merged only once with their
adjacent triangle(s) keeping in consideration that the merged region formed is a convex region i.e. a
region in which no inner angle is greater than 180 degrees. The use of convex regions implies that any
point within the region is visible from any other point inside the same region. Joining the centroids of
adjacent regions forms a regions graph. This graph is then converted into a Minimum Spanning Tree
(MST) by identifying points (called cover nodes) where the cycles in the graph are to be broken. The
cycles are broken through placing blocker robots and the remaining regions are searched through
searchers. This is shown using results involving practical experiments. This algorithm is well suited to
the search and secure algorithm but it can be improved by implementing a better merging strategy and
optimizing the time each robot takes to reach its final position.
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
55
3. Problem Description
The problem at hand involved the complete search and surveillance of a known environment. The
targeted environment, shown in Figure 1, consisted of nine obstacles enclosed within a boundary; the
area other than obstacles is the free area needed to be searched where robots (or intruders) could
move.
Figure 1: Environment Map (obstacles, boundary and free area)
The environment was modeled in the form of structures as:
where Sboundary = [Vbound , Ebound] such that Vbound are the vertices and Ebound are the edges of the
boundary. Similarly, S_obsi = [V_obsi , E_obsi] such that V_obsi are the vertices and E_obsi are the
edges between these vertices for the i-th obstacle, where i = 1 to no. of obstacles.
The environment, modeled in the aforementioned structures, was to be searched and secured such that
the whole free area was surveyed and all possible intruders present were detected with optimal
number of robots and within minimum time. The aim of this research was not the sensing itself, but to
develop a navigation algorithm, which could be coupled with independent robot sensory control,
processing, and feedback algorithms.
4. Method and Analytical Modeling
The method employed is based on the partitioning strategy and GRAPH-CLEAR methodology. It is
generalized and discussed in the following sub-sections.
4.1. Triangulation and Merging
The free area in the environment (as shown in Figure 1) was partitioned by triangulation. Initially a
basic triangulation was formed by sequentially adding points to a seed triangle. This triangulation was
formed on the basis of visibility. Let Striangle be the set of all triangles thus formed, where each triangle
is a set of three vertices and the edges between them that form the triangle. This triangulation was
analyzed according to the Empty Circle Property for Delaunay Triangulation and Lawson Flip
Algorithm (Gartner & Hoffmann, 2013) to convert it into a Delaunay Triangulation. The reason for
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
56
using Delaunay Triangulation technique rather than Voronoi diagrams was that it produces 10% less
errors than those produced by Voronoi diagram construction directly (Barclay & Galton, 2008). A
triangles graph was formed by connecting the centroids of adjacent triangles:
where
are the coordinates of the centroids of triangles and the edges between them.
represents the adjacency matrix for the triangulation.
These triangles were merged to form convex polygonal regions. Convex regions were formed so that
every point within the region has visibility of every other point in the same region and hence any
robot would be able to survey the complete region from a single point. This is shown in Figure 2.
Figure 2: a) Convex region - all points visible to each other b) Non-convex region - A not visible to B
Let Sregion be the structure that consists of all the corners and edges forming the regions. The algorithm
maximized the merging strategy such that the triangles merged to form regions were further checked
with other adjacent triangles for merging into larger convex regions. An undirected regions graph was
formed by connecting the centroids of adjacent regions:
where
between them.
are the coordinates of the centroids of regions (nodes of the regions graph) and edges
represents the adjacency matrix for the merged regions.
4.2. Blocker Positions and Tree Formation (RMST)
The regions connectivity graph (Voronoi diagram) was analyzed for cycles or loops that the intruder
can use to evade a pursuer. The number of cycles were found by the simple formula:
Number of Cycles in Graph = Number of Edges - Number of Nodes + 1
Depth First Search (DFS) was used to identify the cycles and their node sequences. If any detected
cycle exists inside another cycle, an exclusive or (XOR) operation was performed on them to find all
inner cycles represented by the structure Scycles.
Static blocker positions are found by checking the degree of each region. The degree of a region is
termed as the number of cycles it affects i.e. the number of cycles having this region as a node. The
region with highest degree and consequently its corners were analyzed so that maximum number of
cycles can be removed from the graph using a single blocker. The corners affecting the most number
of cycles were selected as blocker positions given by the Sblocker_pos array. If multiple corners affect the
same number of cycles, then the corner covering the most number of regions among them was
selected as a blocker position; and if they affect the same number of regions as well, the corner
covering the larger area was selected.
All the regions covered by the blockers Sreg_blockers were removed from the regions graph Sregion which
resulted in the formation of a tree (no cycles) known as the Reduced Minimum Spanning Tree
(RMST). The RMST represents the remaining regions in the environment that need to be searched
and secured by the searcher robots and is depicted as:
4.3. Search Tree and RMST Root Optimization
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
57
The root of the RMST is considered to be the start point of the tree. An improved root selection
technique was implemented ensuring that (a) the root node is not a leaf, since it adds to the length (or
degree) of all branches of the tree, where a leaf node is a node that has only one neighbour (its parent
node) and a branch is a sequence of at least three consecutively connected nodes starting from the root
and ending at a leaf node. In such a case the parent of the leaf node is selected as the root and (b) the
root is at an end of a branch (parent of a leaf node) so that the number of branches is reduced and the
search tree optimized. The search tree gives the search order Ssearch_order for all searchers according to
the total number of branches in the tree. For a completely uncoordinated search, the number of
searchers is equal to the number of branches and all leaf nodes are searched by placing the searcher at
a point on the common edge between the leaf node and its parent.
4.4. Blocker and Searcher Paths
The blocker paths Sblocker_path were optimized through Dijkstra's shortest path algorithm. The algorithm
itself only gives the length of the shortest path, but it was modified to return both the path length as
well as the actual path coordinates. Hence, the paths from the root to all blocker positions Sblocker_pos
were determined.
The searcher paths Ssearch_path were also finalized on the basis of the shortest path algorithm and the
path was optimized keeping certain improvements in consideration. Every searcher path originated
from the root node and it was optimized such that as the next node from the Ssearch_order was added to
the path, it formed the shortest path keeping in consideration all leaf nodes connected as children of
the node being added.
5. Results and Simulations
The simulation results for the implemented algorithm are summarized in this section. The Delaunay
Triangulation and triangles graph of the environment in Figure 1 can be seen in Figure 3(a); whereas
Figure 3(b) shows the results of merging the triangles into polygonal convex regions and the regions
graph (Voronoi diagram) formed by connecting centroids of adjacent regions. A total of 24 regions
were formed after merging 56 triangles.
Figure 3 : a) Triangles Graph b) Merged Regions (numbered) and Regions Graph
The number of cycles formed by the 24 regions in the regions graph as can be seen in Figure 3(b) are
09. These cycles were broken on optimal blocker positions identified by the algorithm using only 03
blockers. The RMST formed by removing regions covered by blockers and the resulting blocker
positions are shown in Figure 4(a) and Figure 4(b).
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
58
Figure 4 : a) RMST and Blocker Positions b) RMST and Blocker Positions (without regions)
The root, as shown in Figure 4, was optimized to minimize the number of branches in the search tree.
The number of branches for searchers are 01 in this case and the search order is given by:
The blocker paths for the 03 blockers are shown in Figure 5.
Figure 5 : Blocker Paths (starting from root node)
The searcher path for the single searcher identified by the algorithm is shown in Figure 6.
Figure 6 : a) Searcher Path b) Searcher Path (with regions)
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
59
6. Discussion
The results of the algorithm were compared to research on the same environment by Katsilieris
(2009). The strategy implemented by Katsilieris (2009) was practically experimented with the
Groundbot developed by Rotundus having an average speed of 0.64 m/s. The overall comparison of
that algorithm with the algorithm presented in this paper (same average speed) is tabulated in Table 1.
Table 1: Comparison of algorithm results depicting time and cost efficiency
No. of Regions
No. of Blockers
No. of Searchers
Critical Path Length (CPL) Blockers
Time to cover CPL Blockers
Critical Path Length (CPL) Searchers
Time to cover CPL Searchers
Total Time to Secure Environment
Total Robots required
Search & Secure Algorithm
by [2]
33
04
02
235 meters
06 min 08 sec
346 meters
09 min
15 min 08 sec
06
Presented Algorithm
24
03
01
146 meters
03 min 38 sec
310.8 meters
08 min 05 sec
11 min 43 sec
04
As it is clear from Table 1, the number of regions formed after merging triangles are reduced to 3/4th
by improving the merging strategy. Merging triangles into largest possible convex regions forms a
simplified regions graph (Voronoi diagram) with lesser number of nodes, resulting in significant
reduction of number of robots required (and invariably cost). In this particular case, a 1/3rd reduction
in robots was observed as the number of blockers required to break cycles as well as the number of
searchers required to search the complete environment are reduced. The Critical Path Length (CPL)
for blockers is defined as the longest distance for any blocker robot to reach its position. This is very
important as searcher robots cannot begin searching the environment unless all blockers are in
position to break the cycles in the graph. Reduced number of regions along with tree root optimization
and shortest path algorithm minimized the CPL for blockers as compared to the sub-optimal blocker
paths generated due to arbitrary root selection by Katsilieris (2009). In this case, CPL for blockers
was reduced by almost 40%, consequently reducing the time required by blockers to reach their
positions by the same percentage. Similarly, the CPL for searchers was also reduced by generating
shortest possible trajectories for them. To secure the overall environment in this case, a 1/4th increase
in time efficiency and 1/3rd decrease in required robot resources was observed.
7. Conclusion
We have presented an improved implementation of the search and secure algorithm that significantly
increases the overall time and cost efficiency for an uncoordinated search of a known environment.
As part of the detailed analysis of this algorithm, we showed the results of an improved regions
merging strategy and the advantages of root optimization along with implementation of the shortest
path algorithm for searcher and blocker paths. The algorithm can be used for searching and securing
any environment modeled in the form of obstacles enclosed inside a boundary with multiple intruders
and we proved the efficiency of the algorithm by an analytical comparison with a search and secure
algorithm already being used practically.
8. Acknowledgements
We wish to thank Urooba Shaikh for her valued technical assistance in developing environment maps
for validation of the algorithm.
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
60
References
Batalin, M., & Sukhatme, G. (2002). Multi-Robot Dynamic Coverage of a Planar Bounded
Environment (CRES-03-011). Robotic Embedded Systems Laboratory, University of
Southern California. Retrieved from
http://www.cens.ucla.edu/~maxim/Publications/ papers/331.pdf
Barclay, M., & Galton, A. (2008, July). Comparison of region approximation techniques based on
Delaunay triangulations and Voronoi diagrams, Journal of Computers, Environment and
Urban Systems, 32(4), 261–267.
Bondy, J., & Monty, U. (1976). Graph Theory with Applications (5th ed.). New York, NY: The
Macmillan Press Ltd., Elsevier Science Publishing Co. Inc.
Elmaliach, Y., Agmon, N., & Kaminka, G. (2007, April). Multi-Robot area patrol under frequency
constraints, IEEE International Conference on Robotics and Automation (ICRA), Rome, Italy,
pp. 385–390.
Gartner, B., & Hoffmann, M. (2013). Delaunay Triangulations. In Computational Geometry Lecture
Notes HS 2013 (Ch.06). Retrieved from
http://www.ti.inf.ethz.ch/ew/courses/CG13/lecture/Chapter%206.pdf
Katsilieris, F. (2009, May). Search and secure using mobile robots (Masters' Degree Project). KTH
Royal Institute of Technology, Stockholm, Sweden.
Kolling, A., & Carpin, S. (2007). The GRAPH-CLEAR problem: definition, theoretical properties and
its connections to multirobot aided surveillance, IEEE/RSJ International Conference on
Intelligent Robots and Systems (IROS), San Diego, California, U.S.A, pp. 1003–1008.
Portugal, D. B. S. (2009). RoboCops: A study of coordination algorithms for autonomous mobile
robots in patrolling missions (Masters' Thesis). University of Coimbra, Coimbra, Portugal.
Sgorbissa, A., & Arkin, R. (2003, October). Local Navigation Strategies for a Team of Robots,
Robotica, 21(5), 461–473. Cambridge University Press.
Wurm, K., Stachniss, C., & Burgard, W. (2008, September). Coordinated Multi-Robot Exploration
using a Segmentation of the Environment, IEEE/RSJ International Conference on Intelligent
Robots and Systems (IROS), Nice, France, pp. 1160–1165.
AICS e-Journal of Artificial Intelligence and Computer Science, e-ISSN: 2289-5965.
Vol 2, 2014.Published by http://worldconferences.net/
61