Accepted Manuscript
New Robot Navigation Algorithm for Arbitrary Unknown Dynamic Environments based on Future Prediction and Priority Behavior Farah Kamil , Tang Sai Hong , Weria Khaksar , Mohammed Yasser Moghrabiah , Norzima Zulkifli , Siti Azfanizam Ahmad PII: DOI: Reference:
S0957-4174(17)30380-9 10.1016/j.eswa.2017.05.059 ESWA 11351
To appear in:
Expert Systems With Applications
Received date: Revised date: Accepted date:
18 April 2016 8 May 2017 24 May 2017
Please cite this article as: Farah Kamil , Tang Sai Hong , Weria Khaksar , Mohammed Yasser Moghrabiah , Norzima Zulkifli , Siti Azfanizam Ahmad , New Robot Navigation Algorithm for Arbitrary Unknown Dynamic Environments based on Future Prediction and Priority Behavior, Expert Systems With Applications (2017), doi: 10.1016/j.eswa.2017.05.059
This is a PDF file of an unedited manuscript that has been accepted for publication. As a service to our customers we are providing this early version of the manuscript. The manuscript will undergo copyediting, typesetting, and review of the resulting proof before it is published in its final form. Please note that during the production process errors may be discovered which could affect the content, and all legal disclaimers that apply to the journal pertain.
ACCEPTED MANUSCRIPT
Highlights Establish a new sensor-based path planning in an unknown dynamic environment. This approach depends on future prediction behavior and priority behavior Successful in handling complex dynamic environments with various obstacle shapes
AC
CE
PT
ED
M
AN US
CR IP T
1
ACCEPTED MANUSCRIPT
New Robot Navigation Algorithm for Arbitrary Unknown Dynamic Environments based on Future Prediction and Priority Behavior Farah Kamil a*, Tang Sai Hong a, Weria Khaksar b, Mohammed Yasser Moghrabiahc Norzima Zulkifli a, and Siti Azfanizam Ahmada a
Department of Mechanical and Manufacturing Engineering, Universiti Putra Malaysia, 43400 Serdang,
*
CR IP T
Selangor, Malaysia, Corresponding author and on leave from the AL-Furat AL-Awast Technical University, AL-Diwaniyah Technical Institute, Iraq
[email protected],
[email protected],
[email protected],
[email protected] b
Robotics and Intelligent Systems Group (ROBIN), Department of Informatics, University of Oslo, Norway
AN US
[email protected] c
Department of Computer and Communication System Engineering, Universiti Putra Malaysia, 43400 Serdang, Selangor, Malaysia
[email protected]
M
Abstract: This study focuses on existing drawbacks and inefficiencies of the available path planning approaches within unknown dynamic environments. The drawbacks are the inability to plan under uncertain dynamic environments, non-optimality, failure in crowded complex situations, and difficulty in predicting the velocity vector
ED
of obstacles. This study aims (1) to develop a new predictive method to avoid static and dynamic obstacles in planning the path of a mobile robot in unknown dynamic environments in which the obstacles are moving and their speed profiles are not pre-identified, to find a safe path and to react rapidly and (2) to integrate a decision-making
PT
process with the predictive behavior of the velocity vector of obstacles by using the sensory system information of the robot. Information on the locations, shapes, and velocities of static and dynamic obstacles is presumed to be
CE
unavailable. Such information is determined online using rangefinder sensors. Thus, the robot recognizes free directions that lead it toward its destination and keep it safe and prevent collision with obstacles. Extensive simulations confirm the efficiency of the suggested approach and its success in handling complex and extremely
AC
dynamic environments that contain various obstacle shapes. Findings indicate that the proposed method exhibits attractive features, such as high optimality, high stability, low running time, and zero failure rates. The failure rate is zero for all test problems. The average path length for all test environments is 16.51 with a standard deviation of 0.49, which provides an average optimality rate of 89.79%. The average running time is 4.74 s (the standard deviation is 0.26). Keywords: dynamic environment, navigation, obstacle avoidance, path planning, robotics,
2
ACCEPTED MANUSCRIPT
I. INTRODUCTION The application of robotic vehicles has been intensely developed in the last few decades (Behroo & Banazadeh, 2015). One of the essential issues in robotics is path planning, which aims to move a robot from its initial position to a destination while preventing collisions with static and dynamic obstacles (Shiller, 2015). Motion planning consists of two major classifications, namely, global motion planning that comprises all gained knowledge of a robot (surrounding information is identified) to reach a
CR IP T
destination and local trajectory that is the procedure of using only the currently sensed data of the robot (surrounding information is unidentified or partially unidentified) (Wu & Feng, 2012a).
The classification of existing research in robot navigation can be grouped into two essential lines, namely, conventional and heuristic methods (Orozco-Rosas et al., 2015). Conventional methods pertain to common approaches, such as roadmap, potential fields (PFs), cell decomposition, and mathematical
AN US
programming. These approaches are not mutually exclusive, and many methods use their hybridizations (Morales et al., 2016). Heuristic approaches were proposed by researchers to overcome the limitations of conventional methods. The best representative approaches within this grouping are artificial neural network (Ćirović et al., 2014), probabilistic roadmap (PRM) (Geraerts & Overmars, 2004), simulated annealing (SA) (Q. Zhu et al., 2006), ant colony (ACO) optimization (Mou et al., 2008), rapidly exploring random tree (RRT) (LaValle & Kuffner Jr, 2000), artificial genetic algorithm (GA) (Aybars, 2008),
M
stigmergy (Cazangi et al., 2006), particle swarm optimization (PSO) (Chen & Li, 2006), tabu search (Nguyen et al., 2012), and fuzzy logic (FL) (Kladis et al., 2011).
ED
Numerous efforts have focused on dynamic motion planning procedures (Sun et al., 2015). The Dijkstra procedure (Dijkstra, 1959) is one of the most significant procedures for graph search and allows the
PT
finding of a minimum route between two nodes of a graph. The algorithm selects the path with low cost between a certain vertex and every other vertex. However, this algorithm is applied only for static obstacles. Therefore, Sipahioglu et al. (2008) implemented the traveling salesman problem-based tour
CE
construction procedure for a mobile service robot in a changing environment. The saving procedure and Dijkstra procedure were used to identify a feasible tour for the mobile robot, but these methods
AC
disregarded the dynamic constraints of obstacles. Hart et al. (1968) suggested the A* algorithm, which was a method that determined the shortest route from a start node to a destination node. This method was based on two cost functions, namely, the going motion cost to travel from the initial point to every cell on the grid and the heuristic guessed motion cost to travel from every cell on the C-space to the destination while ignoring obstacles. However, this approach dealt with static obstacles. Consequently, Mohammadi et al. (2014) offered an enhanced A-Star path-planning procedure in a changing environment that exhibited the best smoothness and calculation time of the latest route. The track was smoother than the
3
ACCEPTED MANUSCRIPT
tracks that came from other traditional procedures, but this approach also disregarded the dynamic constraints of obstacles. The use of the bacterial evolutionary method with the PF method (Montiel et al., 2015) aims to acquire an enhanced flexible route planner performance. Although this combination ensures an optimal, safe, and realistic route, it ignores the velocity vector of obstacles. A behavior-based FL controller to determine
CR IP T
robot trajectory and priority-based control was recommended by Dongshu et al. (2011) to realize the free motion of mobile robots in changing and unknown circumstances. This approach could guide mobile robots in changing unidentified environments successfully, but it ignored the speed of obstacles. Sezer & Gokasan (2012) proposed a new method called “follow the gap,” which ensured safety by directing the robot into the middle of the maximum gap as much as possible while producing the arrival to the end
AN US
point, but it suffered from local minimum and low velocity.
Miao & Tian (2013) developed the SA approach for robot trajectory in changing environments with static and moving obstacles to improve the performance in robot route solution and processing epoch. This approach provided a near-optimal path solution and made its online implementations possible, but it ignored the robot dimension. Zhong et al. (2011) used an enhanced velocity obstacle (VO) method to prevent dynamic collision by considering epoch and distance before the collision. This method achieved
M
fast motion toward the destination when the robot evaded collision with moving obstacles. However, this method was specified to avoid only obstacles with circular shapes. Lin & Yang (2015) developed the
ED
RRT method through a novel 2D span-resampling approach and a pruning technique that depended on a b-spline function to reduce track distance and arrival time. Nevertheless, after the robot passed through two obstacles, route planning disregarded the safe border, and the recommended method ignored any
PT
difference between physical and presumptive obstacle locations. Hossain & Ferdous (2015) developed a new procedure dependent on the bacterial foraging approach to
CE
calculate the shortest route to track from any current place to the destination in unidentified surroundings with dynamic obstacles. Nonetheless, this approach ignored the robot direction and obstacles. Goel &
AC
Singh (2013) offered an enhanced approach to motion planning through the artificial bee colony method to realize the non-collision shortest track in varying environments. This approach suffered from discarding the real dimensions of the mobile robot. A hybrid planning approach including global and local planning was suggested by adopting an improved AC method to plan the global track and rolling window to escape the local collision. However, this approach only dealt with the trajectory in which the moving track of obstacles was known (Dong-Shu & Hua-Fang, 2011).
4
ACCEPTED MANUSCRIPT
Vector field histogram (VFH), proposed by (Borenstein & Koren, 1991), is a real-time motion-planning method that relies on the histogram grid. This method deals with uncertainties arising from sensors and modeling errors. In contrast to other algorithms, VFH considers such elements as dynamics and robot shape while producing steering commands. VFH is a local path planner that can produce near optimal paths. However, VFH is inapplicable if narrow areas are encountered (Borenstein & Koren, 1990). The collision between two moving circular-shaped objects can be effectively prevented by using the collision
CR IP T
cone principle (Fiorini & Shiller, 1998). This principle refers to a set of overall velocities of a robot that will cause a collision with another robot at a specific moment and supposes that the other robot maintains its current velocity. If the robot selects a velocity inside the velocity cone, then the robots will finally collide with the obstacle if it selects a velocity outside the velocity cone; such a collision is ensured not to occur. Nevertheless, the mobile robot cannot occasionally, especially in crowded environments, move to
AN US
its destination because all its velocities to the goal are situated within collision cones (Alsaab & Bicker, 2014).
The dynamic window (DW) method is a real-time collision avoidance approach developed by (Fox et al., 1997), which is derived directly from the robot dynamics. This method is mainly used to deal with constraints, such as limited velocities and accelerations of the robot. In this method, the robot trajectories
M
are represented by a sequence of circular arcs. A velocity pair (v, ω) is assigned to each circular arc, where v and ω are the translational and angular velocities of the robot, respectively (Maroti et al., 2013).
ED
The basic system includes finding the admissible controls that can stop the robots before hitting an obstacle. Optimization is then performed to determine the control that provides the highest utility (Ögren & Leonard, 2005). A search space consisting of only admissible velocities and accelerations of the robot
PT
within a short time interval is also identified in this method (Mallik & Sinha, 2013). The area outside the current window is treated as a free region. This region is not bounded by the obstacle constraints (Ma &
CE
Lei, 2010).
Wu & Feng (2012b) created a local track through obstacle-movement guessing and a rolling window for
AC
dynamic motion planning to partly change the global track. Global and local obstacle avoidance was accomplished via motion, which led to the best path and in turn confirmed the feasibility and effectiveness of the method. The drawback of this method was the limited zone, which meant not a crowded area. Faisal, Al-Mutib et al. (2013) used the FL procedure with four modules to steer an autonomous mobile robot in unstructured, varying, and unidentified environments to arrive at the destination, and obstacle avoidance acted among the four modules and exchanged the control among them. The suggested technique was active and robust under dynamic obstacle scenarios. However, the author did not present any evidence on the actual time process because of the use of several sensors to 5
ACCEPTED MANUSCRIPT
predict the surroundings and did not determine the extent of the system efficiency due to the absence of testing and simulation. Faisal, Hedjar et al. (2013) showed that a wheeled mobile robot (WMR) can perform obstacle avoidance and was directed to its goal through the FL control technique. This technique provided smooth paths, cost savings, self-organization, and flexibility, but it was not precise for a rapid dynamic move of WMR. A 3D
CR IP T
extension of the Bayesian occupancy filter was proposed by (Llamazares et al., 2013) to resolve the issue of dynamic obstacle avoidance for a mobile platform via the stochastic optimum control structure to determine the most suitable routes with regard to safety and energy competence under limitations. This technique, however, suffered from the high computation cost of utilizing the approximate inference control method in real-time planning execution.
AN US
Ali et al. (2013) advocated a new search graph method to discover a free-collision track in a complex, unknown environment. The fundamental aspects and methodology of the laser simulator method were clearly offered and clarified for visibility search of the optimum trajectory in unknown environments with the presence of several motion restrictions and rules. Nevertheless, this approach disregarded the velocity and vector of moving obstacles. Lee et al. (2012) introduced a path-replanning method for the RRT implemented to robot motion planning in dynamic environments using the VO concept, otherwise known
M
as grafting, because the original RRT produced a robot track without considering the existence of moving obstacles. A comprehensive review of motion planning in unknown dynamic environments has been
ED
extensively studied in the literature (Muslim et al., 2016). In this study, we developed a new approach to avoid static and dynamic obstacles based on the prediction
PT
of the future trajectory and priority behavior of obstacles in planning the path of a square WMR in unknown dynamic environments with obstacles that consisted of various shapes. Information on the
CE
locations, shapes, and velocities of static and dynamic obstacles was presumed to be unavailable and was determined online using rangefinder sensors. Thus, the robot recognized the free directions that led it
AC
toward its destination and kept it safe and far from obstacles. The remainder of this paper is organized as follows. Section 2 presents the problem formulation. Section 3 provides the proposed algorithm. Section 4 explains the simulations, computational results, and comparisons. Sections 5–8 indicate the research limitations, research contributions, future endeavors, and conclusions, respectively. II. PROBLEM FORMULATION
6
ACCEPTED MANUSCRIPT
A common setting of the navigation problem is clarified in Fig. 1. Possible environmental alterations are due to restricted sensing ranges (Rs) and obstacle movements (v). The navigation problem is intended to find an appropriate and collision-free path that joins the initial position p0 of the robot at t0 and its final position pf at tf, where p0 = (x0, y0, φ0) pf= ( xf, yf, φf )
CR IP T
The problem occurs when the robot and obstacle move at the same velocity and direction. Consequently, the robot cannot pass the obstacle and never reach its goal unless it can predict the velocity vector of the obstacle and change its direction to another unobstructed direction, as shown in Fig. 2.
Y
AN US
Dynamic obstacles
v4
Rs
Robot trajectory
PT
Static obstacles
X
CE
0
Goal position pf
v2
ED
v1
Start position p0
M
v3
AC
Figure 1 Path planning problem in a complex dynamic environment
Goal Moving obstacle Obstacle direction Robot direction Robot Start
7
ACCEPTED MANUSCRIPT
Figure 2 Significant issue in the dynamic environment
Therefore, to model the mobile robot and its surroundings, the following assumptions can be made without loss of generality.
CR IP T
A. Robot
The robot is considered a WMR, which has a square shape centered at (rx, ry). The robot has two autonomously driven rear wheels and a castor front wheel, as presented in Fig. 3. The configuration of a square robot at time t is denoted by rc(t) = (rx (t), ry (t), rφ (t)); the first two of which specify the coordinates of the robot center where the robot rotates (Source); and rφ(t) displays the robot orientation
rx
AN US
measured by its angle relation to the positive x-axis. ry
M
φ
ED
Figure 3 Configuration of a square robot
B. Kinematic Model of WMR
PT
The kinematic model of WMR with two autonomously driven rear wheels and a castor front wheel is formulated as (
)
(1)
( )
CE
̇
AC
where k=[x, y, φ]T is the state vector, n= [v, ω]T is the input vector, and
G (k) =[
]
This condition can be equivalently formulated as ẋ= v
(2)
ẏ= v
(3) 8
(4)
ACCEPTED MANUSCRIPT
̇ ẋ=
(
)
(5)
ẏ=
(
)
(6)
̇=
(
)
(7)
In our case, to achieve a straight line trajectory, we assume that
CR IP T
vl (t)=vr(t) vr (t) =vl (t)= v(t)
ω (t) = ̇ (t) =0
At this point, the state vector k=[x, y, φ] T indicates the generalized location (position and direction) of the robot in relation to a stable reference axis, and the control vector n=[v, ω]T indicates the linear and
AN US
angular velocities of the robot.
The robot wheels are supposed to not slip, as stated by the nonholonomic restriction. ẋ
C. Obstacles
(8)
The obstacles are characterized by arbitrary shapes. The obstacle velocity is (vx, vy), where the
M
components on x and y axes are indicated by subscripts x and y, respectively. Obstacles may be stationary or dynamic, and their speed is set randomly (the obstacle velocity is equal to or less than the robot
ED
velocity). The location and velocity vector (speed and orientation) of the obstacles are unidentified to the robot. The obstacles are presumed to be recognizable by the robot and move along arbitrary trajectories.
PT
D. Robot sensing
The speed and location of the obstacles are unidentified to the robot; thus, it must be prepared with
CE
detectors or range sensors to obtain essential information. The robot is prepared with range sensors with a 360° finite direction that obtains information from its surroundings. Its detecting range is a circle centered
AC
at (x, y) with radius Rs through which it makes a visibility scan and senses obstacle positions. When the robot arrives at a new position in the configuration space, it first calculates its distance to neighboring obstacles through its radial sensor readings and then stores the outcome in a visibility matrix that comprises the position of visible obstacle points. The obstacle velocities are discovered as the robot calculates the obstacle positions in two sequential repetitions (time intervals) to estimate the speed vector of each obstacle.
9
ACCEPTED MANUSCRIPT
III. PROPOSED ALGORITHM In this section, we explain the concept of our approach to path planning and obstacle avoidance in unknown dynamic environments through several behaviors: 1. Goal-seeking behavior The
robot
initially
navigates
toward
the
goal
with
angle
φ
and
distance
d
CR IP T
through the steering direction equation and the Euclidean equation between the start and goal positions (x1, y1), (x2, y2), respectively, as shown in the following: |
| ] |
[| )
(
)
(10)
AN US
√(
(9)
2. Predictive behavior of obstacle trajectories
After an obstacle enters into the robot range, the distance between it and the robot is determined, and the orientation of the moving obstacle is predicted. The following is a discussion of such a case: An obstacle is assumed to enter into the robot range with position (rx, ry) at t, and the positions of the
M
obstacle at t and t+Ť are (x0, y0 ) and (xŤ, yŤ), respectively, where Ť is the sample time. If the prediction exposes that the obstacle position does not change, then the obstacle is static; otherwise, the obstacle is dynamic. The direction of the moving obstacle is then estimated, and the robot will decide to select the
ED
next step depending on the future velocity vector of the obstacle and priority constraints. Therefore, the robot departs from its original path if the future trajectory of the obstacle crosses its path. If the distance
PT
between the robot and the obstacle widens, then the obstacle is moving far from the robot; otherwise, the obstacle is moving toward the robot.
CE
When the obstacle has a large boundary, the predictive behavior for this case of obstacle will be achieved from the following notion: the range sensor comprises four circles with different radii of R1, R2, R3, and R4; the largest circle is the maximum range of the sensor, the smallest circle is the minimum safe
AC
threshold between the robot and the obstacle, and two other medium circles exist between the largest and smallest circles (refer to Fig. 4). We can formulate this notion as: Circlei = Check around (rxi, ryi, Ri); where i=1, 2, 3, 4, and R=0.2, 0.3, 0.4, 0.5 R3 R4 R32 R1 10
(11)
ACCEPTED MANUSCRIPT
Figure 4 Proposed range sensor These circles are divided into four areas to estimate the position of the direction of the moving obstacle. The first area is between 0 and 90º, the second area is between 90º and 180º, the third area is between −180º and −90º, and the fourth area is between −90º and 0 (refer to Fig. 5). The
CR IP T
robot should record the intersection points between the obstacle positions and these circles and determine which of the areas have these intersection points. The sensor reading records 1 for any area inside obstacle and 0 for a free path to estimate the future trajectory of the moving obstacle after it records the positions in two consecutive iterations (time intervals) to estimate the speed vector of each obstacle. The equation to determine the intersection points is:
Area 2
Area 1
Area 3
M
AN US
Intersection Points of Circlei= Check in Polygon (No. of polygon, rxi, ryi, xpolygon, ypolygon);
ED
Area 4
Area 3
Area 1
Area 4
At time (t+T)
PT
At time (t)
Area 2
(12)
Figure 5 Detection of moving obstacles at (t) and (t+T)
CE
If the prediction reveals that the number of intersection points does not change, then the obstacle is static; otherwise, the obstacle is dynamic. The direction of the moving obstacle is subsequently determined by measuring the number of intersection points. If the number is increased, then the direction of the moving
AC
obstacle is toward the robot; if not, the obstacle is moving away from the robot. For example, if the obstacle direction is toward the first area, then the robot navigates away from this area. We can formulate the number of intersection points at each quarter as: NO. Intersection Points in Quarteri = ∑
(
)
3. Priority behavior
11
(13)
ACCEPTED MANUSCRIPT
If the distance between the obstacle and the robot becomes less than the safety threshold, then the robot decides to deviate from its planned path. The robot should consider its next position and direction based on the following three priorities: 1- The robot distance to the destination should be reduced continuously throughout the navigation. If two positions occur to the goal, then the next location of the robot (N1) needs to be nearer to the
CR IP T
destination than the other position of the robot (N2). We can express this constraint as:
Next position (Ni) = Current position (Ci-1) + Step× [cosφi, sinφi]T N1
Best next position (Nbi) =
If DisN1, G < DisN2, G
otherwise
AN US
N2
(14)
(15)
2- The next position of the robot should not intersect with the future prediction trajectory points of the moving obstacles in the environment. We can formulate this constraint as:
(16)
M
Next position (Nfi) = Current position (Ci-1) + Step× [cos φi, sinφi]T ∉ Future obstacle trajectory
3- The robot (rx, ry) should return to its original path after passing the obstacle and reaching its
ED
destination (xg, yg) to maintain its short path and time depending on the direction equation (φ)
PT
and the distance (d) equation, as shown in Formulas (9) and (10), respectively.
4. Calculating path length After a complete navigation, the approach calculates the path that does not intersect with any obstacle.
CE
The total length of the path can be determined by the Euclidean distance among the points along the path. The Euclidean distance between two points can be determined in 2D environments, as in the following
AC
equation: √(
)
(
)
where n is the number of points along the path. The total length of the route is the sum of the distances. In the equation, L is the total length of the route. fL = L= min ∑
( )
(17)
12
ACCEPTED MANUSCRIPT
5. Determining the reasonable arrival time The approach also calculates the arrival time to guide the robot through the obstacle-free path of the space and to reach the destination D at a reasonable time tf > 0: r (t)∉ ⋃
(
( ))
[
]
(18)
CR IP T
r (tf) =D;
where r (t) is the robot location at t period, and O (t) is the obstacle location at t period.
By integrating the aforementioned components in architecture, the sensor-based online motion planner follows these behaviors to create a goal-driven navigation. The first behavior in our approach is goal seeking, which motivates the robot to move from its source to a destination position. Like most other
AN US
navigation algorithms, our approach begins by checking the destination reachability. If the destination is reachable, then the robot moves straight to the target and the algorithm is finished. Otherwise, the algorithm evokes the next behavior, which is known as predicting obstacle trajectories. In this behavior, the robot senses the surrounding area depending on the range sensor to check if any obstacle exists. If the sensor discovers an obstacle, then the robot should study it to determine if it is a static or dynamic
M
obstacle. Priority behavior is then evoked, where it takes place by finding suitable positions. If the obstacle is static and it intersects with the robot trajectory, then the robot deviates from its original path depending on near-to-goal priority. On the contrary, if it is a dynamic obstacle, then the robot should
ED
predict the future velocity vector of the moving obstacle to decide which direction is better. The robot should subsequently consider its next position and direction based on the aforementioned three priorities.
PT
If the algorithm finds a new location, then it will be the next position of the robot. When the robot reaches a destination, the program calculates the path length and arrival time. If the planner cannot find a location,
CE
then no promising solution exists for this navigation problem and the algorithm fails. Fig. 6 displays the
AC
flowchart of the suggested algorithm.
13
ACCEPTED MANUSCRIPT
Start Modelling Environment Yes
Static Obstacle?
Reach to goal
No
Sensor Reading
Yes
No
New position intersects with other obstacles?
No
CR IP T
No
Navigate Toward the new position depends on priority constrains
Obstacle is Detectable?
Yes
Yes
AN US
Records obstacles’ positions in two successive iterations
Yes Intersect with robot path? No
Deviate from original path Depend on Near to Goal Priority constrains depend on some replacement solutions
Yes Static Obstacle?
M
Keep navigation toward goal
New position is found No Failure
No
Predict the obstacles’ Velocity Vector Intersect with robot path? Yes
Deviate from forbidden area in free direction depend on some replacement solutions
Stop
PT
ED
Yes
No
CE
Figure 6 Flowchart of sensor-based prediction and priority behavior navigation algorithm in unknown dynamic environments
AC
IV SIMULATION STUDIES The proposed method needed to be simulated in several test environments. Several problems were designed and solved. Twenty different arbitrary environments with different numbers of static and moving obstacles in five categories were simulated. These categories comprised convex, concave, maze, narrow passage, and mix environments with four test environments in each category. Arbitrary environment meant that the environment (positions of static and dynamic obstacles) for each run was different, as was the velocity of each obstacle. The red objects were the obstacles, and the yellow and green parts were the start and goal positions, respectively. These environments were designed cautiously 14
ACCEPTED MANUSCRIPT
to address diverse possible situations. The descriptions and features of the test environments are given in this section. The algorithm was performed in each environment 100 times. The simulations were conducted with MATLAB R2013a using a 2.30-GHz Intel Core 7 Duo Processor. Some of the simulations are shown in Fig. 7. The arrival time and path length for every run are denoted in Table 1.
b
c
f
g
h
k
l
ED
M
e
d
AN US
a
CR IP T
The algorithm created safe and short paths with reasonable arrival time.
j
CE
PT
i
n
o
p
r
s
t
AC
m
q
Figure 7 Simulation results in an unknown dynamic environment with different shapes: convex, concave, and narrow passage obstacles 15
ACCEPTED MANUSCRIPT
Figure 7 illustrates that the robot was commanded to move from the starting point (0, 0) to the target point (15, 15) and avoided 25 static obstacles and 25 dynamic obstacles, which were located at unknown dynamic positions and moving at arbitrary unknown velocities. The robot initially navigated toward the goal depending on the optimal path between the start and goal positions (refer to Fig. 7(a)). The environment was crowded and changing along with every step, and the robot checked the environment after each step to ensure the safety of the route. If the sensor did not detect any obstacle, then it recorded 0
CR IP T
in the priority matrix; if it detected an obstacle, as shown in Fig. 7(b), which was a narrow pass, then the sensor recorded 1. The robot then verified if it was a static or dynamic obstacle. The robot emitted four circles of range sensors to calculate the intersection points between the obstacles and sensor circles for two time intervals. The same old and new positions of the obstacle indicated that the obstacle was static. Consequently, the robot searched for the next safe step depending on its near-to-goal priority (part c). As
AN US
shown in parts (d & e), the robot successfully entered the narrow pass and followed the obstacle wall. After passing the obstacle, the robot returned to its original path and direction to reach the goal in the optimal path (part f). When the robot detected a moving obstacle with its circle sensors, the velocity vector of the moving obstacle was recorded in two time intervals to determine the future trajectory of the obstacle. The robot subsequently decided on the best next step depending on the future trajectory and
M
priority constraints of the obstacle. This process is illustrated in Fig. 7(g), which shows that the moving obstacle was in the –x direction, thereby making the robot decide to navigate toward the +x direction to
Obstacle’s velocity vector
CE
PT
shown in the following.
ED
avoid the moving obstacle. We enlarged this case because it was an important case in our approach, as
AC
Figure 8 Robot deciding to navigate to the inverse direction of moving obstacle
After avoiding the moving obstacle, the robot continued its navigation to its destination until it detected the moving obstacle in the –y direction (part h). As a result, the robot decided to change its path to the +y direction to avoid this moving obstacle while considering the static obstacle nearby. The robot then navigated toward the gap between these two obstacles successfully (part i). We enlarged this case for clarity, as shown in the following:
16
ACCEPTED MANUSCRIPT
Static obstacle
Obstacle’s velocity vector
static obstacle
CR IP T
Figure 9 Robot deciding to navigate to the inverse direction of moving obstacle while considering the
When the robot reached the concave shape, as shown in parts (j & k), it could change its path without being trapped in local minima. The algorithm also produced a safe route when the robot faced a convex shape, as illustrated in parts (l & m). The robot successfully navigated the narrow pass again until it
AN US
detected a moving obstacle in the (+x) and (-y) directions, where it decided to change the route into (+x) and (+y) (parts n & o). We enlarged this case for clarity, as shown in the following: Obstacle’s velocity vector
M
At time (t) At time (t+T) Figure 10 Robot navigating to the other direction of moving obstacle
ED
The robot continued its navigation toward its destination by using the same concept (parts p & q). In parts (r & s), the robot faced two obstacles; the first one was toward +y, and the second one was toward
PT
(+x) & (+y). Therefore, the robot decided to deviate toward (+x) to avoid the obstacles until it reached the target (part t), as shown in the following after having enlarged the previous parts:
AC
CE
Obstacles’ velocity vectors
Figure 11 Robot navigating by the same concept until reaching the target
The arrival time to reach the target was (12.4 s) because the robot was moving in crowded and complex environments. The optimal path length, which was dependent on the Euclidian equation, was (21.2); the actual path length was (26.29). This difference was due to the crowded environment, which made the robot more cautious in avoiding all static and dynamic obstacles. The result is enlarged in the following:
17
CR IP T
ACCEPTED MANUSCRIPT
Figure 12 Results of one navigation
CE
PT
ED
M
AN US
The simulation results of the proposed algorithms in other test environments are shown in Figures 13–17:
AC
Figure 13 Simulation results of the proposed algorithm in convex workspaces
18
M
AN US
CR IP T
ACCEPTED MANUSCRIPT
AC
CE
PT
ED
Figure 14 Simulation results of the proposed algorithm in concave workspaces
19
AN US
CR IP T
ACCEPTED MANUSCRIPT
AC
CE
PT
ED
M
Figure 15 Simulation results of the proposed algorithm in maze workspaces
20
AN US
CR IP T
ACCEPTED MANUSCRIPT
AC
CE
PT
ED
M
Figure 16 Simulation results of the proposed algorithm in narrow workspaces
21
AN US
CR IP T
ACCEPTED MANUSCRIPT
M
Figure 17 Simulation results of the proposed algorithm in mix workspaces
AC
CE
PT
ED
The results for 02 arbitrary environments are shown in Table 1.
22
ACCEPTED MANUSCRIPT
Table 1: Results of 20 different environments Runtime (Sec) Average Std
Optimal Path Length
Actual path Length Average
Std
Failure
Optimality
1.66
0.39
13.12
13.25
0.63
0.00%
99.01%
Convex 2
2.13
0.34
12.15
12.95
0.61
0.00%
93.82%
Convex 3
2.17
0.37
13.16
13.21
0.44
0.00%
99.62%
Convex 4
4.41
0.35
13.01
13.62
0.80
0.00%
95.52%
Concave 1
3.14
0.35
12.90
13.64
0.66
0.00%
94.57%
Concave 2
5.03
0.33
13.38
17.24
0.86
0.00%
77.61%
Concave 3
2.3
0.29
11.44
13.02
0.51
0.00%
87.86%
Concave 4
1.74
0.31
7.56
9.65
0.85
0.00%
78.34%
Maze 1
15.25
0.15
15.89
28.84
0.65
0.00%
55.09%
Maze 2
14.28
0.47
45.67
51.18
0.70
0.00%
89.23%
Maze 3
7.35
0.35
12.33
17.67
0.61
Maze 4
4.68
0.20
8.88
Narrow 1
7.03
0.33
Narrow 2
7.09
0.30
Narrow 3
2.04
0.15
8.75
Narrow 4
4.22
0.28
9.65
Mix 1
2.15
0.16
9.59
Mix 2
2.21
0.15
12.04
Mix 3
2.24
0.22
Mix 4
13.98
0.43
CR IP T
Convex 1
M
problems
69.77%
0.48
0.00%
71.90%
20.61
23.82
0.40
0.00%
86.52%
14.94
15.32
0.35
0.00%
97.51%
AN US
0.00%
12.35
0.48
0.00%
95.12%
0.78
0.00%
89.10%
11.30
0.32
0.00%
84.86%
12.95
0.60
0.00%
92.97%
12.40
13.06
0.82
0.00%
94.94%
23.20
26.53
0.29
0.00%
87.44%
ED
9.19
10.83
The algorithm generated a safe and relatively short path with running time within a few seconds. The
PT
main objectives of the proposed algorithm in this stage were to plan in unknown dynamic environments and to predict the velocity vector of obstacles to find the safe and fast reactive trajectories in unforeseen
CE
environments containing both static and dynamic obstacles. Extensive simulations confirmed the efficiency of the suggested approach and its success in handling complex and extremely dynamic environments that contain various obstacle shapes. Findings indicated that the proposed method exhibited
AC
attractive features, such as high optimality, high stability, low running time, and zero failure rates. The failure rate is zero for all test problems. The average path length for all test environments is 16.51 with a standard deviation of 0.49, which provides an average optimality rate of 89.79%. The average running time is 4.74 s (the standard deviation is 0.26).
23
ACCEPTED MANUSCRIPT
Path Length
Runtime
100
20
50
10
0
0 1 3 5 7 9 11 13 15 17 19
1 3 5 7 9 11 13 15 17 19
Optimality 100.00% 50.00% 0.00%
CR IP T
(b)
(a)
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20
AN US
(c)
Failure 100% 50% 0%
Success
M
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20
(d)
Figure 18 Summary of the performance of the proposed multilayer decision (MLD) algorithm in 20
ED
workspaces, including convex, concave, maze, narrow, and mix. (a) Path length, (b) running time, (c) optimality rate, and (d) rate of success are shown for all examples.
PT
The effectiveness of our proposed method was tested and compared with that of other algorithms. The performance of our proposed method was assessed by using several well-known motion-planning
CE
methods, comprising sensor-based planners (bug algorithm, DW approach, and VFH) and four famous randomized planners (PRM, randomized bridge builder (RBB), RRT, and Gaussian sampling (GS)). Each method was selected cautiously to cover diverse parts of the research objectives, and their performances
AC
were compared with the performance of the proposed method in terms of safety, complexity, path length, and computing time. Some of the aforementioned approaches failed to find a safe path in the presence of moving obstacles. As a result, the comparison was classified into two types, namely, comparison in static environments and comparison in dynamic environments, to assess the performance of different algorithms containing the proposed approach in terms of computation time and path length. Each of the algorithms was selected carefully considering the various aspects of the proposed planner researchers (Babinec et al., 2014; Boor 24
ACCEPTED MANUSCRIPT
et al., 1999; Borenstein & Koren, 1991; Ferguson et al., 2006; Hsu et al., 2003; Jie et al., 2010; Karaman & Frazzoli, 2011; Seder & Petrovic, 2007; Tomita & Yamamoto, 2009; Y. Zhu et al., 2012; Zucker et al., 2007). The proposed method was tested on dynamic obstacles in the same environments that were used for static obstacles. The results are shown in Figures 19–23. 35 25 20 15 10 5 0 Dynamic
Static
Convex1 DW
PRM
60 50 40 30 20 10 0 Static
Dynamic
RRT
Static
VFH
Dynamic
RRT
GS
RBB
Static
VFH
GS
Multilayer
Dynamic
Convex3 RBB
Opt
Static
AC
Dynamic
Convex4 Multilayer
100.00% 80.00% 60.00% 40.00% 20.00% 0.00%
Figure 19 Comparison results in convex environments
25
Dynamic
Convex4
PT
PRM
Static
CE
Optimality
DW
Dynamic
Convex3
Convex2
ED
Convex1 BUG
Static
Convex2
M
Runtime
BUG
Dynamic
AN US
Static
CR IP T
Path Length
30
40 35 30 25 20 15 10 5 0 Static
Dynamic
Static
Concave1 BUG
Dynamic
Static
Concave2
DW
PRM
RRT
Dynamic
Concave3
VFH
GS
RBB
60
30 20 10 0 Dynamic
Concave1
100.00%
PRM
RRT
Static
Dynamic
Concave3
VFH
GS
RBB
Opt
Static
Dynamic
Concave4
Multilayer
PT
80.00% 60.00% 40.00%
CE
Optimality
Dynamic
Concave2 DW
Multilayer
ED
BUG
Static
M
Static
Dynamic
Concave4
AN US
Runtime
50 40
Static
CR IP T
Path Length
ACCEPTED MANUSCRIPT
20.00%
AC
0.00%
BUG
DW
VFH
PRM
RRT
GS
RBB
Figure 20 Comparison results in concave environments
26
Multilayer
ACCEPTED MANUSCRIPT
70
Path Length
60 50 40 30 20 10 Static
Dynamic
Static
Maze1 BUG
Dynamic
Static
Maze2
DW
PRM
RRT
Dynamic
Maze3 VFH
GS
RBB
35
Runtime
20 15 10 5 0 Dynamic
Maze1
RRT
Dynamic
Maze3
VFH
GS
RBB
AC
Dynamic
Maze4
Multilayer
Figure 21 Comparison results in maze environments
27
Dynamic
Opt
Static
ED
PRM
Static
PT
100.00% 90.00% 80.00% 70.00% 60.00% 50.00% 40.00% 30.00% 20.00% 10.00% 0.00%
Dynamic
Maze2
DW
Multilayer
CE
Optimality
BUG
Static
M
Static
Static
Maze4
AN US
30 25
CR IP T
0
ACCEPTED MANUSCRIPT
35
Path Length
30 25 20 15 10
0 Static
Dynamic
Static
Narrow1
Dynamic
Static
Narrow2
BUG
DW
PRM
Static
Dynamic
RRT
Dynamic
Narrow3
VFH
GS
RBB
60
30 20 10 0 Static
100.00%
PRM
Multilayer
RRT
Dynamic
Narrow3
VFH
GS
RBB
Opt
Static
Multilayer
60.00% 40.00%
CE
20.00%
AC
0.00%
Figure 22 Comparison results in narrow environments
28
Dynamic
Narrow4
PT
80.00% Optimality
DW
Static
Dynamic
Narrow4
ED
BUG
Dynamic
Narrow2
M
Narrow1
Static
AN US
Runtime
50 40
CR IP T
5
ACCEPTED MANUSCRIPT
35
Path Length
30 25 20 15 10
0 Dynamic
Static
Runtime
Mix1 BUG
DW
PRM
Static
Dynamic
RRT
40 35 30 25 20 15 10 5 0 Static
100.00%
VFH
Dynamic
RBB
RRT
Static
VFH
Multilayer
Dynamic
GS
RBB
Dynamic
Mix4 Opt
Static
Mix3
M
PRM
GS
Static
Dynamic Mix4
Multilayer
PT
80.00%
Mix3
Mix2 DW
Dynamic
ED
BUG
Static
Mix2
Mix1
60.00% 40.00%
CE
Optimality
Dynamic
AN US
Static
CR IP T
5
20.00%
AC
0.00%
Figure 23 Comparison results in mix environments
The comparison outcomes indicated that when the number of obstacles was increased, our proposed approach performed better than the other approaches in terms of path length and running time. The reason for this behavior was that when the environment became crowded with obstacles, the GS, PRM, and RBB approaches, for example, tried to find safe regions away from the crowded areas. However, our approach could find the path inside these crowded areas safely. This advantage was basically due to the behavioral 29
ACCEPTED MANUSCRIPT
nature of our approach in finding free-collision paths inside narrow passes, as illustrated in the following figures.
Proposed approach
CR IP T
Gaussian sampling
PRM approach
ED
M
AN US
RBB approach
PT
Figure 24 Example of the performance comparison of our approach with GS, PRM, and RBB in an environment including obstacles
AC
CE
V RESEARCH LIMITATIONS One of the important limiting factors in our study is in implementing the proposed algorithms in practical applications. The application of the proposed approach in real-world environments would demonstrate the feasibility of the proposed method, although the simulation studies demonstrate the effectiveness of our algorithm.
VI RESEARCH CONTRIBUTION This study focuses on the existing drawbacks and inefficiencies of available path-planning approaches in unknown dynamic environments. The drawbacks are the inability to plan under uncertain dynamic environments, non-optimality, inefficiency in crowded complex situations, and difficulty in predicting the velocity vector of obstacles.
30
ACCEPTED MANUSCRIPT
A novel technique called MLD approach is proposed, which successfully guides the robot in test environments although the environment information is not provided for the planner and the workspaces are unknown for the robot. The robot gains the information from the environments by using a new sensor-based online technique. The failure rate is zero for all test problems. The running time and path length of the planner are significantly lower than those obtained by other studied algorithms.
The proposed approach depends on the future prediction of behavior to predict the velocity vector and priority behavior of obstacles to decide on the best navigation to reach the destination safely.
CR IP T
VII FUTURE ENDEAVORS In this section, several suggestions are offered for further studies in the field of online sensor-based path planning. These recommendations may extend the field of sensor-based path planning and result in more effective algorithms.
CE
PT
ED
M
Interested researchers are suggested to use type-2 FL for designing the planner. Moving a mobile robot in unknown dynamic environments is one of the most challenging areas of high complexity and uncertainty. The use of type-2 FL, which is originally designed for systems with higher uncertainty, may result in improved solutions. However, the application of a type-2 fuzzy inference system to a sensor-based planner is a more complex and difficult procedure that needs further study for the localization of the fuzzy model. Another recommendation is to use an optimization technique, such as adaptive neuro-fuzzy inference system, GA, PSO, bee colony optimization, or any other available technique for optimizing the planner. Each optimization method has its own advantages, and the selection of the optimization technique can affect the overall performance of the algorithm. However, these techniques cannot be easily applied for optimizing the model. The selected optimization methods have to be adjusted and localized to work with the parameters of our model, and these adjustments and localization process are difficult tasks. The proposed algorithm needs to be implemented in practical applications to demonstrate the feasibility of the proposed method, although the simulation studies demonstrate the effectiveness of our algorithm. Our study should be extended to handle more complex environments, such as tracking moving targets.
AN US
AC
VIII CONCLUSIONS In this study, we propose a new sensor-based online technique for producing collision-free paths for differential-drive WMRs that are applied in unknown dynamic environments. This study focuses on the current drawbacks and inefficiencies of available motion-planning approaches in dynamic environments. These drawbacks are the poor quality of the resulting path, high running times of the planner, inability to solve complex problems effectively, and incapability to plan in unknown dynamic environments. The proposed navigation method consists of avoiding static obstacle behavior and reacting to dynamic environments.
31
ACCEPTED MANUSCRIPT
The main idea of the predictive method is to divide the range sensor into four circles with different radii. These circles are divided into four areas to estimate the position of the direction of the moving obstacle. The robot should record the intersection points between the obstacle positions and these circles and determine which of these areas have these intersection points. If the prediction reveals that the number of intersection points does not change, then the obstacle is static; otherwise, the obstacle is dynamic. The direction of the moving obstacle is determined by measuring the number of these intersection points. The
CR IP T
robot avoids static obstacles by using near-to-goal priority. If the robot detects a dynamic obstacle, then the robot can recognize the position and moving direction of the obstacle by predicting the future trajectory of the obstacle. If the prediction demonstrates that the robot will collide with an obstacle, then the dynamic avoidance behavior will enable the robot to find a new path to avoid the obstacle by utilizing detouring strategy and direction priority.
AN US
In our proposed method, the planner does not require the available information about the locations, shapes, and velocities of static and dynamic obstacles, which is to be determined online using rangefinder sensors. Only the knowledge about its current and goal positions is required. We design 20 arbitrary, unknown dynamic environments that include static and dynamic obstacles, which are located at unknown dynamic positions and moving in arbitrary unknown velocities. The obstacles have different and complex
M
shapes, such as concave, convex, maze, and narrow passages. The environment for each run is different due to the random positions of the static and dynamic obstacles.
ED
The simulation outcomes confirm the success and effectiveness of the algorithm in dealing with diverse problems, from simple obstacles to extremely concave polygons. The robot can effectively reach its destination without any collision. Finally, we compare the performance of our approach with that of some
PT
famous path-planning techniques. When the environment becomes crowded with obstacles, our approach can find a safe and short path inside these crowded areas with less running time. The proposed planner
CE
successfully guides the robot in unknown dynamic environments through a relatively short path and in a few seconds of running time and with a considerably low variation in the results in different runs of the
AC
planner. The average path length for all test environments is 16.51 with a standard deviation of 0.49, which provides an average optimality rate of 89.79%. The average running time is 4.74 (the standard deviation is 0.26). Apart from the path length and running time of our algorithm, another advantage of our approach is that it is similar to the real world because it considers several real parameters, such as time, and online prediction such as unexpected obstacles and obstacle velocity vector. Thus, our approach is easy to transform into a practical application.
32
ACCEPTED MANUSCRIPT
References Ali, M. A., Mailah, M., & Hing, T. H. (2013). A novel approach for visibility search graph based path planning. Recent Advances in Electrical Engineering Series, (11) Alsaab, A., & Bicker, R. (2014). Improving velocity obstacle approach for obstacle avoidance in indoor environments. Control (CONTROL), 2014 UKACC International Conference On, 325-330.
CR IP T
Aybars, U. (2008). Path planning on a cuboid using genetic algorithms. Information Sciences, 178(16), 3275-3287. Babinec, A., Duchoň, F., Dekan, M., Pásztó, P., & Kelemen, M. (0214). VFH\ ast TDT (VFH\ ast with time dependent tree): A new laser rangefinder based obstacle avoidance method designed for environment with non-static obstacles. Robotics and Autonomous Systems, 62(8), 1098-1115.
AN US
Behroo, M., & Banazadeh, A. (2015). Near-optimal trajectory generation, using a compound B-spline interpolation and minimum distance criterion with dynamical feasibility correction. Robotics and Autonomous Systems, 74, 79-87. Boor, V., Overmars, M. H., & van der Stappen, A Frank. (1999). The gaussian sampling strategy for probabilistic roadmap planners. Robotics and Automation, 1999. Proceedings. 1999 Ieee International Conference On, , 2 1018-1023.
M
Borenstein, J., & Koren, Y. (1990). Real-time obstacle avoidance for fast mobile robots in cluttered environments. Robotics and Automation, 1990. Proceedings., 1990 IEEE International Conference On, 572-577.
ED
Borenstein, J., & Koren, Y. (1991). The vector field histogram-fast obstacle avoidance for mobile robots. Robotics and Automation, IEEE Transactions On, 7(3), 278-288.
PT
Cazangi, R. R., Von Zuben, F. J., & Figueiredo, M. F. (2006). Evolutionary stigmergy in multipurpose navigation systems. Evolutionary Computation, 2006. CEC 2006. IEEE Congress On, 370-377.
CE
Chen, X., & Li, Y. (2006). Smooth path planning of a mobile robot using stochastic particle swarm optimization. Mechatronics and Automation, Proceedings of the 2006 IEEE International Conference On, 1722-1727.
AC
Ćirović, G., Pamučar, D., & Božanić, D. (0214). Green logistic vehicle routing problem: Routing light delivery vehicles in urban areas using a neuro-fuzzy model. Expert Systems with Applications, 41(9), 4245-4258. Dijkstra, E. W. (1959). A note on two problems in connexion with graphs. Numerische Mathematik, 1(1), 269-271. Dong-Shu, W., & Hua-Fang, Y. (2011). Path planning of mobile robot in dynamic environments. Intelligent Control and Information Processing (ICICIP), 2011 2nd International Conference On, , 2 691-696.
33
ACCEPTED MANUSCRIPT
Dongshu, W., Yusheng, Z., & Wenjie, S. (2011). Behavior-based hierarchical fuzzy control for mobile robot navigation in dynamic environment. Control and Decision Conference (CCDC), 2011 Chinese, 2419-2424. Faisal, M., Al-Mutib, K., Hedjar, R., Mathkour, H., Alsulaiman, M., & Mattar, E. (2013). Multi modules fuzzy logic for mobile robots navigation and obstacle avoidance in unknown indoor dynamic environment. Proceedings of the 2013 International Conference on Systems, Control and Informatics, 371-379.
CR IP T
Faisal, M., Hedjar, R., Al Sulaiman, M., & Al-Mutib, K. (2013). Fuzzy logic navigation and obstacle avoidance by a mobile robot in an unknown dynamic environment. International Journal of Advanced Robotic Systems, 10 Ferguson, D., Kalra, N., & Stentz, A. (2006). Replanning with rrts. Robotics and Automation, 2006. ICRA 2006. Proceedings 2006 IEEE International Conference On, 1243-1248.
AN US
Fiorini, P., & Shiller, Z. (1998). Motion planning in dynamic environments using velocity obstacles. The International Journal of Robotics Research, 17(7), 760-772. Fox, D., Burgard, W., & Thrun, S. (1997). The dynamic window approach to collision avoidance. IEEE Robotics & Automation Magazine, 4(1), 23-33. Geraerts, R., & Overmars, M. H. (2004). A comparative study of probabilistic roadmap planners. Algorithmic foundations of robotics V (pp. 43-57) Springer.
M
Goel, P., & Singh, D. (2013). An improved abc algorithm for optimal path planning. Int.J.Sci.Res.(IJSR), 2(6), 261-264.
ED
Hart, P. E., Nilsson, N. J., & Raphael, B. (1968). A formal basis for the heuristic determination of minimum cost paths. Systems Science and Cybernetics, IEEE Transactions On, 4(2), 100-107.
PT
Hossain, M. A., & Ferdous, I. (2015). Autonomous robot path planning in dynamic environment using a new optimization technique inspired by bacterial foraging technique. Robotics and Autonomous Systems, 64, 137-141.
CE
Hsu, D., Jiang, T., Reif, J., & Sun, Z. (2003). The bridge test for sampling narrow passages with probabilistic roadmap planners. Robotics and Automation, 2003. Proceedings. ICRA'03. IEEE International Conference On, , 3 4420-4426.
AC
Jie, D., Xueming, M., & Kaixiang, P. (2010). IVFH∗: Real-time dynamic obstacle avoidance for mobile robots. Control Automation Robotics & Vision (ICARCV), 2010 11th International Conference On, 844-847. Karaman, S., & Frazzoli, E. (2011). Sampling-based algorithms for optimal motion planning. The International Journal of Robotics Research, 30(7), 846-894. Kladis, G. P., Economou, J. T., Knowles, K., Lauber, J., & Guerra, T. (2011). Energy conservation based fuzzy tracking for unmanned aerial vehicle missions under a priori known wind information. Engineering Applications of Artificial Intelligence, 24(2), 278-294. 34
ACCEPTED MANUSCRIPT
LaValle, S. M., & Kuffner Jr, J. J. (2000). Rapidly-exploring random trees: Progress and prospects. Lee, H., Yaniss, T., & Lee, B. (2012). Grafting: A path replanning technique for rapidly-exploring random trees in dynamic environments. Advanced Robotics, 26(18), 2145-2168. Lin, H., & Yang, C. (2015). 2D-span resampling of bi-RRT in dynamic path planning. International Journal of Automation and Smart Technology, 5(1), 39-48.
CR IP T
Llamazares, A., Ivan, V., Molinos, E., Ocana, M., & Vijayakumar, S. (2013). Dynamic obstacle avoidance using bayesian occupancy filter and approximate inference. Sensors, 13(3), 2929-2944. Ma, Q., & Lei, X. (2010). Dynamic path planning of mobile robots based on ABC algorithm. Artificial intelligence and computational intelligence (pp. 267-274) Springer.
AN US
Mallik, G. R., & Sinha, A. (2013). A novel obstacle avoidance control algorithm in a dynamic environment. Computational Intelligence for Security and Defense Applications (CISDA), 2013 IEEE Symposium On, 57-63. Maroti, A., Szaloki, D., Kiss, D., & Tevesz, G. (2013). Investigation of dynamic window based navigation algorithms on a real robot. Applied Machine Intelligence and Informatics (SAMI), 2013 IEEE 11th International Symposium On, 95-100.
M
Miao, H., & Tian, Y. (2013). Dynamic robot path planning using an enhanced simulated annealing approach. Applied Mathematics and Computation, 222, 420-437.
ED
Mohammadi, A., Rahimi, M., & Suratgar, A. A. (2014). A new path planning and obstacle avoidance algorithm in dynamic environment. Electrical Engineering (ICEE), 2014 22nd Iranian Conference On, 1301-1306.
PT
Montiel, O., Orozco-Rosas, U., & Sepúlveda, R. (2015). Path planning for mobile robots using bacterial potential field for avoiding static and dynamic obstacles. Expert Systems with Applications, 42(12), 5177-5191.
CE
Morales, N., Toledo, J., & Acosta, L. (2016). Generating automatic road network definition files for unstructured areas using a multiclass support vector machine. Information Sciences, 329, 105-124. Mou, C., Qing-xian, W., & Chang-sheng, J. (2008). A modified ant optimization algorithm for path planning of UCAV. Applied Soft Computing, 8(4), 1712-1718.
AC
Muslim, A., Kamil, F., Tang, S. H., Khaksar, W., Zulkifli, N., & Ahmad, S. A. (2016). Obstacles avoidance mobile robot system in uncertain and ever-changing surroundings. Pertanika Journal of Scholarly Research Reviews, 2(2), 103-120. Nguyen, V., Prins, C., & Prodhon, C. (2012). A multi-start iterated local search with tabu list and path relinking for the two-echelon location-routing problem. Engineering Applications of Artificial Intelligence, 25(1), 56-71. Ögren, P., & Leonard, N. E. (2005). A convergent dynamic window approach to obstacle avoidance. Robotics, IEEE Transactions On, 21(2), 188-195. 35
ACCEPTED MANUSCRIPT
Orozco-Rosas, U., Montiel, O., & Sepúlveda, R. (2015). Pseudo-bacterial potential field based path planner for autonomous mobile robot navigation. International Journal of Advanced Robotic Systems, 12 Seder, M., & Petrovic, I. (2007). Dynamic window based approach to mobile robot motion control in the presence of moving obstacles. Proceedings 2007 IEEE International Conference on Robotics and Automation, 1986-1991.
CR IP T
Sezer, V., & Gokasan, M. (0210). A novel obstacle avoidance algorithm:“Follow the gap method”. Robotics and Autonomous Systems, 60(9), 1123-1134. Shiller, Z. (2015). Off-line and on-line trajectory planning. Motion and operation planning of robotic systems (pp. 29-62) Springer. Sipahioglu, A., Yazici, A., Parlaktuna, O., & Gurel, U. (2008). Real-time tour construction for a mobile robot in a dynamic environment. Robotics and Autonomous Systems, 56(4), 289-295.
AN US
Sun, X., Li, N., & An, C. (2015). Ming yue. Journal of Dynamic Systems, Measurement, and Control, 137, 101006-101001. Tomita, M., & Yamamoto, M. (2009). A sensor based navigation algorithm for moving obstacles assuring convergence property. Mva, 295-299.
M
Wu, Z., & Feng, L. (2012a). Obstacle prediction-based dynamic path planning for a mobile robot. International Journal of Advancements in Computing Technology, 4(3)
ED
Wu, Z., & Feng, L. (2012b). Obstacle prediction-based dynamic path planning for a mobile robot. International Journal of Advancements in Computing Technology, 4(3)
PT
Zhong, X., Peng, X., & Zhou, J. (2011). Dynamic collision avoidance of mobile robot based on velocity obstacles. Transportation, Mechanical, and Electrical Engineering (TMEE), 2011 International Conference On, 2410-2413.
CE
Zhu, Q., Yan, Y., & Xing, Z. (2006). Robot path planning based on artificial potential field approach with simulated annealing. Intelligent Systems Design and Applications, 2006. ISDA'06. Sixth International Conference On, , 2 622-627.
AC
Zhu, Y., Zhang, T., Song, J., & Li, X. (2012). A new bug-type navigation algorithm for mobile robots in unknown environments containing moving obstacles. Industrial Robot: An International Journal, 39(1), 27-39. Zucker, M., Kuffner, J., & Branicky, M. (2007). Multipartite RRTs for rapid replanning in dynamic environments. Proceedings 2007 IEEE International Conference on Robotics and Automation, 16031609.
36