Conference PaperPDF Available

Map Generation and Path Planning for Autonomous Mobile Robot in Static Environments Using GA

Authors:

Abstract and Figures

In this paper, we present our initial idea of developing an integrated an autonomous mobile robot system that can explore an unknown environment. The proposed system consists of three components 1) a map generation 2) path planning and 3) path tracking. The proposed approach allows a mobile robot to navigate the unknown environment, avoiding obstacles and following a defined path to reach the target position without collision. Ultrasonic sensor data was collected via moving the robot along the perimeter of the environment while incrementally updating the occupancy grid using ultrasonic/laser sensor to measure the distance between the obstacles and the edge of the environment. This dataset will be converted to a map that is used by Genetic Algorithms (GAs) to create an optimal route from a pre-defined start and target points. The autonomous robot system will travel between these points by following a trajectory defined by waypoints estimated using GAs. The pure pursuit (PP) algorithm is used for trajectory following. The proposed system was tested in a real environment using LEGO robot and in simulation using GAZEBO software. The results indicate that the proposed integrated autonomous mobile robot system is promising
Content may be subject to copyright.
Map Generation and Path Planning for Autonomous
Mobile Robot in Static Environments Using GA
Karthikeyan U. Gunasekaran, Evan Krell, Alaa Sheta, Scott A. King
Department of Computing Sciences
Texas A&M University-Corpus Christi
Corpus Christi, TX 78412, USA
Abstract—In this paper, we present our initial idea of developing
an integrated an autonomous mobile robot system that can
explore an unknown environment. The proposed system consists
of three components 1) a map generation 2) path planning and
3) path tracking. The proposed approach allows a mobile robot
to navigate the unknown environment, avoiding obstacles and
following a defined path to reach the target position without
collision. Ultrasonic sensor data was collected via moving the
robot along the perimeter of the environment while incrementally
updating the occupancy grid using ultrasonic/laser sensor to
measure the distance between the obstacles and the edge of the
environment. This dataset will be converted to a map that is
used by Genetic Algorithms (GAs) to create an optimal route
from a pre-defined start and target points. The autonomous robot
system will travel between these points by following a trajectory
defined by waypoints estimated using GAs. The pure pursuit
(PP) algorithm is used for trajectory following. The proposed
system was tested in a real environment using LEGO robot
and in simulation using GAZEBO software. The results indicate
that the proposed integrated autonomous mobile robot system is
promising
Index Terms—Robot navigation system, Genetic Algorithm, Path
Planning, Metaheuristic Search Algorithms, Map Generation
I. INTRODUCTION
An autonomous robot is a physical agent that independently
interacts with its environment to perform tasks [6]. Intelligence
is desirable for a robot in order to make decisions that
increase mission success. Mobile robots are able to move
in an environment using wheels, legs, etc. For autonomous
operation, mobile robots should have a representation of their
environment, a mechanism for selecting targets, and a method
for efficiently navigating to a target. Combined with sufficient
localization capability, a detailed world representation allows a
robot to navigate effectively in a given environment. A ground
robot working on a factory floor could have a 2D grid where
each cell is either occupied or not. These are called "occupancy
grids" and enable path planning and navigation with a low
memory footprint [10]. Autonomously generating a map for
an unknown area remains a challenge, especially for complex
environments.
Many solutions have been implemented based on simultaneous
localization and mapping (SLAM); a mobile robot is placed
at an arbitrary, unknown location and incrementally builds a
map while determining its position relative to this map [6].
SLAM techniques are computationally intensive and require
much exploration [9]. This paper proposes a less intense
mapping technique that is very simple to implement and can
either wholly or partially map specific environments. Even a
partially-completed map can be a starting point to direct a
more complicated technique toward specific unknown areas
rather than exhaustive exploration. Once the map is available,
planning a collision-free path with minimal costs such as time,
energy, and distance is possible for robot navigation.
The path planning problem for autonomous robot system
remains a challenge because of the high computational effort
required; the problem is NP-hard [9]. The computational effort
of traditional shortest-distance algorithms such as Breadth-
first search, Dijkstra, and Bellman-Ford led to the develop-
ment of heuristic approaches that reduce the search space.
Metaheuristic algorithms and soft computing techniques have
been explored for path planning [15], [17] such as Genetic
Algorithms [18]–[20], Neural Networks [7], and Fuzzy Logic
[12]. The advent of metaheuristic search algorithms such as
GA, Particle Swarm Optimization (PSO) and Ant Colony
Optimization (ACO) approaches can be used to substantially
reduce computation [11], [17].
This paper is organized as follows. In Section II, we provide a
general overview of GAs. The adopted hardware and software
components are presented in Sectionhardware. The proposed
autonomous mobile robot system architecture is presented in
Section IV. The experimental results are given in Section V.
Finally, we provide a conclusion.
II. GE NE TI C ALGORITHM
GA is a bio-inspired search algorithm that applies Darwin’s
principles of natural selection to computational problems.
Survival of the fittest is used to gradually direct a random
set of solutions toward optimal ones. An individual’s fitness
improves as that individual moves in the direction of an
optimal solution. A single individual is represented as a
chromosome, which is a set of genes. Each gene corresponds
to a dimension of the problem. A fitness function scores the
individual based on the chromosome. Improvement occurs by
applying the genetic operations, crossover and mutation, to
chromosomes in the current population such that they repro-
duce and generate the next population. More fit chromosomes
are allowed to reproduce at a higher rate than weaker ones,
such that successive generations are more influenced by fitter
genes. The expectation is that components of feasible solutions
can be combined to yield a fitter solution.
GA is well-established in robotics. It has been used to tune the
parameters for path planning of a mobile robot, demonstrating
real-time performance in a dynamic, complex environment
[13]. GA was used within a multi-robot team playing soccer
[5]. GA was applied to the difficult task of controlling a hexa-
pod robot. The robot learned to walk by using the feedback
of walking trials as input to the evolution [14].
There has been much research in applying GA and similar
metaheuristic techniques to mobile robot path planning. The
majority of work in this area only evaluates the results as paths
generated in a 2D environment. Little work deals with creating
the map that will be used for path planning or demonstrating
the robot can adequately follow the path. Our work’s proposed
mapping scheme will allow the robot to generate a map
for path planning. Also, the Gazebo simulator is used to
show the paths are feasible for a robot in a 3D world with
realistic physics. Two recent (2017) studies demonstrate that
GA produces smooth, near-optimal paths [18], [19]. However,
in both cases, the map is known a priori, and no actual path
following is shown. There are a few cases that use real robots,
such as a 2010 study that included experiments where a robot
with range-finding sonars was able to navigate using the GA-
generated paths [20]. The map of the real environment was
known a priori.
III. HAR DWARE AND SO FT WARE
A. LEGO robot
The LEGO Mindstorm EV3 [4] is a popular robotics kit. The
EV3 brick is a programmable microcomputer, running Linux,
that controls the motors and sensors and provides Wi-Fi and
Bluetooth [16]. The digital EV3 ultrasonic sensor [1] generates
sound waves and reads their echoes to detect and measure
the distance between objects. This sensor measures distances
between 1 and 250 ±1cm.
B. Software Tools: Gazebo and MATLAB
Gazebo [2] is a robotics simulator suited to experiments in
algorithms, robot design, regression testing, and training of
machine learning systems. The gazebo is famous because of
its plethora of existing robots and environmental components
with realistic physics support and high-quality 3D graphics.
MATLAB [3] connects to Gazebo through the Robotic Oper-
ating System (ROS) interface. ROS abstracts communication
among robots and control software such that the MATLAB
code written for Gazebo should easily port to actual robots.
IV. PROPOSED AUTONOMOUS ROBOT SYSTEM
This paper proposes an integrated system with 2D map gen-
eration and trajectory following for an unknown environment.
Instead of exploring the interior of the space using expensive
SLAM techniques, the robot moves along the perimeter of
the environment and generates an occupancy grid. The robot’s
laser sensor is used to collect ranges and calculate the distance
to objects in the space. These distances are continually updated
in an initially empty grid. That grid is used to generate paths
to an arbitrary target location in the area. Optimal paths
are computed using GA. Trajectory following is performed
using pure pursuit [8]. A complete framework is demonstrated
where a robot can autonomously move to target locations in
an unknown environment. The proposed system hierarchy is
provided in Figure 1.
Map
Generation
Path Planning
(GA)
Trajectory
Following
(Pure Pursuit)
Fig. 1: Proposed Autonomous Mobile Robot System
A. Map Generation
To generate the map, the robot moves along the perimeter of
the environment while incrementally updating the occupancy
grid using laser scan sensor. Cell value of 1 indicates occupied
and 0 indicates free. This research assumes that the environ-
ment is static, the cells are independent of each other, and the
area of a cell is either completely free or occupied with an
obstacle.
To avoid collisions, if any part of the cell intersects an obstacle,
the entire cell should be considered as an obstacle. Increasing
the grid resolution decreases the free area that is viewed as an
obstacle. The resolution should be adjusted based on the needs
of the actual workspace the robot will be operated in. There
is a trade-off between map accuracy and path planning time
since the higher the number of cells the longer the search will
take. The mapping methodology is explained in Algorithm 1
with an example of a 4×4grid which spans 100cm ×100cm.
The area of each cell is 25cm2.
Figure 2 shows the sample environment where cells filled in
blue indicate obstacles. The robot starts at the point Aand
moves towards position B. It then turns left towards point C.
From C, it moves toward Dand finally reaches the starting
point A. The laser sensor measures the horizontal distance.
The point xis the position of the robot and yis either the
entire distance from location Ato D(100 cm or until the start
point of an obstacle). For example, if an obstacle is placed at
the fourth cell in the second row from the left top corner,
then ywould be set at the 75cm from the starting point x.
This process is repeated iteratively to measure the horizontal
Fig. 2: Sample environment with obstacles.
Algorithm 1: Basic steps of Mapping Algorithm
Input: Lidar Sensor Values (L), Row Length (RL), Cell
Length (CL), Total Distance (T D).
Output: Resultant Matrix, M
1begin Mapping
2Input Lis subdivided into four lists L1,L2,L3,L4.
3L3,L4are reversed and stored as L3r,L4r
4For i=1to2(L2c, L3rc)
5For i= 1 to row length RL
6Add cell length CL to each list values L2c, L3rc
7If L2c, L3rc greater than total distance T D
8Swap values with twice total distance
9Next for
10 For i= 1 to row length RL
11 Subtract T D from L2c, L3rc
12 Next for
13 Next for
14 For i= 1 to row length RL
15 For i= 1 to row length RL
16 Divide CL with each L1, L2c, L3rc , L4r
17 Update zero matrix with L1f, L2f, L3f, L4f
18 Next for
19 Next for
20 end Mapping
distance and vertical distance of the environment with respect
to the robot.
The sensor data is processed and a list is created from these
values as input for the proposed mapping algorithm. The
created list is named L, which is then sub-divided into four
lists. L1encompasses values from point A to B. L2stores
values from point B to C and similarly L3and L4store values
from point C to point D and from point D to point A. L3r
and L4rare reversed. In this example,
Lfull = [25, 25, 50, 0, 0, 50, 25, 50,
75, 25, 0, 50, 25, 50, 0, 75]
L1= [25, 25, 50, 0] L2= [0, 50, 25, 50]
L3r= [50, 0, 25, 75] L4r= [75, 0, 50, 25]
From L2and L3the total distance, 100, is subtracted from
each element of the list after adding its cell length. In this
example at B1 instances, to 00 the cell length 25 is added
and then the total length 100 is subtracted which gives 75.
The corrected values of L2and L3are called L2cand L3c,
respectively.
L1= [25, 25, 50, 0] L2c= [75, 25, 50, 25]
L3rc = [25, 75, 50, 0] L4r= [75, 0, 50, 25]
The final lists are generated by dividing each element with the
cell length. The final list values are used as the plug-in value
which creates the matrix. For example, L1at A1 instance,
the value 25 is divided by the cell length (25) which gives a
resultant value of 1. The finalized list is called L1f. A zero
matrix is created. The number of rows and columns for the
matrix are equal to the resultant value arrived on the dividing
the number of elements present in Lby four. Here, the L
0100
0100
0010
1000
Update Zero Matrix by L1f
0100
0101
0010
1000
Update Zero Matrix by L2f
0100
0101
0010
1000
Update Zero Matrix by L3f
0100
0101
0010
1000
Update Zero Matrix by L4f
The final map
Fig. 3: Map generation update.
TABLE I: GA Representation of path: Sequence of waypoints.
x1y1x2y2... xnyn
count is 16, which when divided by 4 gives 4 which is called
n. Thus, a 4×4 zero matrix is generated.
L1f= [1, 1, 2, 0] L2f= [3, 1, 2, 1]
L3f= [1, 3, 2, 0] L4f= [3, 0, 2, 1]
The zero matrix is iteratively updated using each final list. The
indices for the obstacle is created using the final list. L1fand
L3fvalues are plugged in as column values and corresponding
row value are incremental values inserted, from zero to n1.
Similarly, the L2fand L3fvalues are plugged in as row values
and corresponding column values are incremental values,
inserted from zero to n1. These indices are assigned one.
The updated zero matrix is shown in Figure 3. The zero matrix
is incrementally updated with each new index created from the
final list values. The resultant zero matrix has one at different
indices which indicates the presence of obstacles.
B. Path Planning using GAs
Path planning is the process of generating a possible sequence
of intermediate waypoints between a start and goal. A possible
path takes the robot to the target position without colliding
with obstacles. The goal is to find a way that minimizes the
distance of the path while remaining collision-free. GA is
used to find solution paths Waypoints are coordinate values
in the robot’s environment, which is the GA search space.
The solution is stored in an array of size 2 times the number
of waypoints since each (even, odd)-pair of array values is a
waypoint. This representation is shown in Table I.
C. Fitness Function
The GA fitness function is used to evaluate the quality of an
individual’s chromosome. Distance minimization is computed
using the Euclidean distance (See Equation 1) between each
pair of waypoints to measure the path’s length. (Equation 2) is
the summation of each subpath between adjacent waypoints,
P athD.
DI ST (xi, yi, xj, yj) = q(xixj)2+ (yiyj)2(1)
P athD=
n1
X
i=1
DI ST (< xi, yi>, < xi+1, yi+1 >)(2)
D. Obstacle Avoidance
Collision avoidance is implemented by penalizing obstacle
presence along with a path. The Penalty (P) is set to an
arbitrarily high value to make paths containing collisions have
poor fitness. We have set the penalty to 10000. The SIN F is
defined as the infeasible portion of the map. This is shown in
Equation 3.
P athO=SIN F P(3)
The full fitness function is comprised of the distance minimiza-
tion and obstacle avoidance functions. The complete fitness
function used in GA is shown in Equation 4.
F itnesspath =P athD+P athO(4)
V. EX PE RI ME NT S AN D RES ULTS
A set of simulation and real-world experiments with different
environmental setups were performed to verify the effective-
ness of the proposed algorithm. Simulation experiments were
implemented using Gazebo simulator and a MATLAB control
program. Real-world experiments are implemented using the
LEGO EV3 robot equipped with a single ultrasonic sensor.
A. Map generation in simulation
For simulation experiments, the full system of map generation,
path planning, and trajectory following was done in three
environments. Each environment was created by specifying
size and randomly generating obstacles in that space. The
three environments are: small-size room (Figure 4a), medium-
size room (Figure 4b), and large-size room (Figure 4c). The
small size room measures 5×5 meters and has 5 obstacles.
The medium-size room measures 10×10 meters and has 8
obstacles. The large-size room measures 20×20 meters with
35 obstacles. The environment layout in the simulation is
provided in Figure 4 (a), (b) and (c). The 2D occupancy
grids generated for all three environments based on real-time
simulation is shown in Figures 5 (a), (b) and (c).
B. Map generation in real-time
Experiments were implemented using the LEGO EV3 in a
laboratory setting. An environment was created by drawing
grid lines and a perimeter track onto a 100×100 cm section
of the floor. This environment is called Lab Environment.
Space was divided into a 5×5 grid where each cell is 20
cm2. This environment is shown in Figure 6. Boxes were
placed on certain grid cells to act as obstacles. The LEGO EV3
robot used a downward-facing light sensor to follow the red
track. A PID controller is used to follow this line. The robot
followed the track and used the ultrasonic sensor to generate an
occupancy grid using the proposed mapping algorithm. Map
generation produced the occupancy grid shown in Figure 7.
C. Path Planning Results
To generate the mobile robot path via the map created in
the previous stage, we run GAs for ten experiments with
various population sizes (i.e., 20, 35, 50, and 100) as shown
in Figure 8. In this case, the 2D-workspace has 10×10 grids;
the start point is at (1,1) and target at (10,10). The best GAs
convergence results were found with a population size of 100.
The fitness value represents the combined path distance and
obstacle penalty, so GA minimizes this value. The 0-point
of the y-axis is the lowest obtained fitness value. Due to
nondeterminism of GA, repeated trials are needed to confirm
that a near-optimal path can reliably be obtained.
The results of 10 trials using a population size of 100 are
shown in Figure 9. Figure 10 shows the best and worst
experiments as well as a curve generated by averaging points
of all experiments. This is intended to clearly illustrate the
bounds of the fitness and that the average achieves a relatively
smooth curve toward convergence. Figure 11 shows the actual
waypoints generated as points (blue "x"’s) in Gazebo. The
cones are the start and goal locations. The robot is seen moving
between waypoints.
The convergence graph using different population size is
shown in figure 8. We experimented with varying population
size namely, 10, 25, 50, 75, 100, 125. It is evident from the
convergence graph that the population size with 100 individ-
uals provides an optimal path, in our case, is the near-optimal
path between the starting and target point when compared with
another population size. Convergence of GA using the same
population size of 100 for 10 runs is shown in the Figure 9.
The graph for the mean, worst and best convergence using
same population size is shown in the Figure 10.
D. Trajectory Following using Pure pursuit
The trajectory following stage inputs the collision-free path
which has been generated by the path planning module. The
robot starts from the start point and reach the target point
by reaching each waypoint in sequence. Using pure pursuit
algorithm, the controller was initialized. The desired linear
velocity was 0.3 and look ahead distance was set to 0.5. The
Turtlebot following the waypoint in sequence on the medium-
size room environment in Gazebo is shown in the Figure 11.
VI. CONCLUSIONS AND FUTURE WORK
We present our idea of building an autonomous robot system
that can search an unknown environment of various sizes. On
doing that, we developed a 2D grid map for the unknown
environment. The generated map has the advantage over other
map generation in the literature that it can be produced with
less time compared to random environment exploration. For
the path planning, GA was able to develop an optimal set of
waypoints for the robot to follow from a designated start and
end-points.
(a) Small room (b) Medium room (c) Large room
Fig. 4: Three different environments used in the experiment.
Binary Occupancy Grid
0 20 40 60 80 100
X [meters]
0
20
10
60
80
100
Y [meters]
(a) Occupancy grid for small room
Binary Occupancy Grid
0 20 40 60 80 100 120 140 160 180 200
X [meters]
0
20
40
60
80
100
120
140
160
180
200
Y [meters]
(b) Occupancy grid for medium room
Binary Occupancy Grid
0 5 10 15 20 25 30 35 40 45 50 55 60 65 70 75 80 85 90 95 100
X [meters]
0
5
10
15
20
25
30
35
40
45
50
55
60
65
70
75
80
85
90
95
100
Y [meters]
(c) Occupancy grid for large room
Fig. 5: 2D occupancy grid maps created by the system for the different environments.
Fig. 6: Lab environment with obstacles.
REFERENCES
[1] The digital ev3 ultrasonic sensor. https://shop.lego.com/en-US/EV3-
Ultrasonic-Sensor-45504. Accessed: 2018-03-25.
[2] Get started - gazebo. Accessed: 2018-03-25.
[3] Get started with gazebo and a simulated turtlebot. Accessed: 2018-03-
25.
[4] Mindstrom lego ev3. Accessed: 2018-03-24.
[5] AL BAB , R. T. U., WIB OWO , I. K. , AND BASUKI, D. K. Path planning
for mobile robot soccer using genetic algorithm. In 2017 International
Electronics Symposium on Engineering Technology and Applications
(IES-ETA) (Sept 2017), pp. 276–280.
[6] BR ESS ON , G., A LS AYED, Z ., YU, L., AND GL AS ER, S . Simultaneous
localization and mapping: A survey of current trends in autonomous
Binary Occupancy Grid
0 20 40 60 80 100
X [meters]
0
20
10
60
80
100
Y [meters]
Fig. 7: Occupancy grid map for the lab environment.
driving. IEEE Transactions on Intelligent Vehicles 2, 3 (Sept 2017),
194–220.
[7] CAC ERE S, C ., ROSARIO, J. M., A ND AM AYA, D. Approach of kine-
matic control for a nonholonomic wheeled robot using artificial neural
networks and genetic algorithms. In 2017 International Conference and
Workshop on Bioinspired Intelligence (IWOBI) (July 2017), pp. 1–6.
[8] CO ULTE R, R. C. Implementation of the pure pursuit path tracking
algorithm. Tech. Rep. CMU-RI-TR-92-01, Carnegie Mellon University,
Pittsburgh, PA, January 1992.
[9] DURRANT-WH YTE , H. , AND BAILEY, T. Simultaneous localization and
mapping: part i. IEEE Robotics Automation Magazine 13, 2 (June 2006),
99–110.
0 20 40 60 80 100
0
0.2
0.4
0.6
0.8
1
1.2
1.4
1.6
1.8
2106
Pop size - 10
Pop size - 25
Pop size - 50
Pop size - 75
Pop size - 100
Pop size - 125
Fig. 8: Convergence of GA with various population sizes.
0 20 40 60 80 100
0
2
4
6
8
10
12
14 105
Fig. 9: 10 runs of GA with population size of 100.
0 20 40 60 80 100
0
2
4
6
8
10
12
14 105
Best
Worst
Mean
Fig. 10: Worst, Best, and Mean of the GAs process of the 10
Runs.
Fig. 11: Waypoints of the optimal path.
[10] EL FES , A. Using occupancy grids for mobile robot perception and
navigation. Computer 22, 6 (June 1989), 46–57.
[11] HU SSE IN , A., M OSTA FA, H. , BADREL-DIN, M. , SU LTAN, O. , AN D
KHAMIS, A. Metaheuristic optimization approach to mobile robot
path planning. In 2012 International Conference on Engineering and
Technology (ICET) (Oct 2012), pp. 1–6.
[12] KU NCH EV, V., JAIN, L ., IVAN CE VIC , V., AND FINN, A . Path plan-
ning and obstacle avoidance for autonomous mobile robots: A review.
In Knowledge-Based Intelligent Information and Engineering Systems
(Berlin, Heidelberg, 2006), B. Gabrys, R. J. Howlett, and L. C. Jain,
Eds., Springer Berlin Heidelberg, pp. 537–544.
[13] LI ANG , Y., HON G, F., LIN, Q ., BI, S., A ND FE NG, L . Optimization
of robot path planning parameters based on genetic algorithm. In 2017
IEEE International Conference on Real-time Computing and Robotics
(RCAR) (July 2017), pp. 529–534.
[14] MANGLIK, A., GU PTA, K ., A ND BHA NOT, S. Adaptive gait generation
for hexapod robot using genetic algorithm. In 2016 IEEE 1st Interna-
tional Conference on Power Electronics, Intelligent Control and Energy
Systems (ICPEICES) (July 2016), pp. 1–6.
[15] O.HACH OU R. Path planning of autonomous mobile robot. System
Application Engineering and Development Issue 4, Volume 2 (2008).
[16] PE REZ , S. R., FATOU M, A. , AN D ABKE , J. Development of an eclipse
plug-in for using the lego mindstorms ev3 in education. In 2016 IEEE
Global Engineering Education Conference (EDUCON) (April 2016),
pp. 631–636.
[17] RA JA, P., AND PUGAZHENTHI, S. Optimal path planning of mobile
robots: A review. International Journal of Physical Sciences 7, no. 9
(2012), 1314 – 1320.
[18] SA NTI AGO , R. M. C ., O CAM PO , A. L. D ., U BAN DO, A . T., BA NDA LA,
A. A., AN D DADIOS, E. P. Path planning for mobile robots using genetic
algorithm and probabilistic roadmap. In 2017IEEE 9th International
Conference on Humanoid, Nanotechnology, Information Technology,
Communication and Control, Environment and Management (HNICEM)
(Dec 2017), pp. 1–5.
[19] WU, M., CH EN , E., S HI , Q., Z HOU, L., CHE N, Z., AN D LI, M. Path
planning of mobile robot based on improved genetic algorithm. In 2017
Chinese Automation Congress (CAC) (Oct 2017), pp. 6696–6700.
[20] YU N, S. C ., GANAPATH Y, V. , AN D CHON G, L. O. Improved genetic
algorithms based optimum path planning for mobile robot. In 2010 11th
International Conference on Control Automation Robotics Vision (Dec
2010), pp. 1565–1570.
... By seamlessly integrating these functionalities, the proposed system aims to enhance the robot's ability to navigate and interact with its environment effectively, even in dynamic and unpredictable scenarios. The system navigates using ultrasonic/laser sensors, creating an occupancy grid to avoid obstacles and find optimal routes through genetic algorithms [7]. For effective use of agricultural robots in farms, accurate topological maps are crucial but often manually created. ...
Chapter
The landscape of wireless communication networks has undergone a breathtaking evolution in recent years, reshaping how we connect, communicate, and interact with the world. This transformation is not merely a technological revolution but a profound societal shift that has touched every aspect of our lives. This book, "Wireless Communication Networks and Applications," is an expansive and in-depth exploration of this dynamic field, offering readers a comprehensive guide to the fundamental principles, state-of-the-art technologies, and practical applications that define the realm of wireless communications. In the age of ubiquitous connectivity, wireless networks have seamlessly woven into the fabric of our daily routines, fostering instantaneous communication and data transfer across an extensive array of devices and platforms. From smartphones and tablets to wearables and the Internet of Things (IoT) devices, the influence of wireless networks is omnipresent, reshaping how we work, entertain ourselves, and stay connected. This book endeavors to unravel the intricacies of wireless communication networks, providing readers with a robust foundation in the underlying theories, protocols, and architectures that govern their operations. The exploration spans a diverse range of topics, delving into the physics of radio wave propagation, sophisticated modulation techniques, multiple access schemes, and the critical considerations of network security. By covering such a broad spectrum, the book ensures that readers gain a holistic understanding of the multifaceted world of wireless communication networks. Furthermore, it is attuned to the field's pulse, addressing the latest advancements in wireless technologies, such as the deployment of 5G networks, the advent of Wi-Fi 6, and the emergence of novel wireless standards. By doing so, the book equips readers with the knowledge and insights necessary to navigate the rapidly evolving wireless landscape with confidence and foresight. Beyond theoretical foundations, the book extends its reach into the practical realm, exploring the real-world applications of wireless networks across diverse domains. Cellular networks, wireless sensor networks, and vehicular networks are scrutinized for their tangible impacts and potential contributions to society. Real-world case studies and practical examples are interwoven seamlessly throughout the book, serving as beacons of illumination that reinforce theoretical concepts and shed light on the challenges and solutions inherent in designing, deploying, and optimizing wireless communication networks. Designed to cater to a diverse audience, whether students, researchers, engineers, or wireless communication enthusiasts, this book strives to be a valuable and accessible resource. As we navigate the intricate pathways of wireless communication networks, this book serves as a compass, pointing us toward a deeper understanding of the subject matter and providing a panoramic view of this everevolving field's vast potential and future directions. With its comprehensive coverage, practical examples, and forward-looking perspective, "Wireless Communication Networks and Applications" is an essential addition to anyone seeking to deepen their understanding and stay abreast of the latest developments in this dynamic and exciting domain
... B Honnaraju, R Deepu, and S Murali [6] proposed a model showing positive improvements in technology and an efficient model for estimating the distance between humans and the camera from a single 2-D image by utilizing human height as guideline. The paper presents the use of Genetic algorithm [7] for path planning. A PID controller and an ultrasonic sensor have been utilized for the map generation. ...
Article
Full-text available
Vision based mobile robot navigation is one of the important because the robots can resolve lots of problems in which human life is dangerous, difficult and costly. A difficult problem is to make a vision-based robot navigate properly to the target by avoiding the obstacles. Path information is very essential for successful navigation of the robot. The main purpose of this paper is to present an approach for mobile robots to generate path and construct maps. This work is focused on providing the path information of an environment using a single 2-D camera. Whenever robot identifies the human in the corridor, it generates the information of the path information and constructs the map is achieved based on the human moment and the human position. On the robot the camera is mounted which acquires images in real time. Oath information is generated for mobile robot using acquired real time images and processing real time images.
... A survey on computer-vision algorithms for obstacle detection in aerial images which are produced by UAV is analyzed in [13]. More recently, Gunasekaran et al. proposed a map generation in a static unknown environment by using a mobile robot [14]. ...
Conference Paper
Mapping and path planning in disaster scenarios is an area that has benefited from aerial imaging and unmanned aerial (UAV) and surface vehicles (USV). Nowadays, there are many application areas of UAV and USV which consist of environmental monitoring, victim recovery and river mapping in the purpose of rescue operations. There are many challenges for flood rescue operations with existing systems where the time response is critical. The environment is completely changing under flood conditions and it causes a dangerous environment for victims and rescue operators. Rescue boats are widely used for search and rescue in flooded areas. However, rescue boats have a limited view while searching and rescuing the victims. By using UAVs, an aerial image can be taken off the flooded environment and this aerial image can provide global information such as the location of victims and landmarks. The rescue operations can be organized based on a generated flood environment map by using this global information. In this work, we analyze ground map generation and path planning algorithms which make use of aerial imaging provided by a UAV in a flooded urban environment. Based on the generated ground map, we used the concept of mobile robot path planning to represent our proposed approach in rescue boat path planning. In this purpose, A*, GA and PRM path planning algorithms are used and analyzed to find near-optimal paths for rescue boat between initial and target locations. Simulations are performed to evaluate the performance of the system algorithms to find out the most suitable algorithm in flooded urban environments.
... A survey on computer-vision algorithms for obstacle detection in aerial images which are produced by UAV is analyzed in [13]. More recently, Gunasekaran et al. proposed a map generation in a static unknown environment by using a mobile robot [14]. ...
Preprint
Mapping and path planning in disaster scenarios is an area that has benefited from aerial imaging and unmanned aerial (UAV) and surface vehicles (USV). Nowadays, there are many application areas of UAV and USV which consist of environmental monitoring, victim recovery and river mapping in the purpose of rescue operations. There are many challenges for flood rescue operations with existing systems where the time response is critical. The environment is completely changing under flood conditions and it causes a dangerous environment for victims and rescue operators. Rescue boats are widely used for searching and rescuing the victims in the flooded areas. However, rescue boats have a limited view while searching and rescuing the victims. By using UAVs, an aerial image can be taken off the flooded environment and this aerial image can provide global information such as the location of victims and landmarks. The rescue operations can be organized based on a generated flood environment map by using this global information. Here we propose a ground map generation and path planning algorithms, which makes use of aerial imaging provided by a UAV in flooded urban environments. Based on the generated ground map, we used the concept of mobile robot path planning to represent our proposed approach in rescue boat path planning. In this purpose, A*, GA and PRM path planning algorithms are used and analyzed to find near-optimal paths for rescue boat between initial and target locations. Experiments are performed to evaluate the performance of the system algorithms to find out the most suitable algorithm in flooded urban environments.
... A survey on computer-vision algorithms for obstacle detection in aerial images which are produced by UAV is analyzed in [13]. More recently, Gunasekaran et al. proposed a map generation in a static unknown environment by using a mobile robot [14]. ...
Thesis
Full-text available
Mapping and path planning in disaster scenarios is an area that has benefited from aerial imaging and unmanned aerial vehicles (UAVs). However, the integration of an unmanned surface vehicle (USV) in flood rescue operations has not received much attention. We propose a novel map generation and path planning algorithm, which makes use of aerial imaging provided by a UAV in combination with surface level information provided by a USV. Since the aerial image is a 2D projection of a 3D world, some areas of interest could be uncertain, such as under trees. Despite this issue, a Probabilistic Roadmap (PRM) path planning algorithm can be applied to the image in order to find near-optimal paths for a rescue boat between initial and target locations. With the method proposed here, the preliminary PRM solution is further improved by means of an online feedback structure, where local information provided by the USV is incorporated to the overall map as soon as it becomes available, eliminating uncertainties. Simulation results demonstrate the effectiveness of the proposed approach for improving the time response in search and rescue operations in flooded areas.
Chapter
Unmanned Aerial Vehicles (UAVs) have been widely used in emergency rescue because of their small size and low cost, which can effectively reduce casualties and improve rescue efficiency. However, for UAV collision avoidance path planning in an unknown dynamic environment is a relatively difficult optimization problem. On the one hand, it is difficult for traditional algorithms to adapt to the huge state space generated by three-dimensional environment, which makes convergence difficult. On the other hand, the dynamic changing environment will affect the flight safety of UAVs. In this paper, an Improved Memory Pool Dueling Deep Q Network algorithm (IM-Dueling DQN) is proposed to optimize obstacle avoidance and path planning. Combined with the state and action space, a comprehensive reward function is designed to speed up the convergence of the algorithm and improve the generalization ability of the UAV to the environment. Experimental simulations show that the algorithm has good robustness in an unknown dynamic environment, and can avoid all obstacles and plan a safe navigation route.
Conference Paper
Many algorithms have been proposed to tackle the path planning problem in mobile robots. Among the well-known and established algorithms are the Probabilistic Road Map (PRM) algorithm, A* algorithm, Genetic algorithm (GA), Rapidly-exploring random tree (RRT), and dual Rapidly-exploring random trees (RRT-connect). Hence, this paper will focus on the performance comparison between the aforementioned algorithms concerning computation time, path length, and fail and success rate for producing a path. For the sake of fair and conclusive results, simulation is conducted in two phases with four different environments, namely, free space environment, low cluttered environment, medium cluttered environment, and high cluttered environment. The results show that RRT-connect has a high success rate in producing a feasible path with the least computation time. Hence, RRTs-based sampling algorithms, in general, and RRT-connect, in specific, will be explored in-depth for possible optimization.
Conference Paper
Full-text available
Animals display naturally robust locomotion designs which enable them to move on rugged terrains and even adapt to injuries. Most of the robots do not possess such robustness and are rendered useless if they get structurally damaged. In this paper; it is shown that such adapting ability can be introduced in robot's locomotion; if damaged; by evolving optimal gaits through genetic algorithm (GA). A hexapod robot simulation was used to test the gaits generated by GA. Simulation results have proven that the evolved gait enables a hexapod to move effectively with one leg damaged. This technique will increase the reliability and effectiveness of autonomous robots in areas hostile to humans.
Article
Full-text available
Path planning is essential for the autonomous navigation of mobile robots. Researchers have been working on ensuring the safe navigation of mobile robots; however, it is impossible to secure the absolute safety of a mobile robot without environmental information. Nevertheless, passive safety of a mobile robot can be secured. With the aim of ensuring safe path planning of a mobile robot, a safety space is proposed in this work by using the parameters of stopping distance and hazard point. Mobile robots should formulate path plans to bypass crossroads or corner areas where their field of view is limited, and they should also be capable of reducing their movement speed to secure safe driving. We demonstrate through extensive simulations that the developed SGPP (safe global path planning) method outperforms the classical A* and PRM (probabilistic roadmap) algorithms. It improves the navigation time and length of the robot path in comparison to the PRM algorithm and reduces the navigation time by up to 26% compared to the classical A* algorithm for safe navigation. In addition, results of an experiment conducted on a real robot show that the SGPP method finds a safe path with limited velocity for safe navigation.
Article
Full-text available
Mobile robots are increasingly used in automated industrial environments. There are also other applications like planet exploration, surveillance, landmine detection, etc. In all these applications, in order that the mobile robots perform their tasks, collision-free path planning is a prerequisite. This article provides an overview of the research progress in path planning of a mobile robot for off-line as well as on-line environments. Commonly used classic and evolutionary approaches of path planning of mobile robots have been addressed. Review shows that evolutionary optimization algorithms are computationally efficient and hence are increasingly being used in tandem with classic approaches while handling Non-deterministic Polynomial time hard (NP-hard) problems. Also, challenges involved in developing a computationally efficient path planning algorithm are addressed.
Article
In this article, we propose a survey of the Simultaneous Localization And Mapping field when considering the recent evolution of autonomous driving. The growing interest regarding self-driving cars has given new directions to localization and mapping techniques. In this survey, we give an overview of the different branches of SLAM before going into the details of specific trends that are of interest when considered with autonomous applications in mind. We first present the limits of classical approaches for autonomous driving and discuss the criteria that are essential for this kind of application. We then review the methods where the identified challenges are tackled. We mostly focus on approaches building and reusing long-term maps in various conditions (weather, season, etc.). We also go through the emerging domain of multi-vehicle SLAM and its link with self-driving cars. We survey the different paradigms of that field (centralized and distributed) and the existing solutions. Finally, we conclude by giving an overview of the various large-scale experiments that have been carried out until now and discuss the remaining challenges and future orientations.