c Consult author(s) regarding copyright matters...

33
This may be the author’s version of a work that was submitted/accepted for publication in the following source: Miao, Hui & Tian, Glen (2013) Dynamic robot path planning using an enhanced simulated annealing ap- proach. Applied Mathematics and Computation, 222, pp. 420-437. This file was downloaded from: https://eprints.qut.edu.au/62208/ c Consult author(s) regarding copyright matters This work is covered by copyright. Unless the document is being made available under a Creative Commons Licence, you must assume that re-use is limited to personal use and that permission from the copyright owner must be obtained for all other uses. If the docu- ment is available under a Creative Commons License (or other specified license) then refer to the Licence for details of permitted re-use. It is a condition of access that users recog- nise and abide by the legal requirements associated with these rights. If you believe that this work infringes copyright please provide details by email to [email protected] License: Creative Commons: Attribution-Noncommercial-No Derivative Works 2.5 Notice: Please note that this document may not be the Version of Record (i.e. published version) of the work. Author manuscript versions (as Sub- mitted for peer review or as Accepted for publication after peer review) can be identified by an absence of publisher branding and/or typeset appear- ance. If there is any doubt, please refer to the published source. https://doi.org/10.1016/j.amc.2013.07.022

Transcript of c Consult author(s) regarding copyright matters...

Page 1: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

This may be the author’s version of a work that was submitted/acceptedfor publication in the following source:

Miao, Hui & Tian, Glen(2013)Dynamic robot path planning using an enhanced simulated annealing ap-proach.Applied Mathematics and Computation, 222, pp. 420-437.

This file was downloaded from: https://eprints.qut.edu.au/62208/

c© Consult author(s) regarding copyright matters

This work is covered by copyright. Unless the document is being made available under aCreative Commons Licence, you must assume that re-use is limited to personal use andthat permission from the copyright owner must be obtained for all other uses. If the docu-ment is available under a Creative Commons License (or other specified license) then referto the Licence for details of permitted re-use. It is a condition of access that users recog-nise and abide by the legal requirements associated with these rights. If you believe thatthis work infringes copyright please provide details by email to [email protected]

License: Creative Commons: Attribution-Noncommercial-No DerivativeWorks 2.5

Notice: Please note that this document may not be the Version of Record(i.e. published version) of the work. Author manuscript versions (as Sub-mitted for peer review or as Accepted for publication after peer review) canbe identified by an absence of publisher branding and/or typeset appear-ance. If there is any doubt, please refer to the published source.

https://doi.org/10.1016/j.amc.2013.07.022

Page 2: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Applied Mathematics and Computation, vol. 222, pp. 420-437, 1

Oct 2013. DOI: 10.1016/j.amc.2013.07.022

Dynamic robot path planning using an

enhanced simulated annealing approach

Hui Miao and Yu-Chu Tian 1

School of Electrical Engineering and Computer Science, Queensland University ofTechnology, GPO Box 2434, Brisbane QLD 4001, Australia.

Abstract

Evolutionary computation is an effective tool for solving optimization problems.However, its significant computational demand has limited its real-time and on-lineapplications, especially in embedded systems with limited computing resources, e.g.,mobile robots. Heuristic methods such as the genetic algorithm (GA) based ap-proaches have been investigated for robot path planning in dynamic environments.However, research on the simulated annealing (SA) algorithm, another popular evo-lutionary computation algorithm, for dynamic path planning is still limited mainlydue to its high computational demand. An enhanced SA approach, which integratestwo additional mathematical operators and initial path selection heuristics into thestandard SA, is developed in this work for robot path planning in dynamic envi-ronments with both static and dynamic obstacles. It improves the computing per-formance of the standard SA significantly while giving an optimal or near-optimalrobot path solution, making its real-time and on-line applications possible. Usingthe classic and deterministic Dijkstra algorithm as a benchmark, comprehensivecase studies are carried out to demonstrate the performance of the enhanced SAand other SA algorithms in various dynamic path planning scenarios.

Key words: Path planning, dynamic environment, simulated annealing algorithm,genetic algorithm, heuristics

1 Y.-C. Tian is the corresponding author of this paper. Email address:[email protected].

Preprint submitted to Elsevier Preprint Version on June 28, 2011

Page 3: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

1 Introduction

Mobile robots are widely used in various applications; typical examples areindustrial robots deployed in hazardous fields where there may be dangers forpeople, e.g., aerospace systems, nuclear applications, and mining equipment.Path planning for mobile robots is one of the most important aspects in robotnavigation. To find an safe path in a dangerous environment for a mobile robotis an essential requirement for the success of any such mobile robot project.When an optimal path planning problem is formulated as an optimizationproblem, solving the problem is also of great importance in theoretical andcomputational investigations [1]

The main goal of the robot path planning is to search a safe path for a mobilerobot, to make the robot move from the start point to the destination pointwithout collision with obstacles. Also, the path is often required to be optimalin order to reduce energy consumption and communication delay.

Depending on the environment in which the robot is located, Existing methodsfor robot path planning can be classified into the following two categories: 1)Path planning in a static environment with static obstacles in the map; and2) Path planning in a dynamic environment with both static and dynamicobstacles in the map. Each of these two categories of methods could be furtherdivided into two sub-groups depending on how much the robot knows aboutthe entire information of the surrounding environment:

• Path planning in a clearly known environment, in which the robot alreadyknows the location of the obstacles before it starts to move. Because theenvironment is fully known, the path for the robot could be globally opti-mized.

• Path planning in a partially known or uncertain environment, in which therobot probes the environment using sensors to acquire the information aboutthe location, shape, and size of the obstacles, and then uses the informationfor local path planning.

Dynamic path planning is the most difficult task among all path planningscenarios, and is the focus of this work.

Evolutionary computation is an effective tool for solving optimization prob-lems. However, it demands significant computational power, limiting its real-time and on-line applications, particularly in embedded systems with limitedcomputing resources, e.g., mobile robots. Heuristic methods such as the geneticalgorithm (GA) based approaches have been shown to be a promising tool forrobot path planning in dynamic environments. However, investigations intothe simulated annealing (SA) algorithm, another popular evolutionary com-putation algorithm, for dynamic path planning are still limited mainly due

2

Page 4: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

to its high computational demand. This paper will develop an enhanced SAapproach with integration of two additional mathematical operators and ini-tial path selection heuristics into the standard SA for robot path planning indynamic environments with both static and dynamic obstacles. It improvesthe computing performance of the standard SA significantly while giving anoptimal or near-optimal robot path solution, making its real-time and on-lineapplications possible.

The paper is organized as follows. Following this introductory section, Section2 discusses related work and motivations. An enhanced SA approach is de-veloped in Section 3 for dynamic path planning. The architecture, algorithmdesign, and initial path selection heuristics of the enhanced SA are discussedin detail in this section. Using the classic Dijkstra algorithm as a benchmark,Sections 4 and 5 demonstrates the performance of the enhanced SA throughcomprehensive case studies in five dynamic environments. Finally, Section 6concludes this paper.

2 Related Work and Motivations

2.1 Related Work on Dynamic Path Planning

Given the entire information of an environment in which a robot is located,the globally optimal or near-optimal path can be found by using optimizationalgorithms, e.g., the genetic algorithm (GA) [2]. Tarokh [3] has developed anintelligent path planning approach for highly mobile robots operating in roughenvironments. The approach consists of characterization of the environmentusing fuzzy logic, and two-stage GA planners with one being global and theother being local. The global planner determines the path that optimizes acombination of terrain roughness and path curvature; while the local plan-ner uses sensory information, and when previously unknown and unaccountedobstacles are detected, performs on-line re-planning to get around the newlydiscovered obstacles. Cheng et al. [4] has proposed a path planner that com-bines the GA with dynamic programming to solve a path planning problemof autonomous underwater vehicles. Recently, Tuncer and Yildirim [5] hasproposed an improved GA algorithm for dynamic path planning of mobilerobots through using a new mutation operator to avoid infeasible paths andpremature convergence.

Nearchou [6] uses the number of vertices produced in visibility graphs to buildfixed length chromosomes in which the presence of a vertex within the pathis indicated by setting a bit at an appropriate locus. A re-ordering operator isapplied for performance enhancement; and the proposed algorithm is capable

3

Page 5: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

of determining a near-optimal solution.

The Dijkstra algorithm is a classic and deterministic algorithm for searchingthe shortest path in a graph with weighted edges. Kang et al. [7] and Wei andLiu [8] have demonstrated typical implementations of the Dijkstra algorithmfor robot path planning. The main drawback of the Dijkstra algorithm is itscomputing inefficiency. The A* algorithm described in Russell [9] introducesheuristics into the Dijkstra algorithm to improve its computing performancewith the focus on minimizing the processing time.

Evolved from the A* shortest-path algorithm, an improved algorithm is de-veloped by Hu and Gu [10] to solve the problem of optimal route planning invehicle navigation systems. It is based on the standard GA and the lambda-interchange local search method. It can find the optimum route efficientlywithout any network constraint conditions and can work well in either contin-uous or discrete networks.

However, in many applications such as those described in Ayers [11] andWilliams and Mahon [12], it is an unrealistic assumption that a robot can getthe full information of the surrounding environment at any one time becausethe status and movement of the obstacles in the environment may change overthe time. A feasible path solution may become infeasible due to the changes inthe environment. To overcome this problem, the robot should have the abilityto sense the environment and to plan the path on-line and in real-time. In adynamic environment, how to manipulate a robot to travel to the destinationsafely and optimally without collisions with obstacles is an important issuefor both fundamental research and practical development.

Limited work has been reported on optimal path planning for mobile robotsin dynamic environments. Chakravorty and Junkins [13] have introduced amethodology for intelligent path planning in uncertain environments. Themethod models the planning problem as a Markov decision process, which ischaracterized by a known, control-dependent exploration system and an un-known, uncontrollable environment. The exploration system is an intelligentadaptive control system; while the probability that governs the environmentprocess is estimated via a Monte-Carlo-based estimation scheme using visionsensors. The method is demonstrated for a mobile rover in a completely un-known terrain. A recent work in mobile path planning is by Mohajer et al. [14],in which an online random particle optimization algorithm is proposed withconsideration of dynamic environments. Another recent work on this topic isby Nakhaeinia and Karasfi [15], in which a behavior-based approach is de-veloped through using fuzzy logic for collision avoidance of mobile robots inunknown and dynamic environments.

In the article by Tan et al. [16], a set of path planning tools have been devel-

4

Page 6: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

oped for racing games with moving obstacles and featuring multiple sourcesand destinations. The tools include path generator, cost map generator andpath editor. Our work in this paper does not deal with multiple sources anddestinations explicitly though it does addresses moving obstacles.

Kala, Shukla and Tiwari [17] has attempted to solve the problem of dynamicpath planning using two-layer hierarchical evaluation algorithms. The coarserpath planner finds the path in a static environment with a known entire roboticmap, while the finer planner takes a section of the map and computes the pathfor both static and dynamic environments. In comparison, we will deal with asingle path planner in this work.

Wang et al. [18] have presented a GA planner to determine optimal or near-optimal path solutions for mobile robots in dynamic environments. A hybridGA technique is also employed to deal with multicriteria-multistage path plan-ning [19]. The GA based approach is shown to be a promising tool for dynamicpath planning though its computational efficiency still needs to be improved.

Considering soccer robots, Zhang, Lu, and Song [20] have developed an artifi-cial potential field algorithm for dynamic path planning in which both targetand obstacles are moving. For solving the local minimum problem, an sim-ulated annealing (SA) algorithm has been integrated into the method. Thepotential field technique has been recently employed in a dynamic subgoalpath planner for mobile agents in large scenario scales and unpredictable en-vironments [21].

From the classic and deterministic Dijkstra method, the D* and A* methodshave been developed for path planning. The D* method in Stentz [22], whichis the dynamic A*, is a typical method for path planning in dynamic and un-known environments. It plans optimal traverses in real-time by incrementallyrepairing the paths to the robot’s state when new environment informationbecomes known to the robot, making it possible to reduce the computationalcost significantly.

Improvements have been made to the D* algorithm to further enhance itsperformance. Representative improvements include the framed-quadatree D*method in Yahja et al. [23], the field D* method in Ferguson and Stentz [24]and others [25–27].

The framed-quadatree D* method uses the quadatree structure to representdynamic environments. In order to minimize the search space, different dimen-sions of grids are used in the quadatree structure and border cells are addedto connect the grids. However, because many sub-cells have to be created, theperformance of this method deteriorates greatly as the fractal gain increases,especially in off-line planning [23].

5

Page 7: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

The field D* method [24] employs an interpolation-based planning and re-planning algorithm to generate smooth paths through non-uniform cost grids.It can produce a smooth optimal path for a robot to overcome the sub-optimalproblem appearing in other non-uniformed-girds methods. However, it scarifiesthe performance for the accuracy: it reduces the path length in off-line andon-line planning but takes 1.8 times longer in calculation than the standardD* method [24].

Willms and Yang [28] proposed a dynamic system for real-time robot pathplanning. Recently, they further developed a grid-based algorithm via a distance-propagating dynamic system [29]. The algorithm is similar to the D* algo-rithm, but it does not maintain a sorted queue of points to update. Instead,it uses local information when computing an update at each point; and theorder of updating is pre-determined. This makes the algorithm easy to paral-lelize by simply assigning a subset of points to each processor. Consequently,it becomes more efficient than the D* algorithm when obstacles and targetsare moving at substantial distances from their current locations.

To reflect the advances in the broad area of robot learning, IEEE publisheda special issue on this topic in 2007 in IEEE Transactions on Systems, Manand Cybernetics Part B [30]. Several articles in this special issue are related torobot path planning and navigation. Among some recent developments in dy-namic path planning are Padula and Perdereau [31] and Do et al. [32]. Padulaand Perdereau [31] presented an online path planner for an industrial manip-ulator to avoid obstacles through using the concept of potential fields; whileDo et al. [32] proposed a dynamic path planning method based on supportvector machine among multiple moving obstacles for autonomous vehicles.

2.2 Motivations of This Work

The two methods reported in Zhang, Lu and Song [20] and Xie and Xie [33]use a simplified representation of obstacles: an obstacle is considered as a pointor a simple square block which could generate a repulsive force to robots. Itis noticed that most of the published papers that use the artificial potentialfield method have ignored the dimensions of the obstacles. As a results, suchmethods are not suitable for optimal path searching in the environments witha variety of sharp obstacles. Therefore, the route generated for those methodsis imprecise; and obtaining the real optimal solution becomes challenging.

Focusing on robot path planning in uncertain environments in which anychanges such as the appearance and disappearance of one or more obsta-cles can be detected by robot sensors [34], the D* method [22] and its variants[23–26,29] use grids to represent the environments. However, moving obstacles

6

Page 8: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

can be described more easily using obstacle vertices. Unfortunately, the resultsfrom Nearchou [6] and Yahja, et al. [23] show that the computational time ofthe searching process in vertices based methods increases exponentially withthe increase of the number of the vertices in the map. This may make thevertices based methods unacceptable for a specific application. This motivatesthe research including this work for efficient manipulation of obstacle verticesfor dynamic path planning.

As an effective tool for solving optimization problems, the GA algorithm, apopular evolutionary computation algorithm, has been investigated for dy-namic path planning [18,19]. However, when dealing with complex environ-ments, GA based approaches consume significant time [18], thus limiting theirapplications in many practical systems. For example, in order to guide a robotto avoid any potential collisions with obstacles, the GA method in Wang, etal. [18] assumes that an adequately large time interval is allowed between thedetection of obstacle movements and the implementation of newly generatedactions. The corresponding results [18] show that for an environment with 14static obstacles and 5 dynamic obstacles, about 10 seconds are required tofind the first feasible path.

The SA algorithm, another popular evolutionary computation algorithm, hasbeen investigated for searching optimal path in static path planning [20,35,36].It is easier to implement than the GA as the GA uses a population thatcontains a collection of chromosomes rather than a single solution. It alsoperforms better than the GA when the problems size increases significantly[35]. According to Balachandar and Kannan [37], the SA can provide similarand even better results than the GA in general optimization searches. It isalso noticed that the SA is shown in Nearchou [6] to behave slightly worsethan the GA in static path planning; but this may not be a general conclusionbecause:

(1) The SA is more sensitive to its control parameters, e.g., initial tempera-ture and cooling rate. In Nearchou [6], only one set of control parametersis tested for three different scenarios. The performance of the SA couldbe improved if the control parameters are better tuned.

(2) Only one operator that flips some bits is used in Nearchou [6] to generatea new solution. This means that the possibility of jumping out of thelocal minimum is small. Using more operators may benefit performanceimprovement.

(3) Searching the initial path is not efficient in Nearchou [6], and heuristicscan be introduced for improving the performance significantly.

However, research on the SA for dynamic path planning is still limited. There-fore, it is worth investigating whether or not the SA is suitable for robot pathplanning in dynamic environments. This work will give a positive answer to

7

Page 9: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

this question through developing an enhanced SA approach, which integratestwo additional mathematical operators and initial path selection heuristics.Some preliminary results of this work have been presented in ICARCV’2008conference [38].

3 Enhanced Simulated Annealing Approach

This section develops an enhanced SA approach for robot path planning indynamic environments. It begins with a discussion in Subsection 3.1 on howto characterize a dynamic environment. Then, the architecture and algorithmstructure of the enhanced SA are presented in Subsections 3.2 and 3.3, re-spectively. After that, Subsection 3.4 proposes initial path section heuristics,and Subsection 3.5 highlights the random path planner with two additionaloperators. The section ends with a discussion in Subsection 3.6 on on-line pathplanning in presence of moving obstacles.

3.1 Dynamic Environments

This work considers dynamic environments with both static and moving obsta-cles. The obstacles in the environments are represented by bounded polygons.Thus, the movement and trajectory of a dynamic obstacle are constituted by aseries of polygons with their positions being updated along with the time. Thevertices of the obstacles form the search space of our path planning algorithm.

The following assumptions are made in this work:

(1) The movement and trajectory of a moving obstacle in the environmentare unknown to the robot through sensors;

(2) The motion parameters, e.g., speed and direction, of the dynamic obstaclecan also be sensed by the robot if the obstacle is in the range of the robotsensors;

(3) The robot can change its moving direction at any time when necessary;(4) As in Wang, et al. [2], all obstacles in the map are enlarged by a fixed

value so that the robot can approach the obstacles without collision; and(5) The dimension of the robot is neglected, and consequently the robot is

regarded as a single point.

Fig. 1 shows a dynamic environment, where the black polygons represent thestatic obstacles and the hollow polygons are moving obstacles. All obstaclesare enlarged by some values through creating additional margins.

8

Page 10: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

3.2 Architecture of the Enhanced SA Approach

The decision-making process of the proposed approach consists of the followingtwo stages:

(1) Off-line path computation based on the information of static obstacles;and

(2) On-line path computation once one or more moving obstacles are detectedby the robot sensors.

The enhanced SA begins with off-line path computation, in which the locationsof the vertices of all static obstacles are known to the robot. After completingthe off-line computation, the robot starts to travel through the static obstacles.

When a moving obstacle enters the detection range of the robot sensors, itwill be detected together with its moving speed and direction. Then, the robotcalculates the possibility of clashing of the robot with the moving obstacle. Ifthe calculation shows that the moving obstacle will not hit the robot, the robotwill keep travelling using the current path. Otherwise, if the robot will likelycollide with the obstacle with the current movement, an alternative path fromthe current location of the robot to the destination will be generated throughon-line computation.

As shown in Fig. 2, a mathematical model can be established for calculatingthe possibility of clashing of the robot with the moving obstacle [18]. Thefirst crossing point of the current robot path and the predicted trajectory ofthe moving obstacle in Fig. 2 can be estimated using the method presentedin Wang, et al. [18]. Then, the time required for the robot to travel from itscurrent location to the first crossing point can be derived; and the locationand consequently the corresponding exclusion area of the moving obstacle canalso be estimated after the obstacle moves forward for the same amount oftime. If the robot path segment from the first crossing point to either of thetwo directions of the path crosses the edges of the moving obstacle odd times,then a collision will likely occur between the robot and the moving obstacle;otherwise, a collision will unlikely happen.

3.3 Algorithm Structure

A feasible path solution is expressed by a series of vertices linking the startpoint through to the end point. Each vertex of the obstacles has its seriesnumber; and thus a path is represented by a sequence of vertex numbers.

9

Page 11: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Therefore, a feasible path solution X is described as:

X = {Vstart, Vstart+1, Vstart+2, · · · , Vend−1, Vend} (1)

where Vi means the ith vertex.

Traditionally, the length of the path, Ef , is used as a criterion to quantifythe quality of the path solution derived from a path planning algorithm: theshorter the path, the better the solution. The evaluation function Ef is givenby:

Ef =end−1∑

i=start

D(Vi, Vi+1) (2)

where D(Vi, Vi+1) is the direct distance from Vi to Vi+1.

Fig. 3 shows the top-level algorithm structure of the enhanced SA for dynamicpath planning. The pseudo-code of the algorithm is given in Algorithm 1,which is self-explained.

Algorithm 1. Enhanced SA for dynamic path planning.

1. T = Tinitial;2. While (T > Tterminate)3. Randomly generate a feasible solution Xs;4. Evaluate Xs, Ef = f(Xs);5. count = 1;6. While (count < Threshold)7. Generate a new feasible solution Xn base on Xs;8. Evaluate Xn; En = f(Xn);9. If f(Xn) < f(Xs) Then10. Xs = Xn;11. Elseif rand(1) < exp

(

f(Xs)−f(Xn)T

)

Then12. Xs = Xn;13. count = count+ 1;14. End-if15. End-while16. T = cool rate ∗ T ;17. Update Xs at each reduction of temperature T ;18. End-while19. Xs is the optimal or near-optimal path solution;20. Return

10

Page 12: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

3.4 Initial Path Selection Heuristics

Like many other path planning algorithms, the enhanced SA starts from aninitial path Xs. From the initial path solution, the search process goes alongthe “down hill” movement. To avoid the local minimum problem, as temper-ature goes down, the algorithm also accepts “up hill” movement.

Therefore, finding a good initial solution is critical for enhancing the effi-ciency and performance of a search approach. It is, however, difficult and timeconsuming. This work introduces heuristics into initial path selection for sig-nificant improvement of the performance of the SA in dynamic path planning.The procedure of the heuristic initial path section is described below:

1) Randomly select a vertex of one obstacle in the map, and connect the currentpoint of the robot, which is the start point at the beginning, to the selectedvertex.

2) Test the feasibility of this connection. If the connection intersects with anyobstacles, the connection is infeasible; otherwise, it is feasible, i.e., the robotcan safely travel to the selected vertex.

3) If the connection is infeasible, the robot stays at the current point and goback to Step 1) to randomly reselect another vertex; otherwise, go to thenext step.

4) If the connection is feasible, move the robot to the selected vertex and goto the next step.

5) If the vertex is not the end point (destination), go back to Step 1) to searchanother feasible vertex; otherwise, go to the next step.

6) The vertex is the end point. Exit with success.

To make the above procedure even more efficient, more heuristics are designedin this work. After a feasible vertex is selected, an end point feasibility test iscarried out before randomly selecting another vertex. The purpose is to findout whether or nor the path segment between the current vertex and the endpoint is feasible. If this path segment is feasible, use the end point as the nextfeasible vertex and complete the initial path selection. Therefore, Step 5) inthe above procedure is modified to the following 5’):

5’) If the vertex is not the end point (destination), carry out an end pointfeasibility test. If the test is infeasible go back to Step 1) to search anotherfeasible vertex; otherwise select the end point as the next feasible vertex,and move the robot to the end point.

11

Page 13: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

3.5 Random Path Planner with two Additional Operators

Different from a simple path planner that was previously used in Nearchou [6],a more efficient random path planner is developed in this work by introduc-ing two additional operators, deleting and switching operators. The deletingoperator, as shown in Fig. 4, randomly deletes a vertex from the initial pathXs; while the switching operator randomly swaps two vertices in Xs. The pathplanner randomly chooses an operator to generate a new path Xn from theinitial path Xs by flipping some bits of Xs.

As in the procedure for heuristic initial path selection (Subsection 3.4), thefeasibility of each path segment generated by the operators is tested. This isto ensure that the path segment does not intersect with any edges in the map.

When the length of the path is chosen as the evaluation criterion, randomlydeleting vertices could help improve the performance of the path solution.Therefore, the possibility of choosing the deleting operator is set to be higherthan that of selecting the switching operator. It is set to be 78% in our casestudies to be carried out later.

After a new path solution is generated by using either the deleting or switchingoperator, it is evaluated using the evaluation criterion, i.e., the length of thepath. It is accepted if it is better than the previous one. To help overcomethe local minimum problem, it may also be accepted in a certain probabilitydefined by the current temperature even if it is not better than the previousone.

3.6 On-Line Path Planning

As discussed in Section 3.2, while a robot uses the route generated by off-lineplanning to travel through static obstacles, the on-line path planner is trig-gered automatically to calculate an alternative path when a dynamic obstacleis detected. As no particular brand or configuration of the sensors is specified,the sensing range of the robot sensors is set to be a fixed value. If the distancesbetween the robot and every vertex of the moving obstacle is shorter than thefixed value, the moving obstacle enters the sensing range of the robot and thuscan be detected by the robot sensors.

It has assumed that robot sensors can monitor the shape and trajectory of amoving obstacle as well as the moving speed and direction. After acquiringthe moving information of the obstacle by using the model from Section 3.2,the robot could infer the possibility of collision with the moving obstacle.

12

Page 14: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

When it is inferred that the robot will collide with the moving obstacle, theenhanced SA uses the model from Subsection 3.2 to predict the position of thecollision area. Then, consider the predicted collision area as a new obstaclewith vertices. After that, update the search space, the status of the robot,and the new predicted collision location and moving information of the mov-ing obstacle to generate a new map. Finally, an alternative path is searchedfrom this map to allow the robot to move from its current location to thedestination.

A “good” dynamic path planning algorithm is expected to be efficient, as wellas effective, so that if a collision is likely to occur the robot could quicklychange its travel direction to avoid the potential collision. The performanceof the enhanced SA for dynamic path planning computation will be evaluatedlater through comprehensive case studies.

4 Case Studies

4.1 Simulation Environments and Parameters

Our comprehensive case studies are carried out in Matlab under Windows XPon a computer with 2.8GHz Pentium Core 2 Duo CPU and 2GB memory.

As shown in Table 1, five dynamic environments containing both static anddynamic obstacles are designed to test the performance of the enhanced SAapproach. The first two environments simulate simple scenarios where the dy-namic obstacles appear simultaneously and simply move forward in the samedirection. With more static and dynamic obstacles, the last three environ-ments represent more complicated scenarios where the dynamic objects eachappears at a random time and moves either forward or backward. The dynamicobstacles have random shapes in all five environments.

For each of the five environments, the number of the vertices of the staticobstacles tabulated in Table 1 is used for off-line path planning before the robotstarts to travel. The location information of the static obstacles is assumed tobe fully known to the robot for off-line planning.

For comprehensive performance comparisons, four versions of SA are imple-mented in the case studies: the standard SA (without multiple mathematicaloperators and without initial path selection heuristics), the SA with multiplemathematical operators (SA MO), the SA with heuristic initial path selection(SA HIPS) and the enhanced SA with multiple mathematical operators andinitial path selection heuristics). Each SA approach runs 80 times for each of

13

Page 15: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

the five environments.

The classic and deterministic Dijkstra algorithm can guarantee the generationof the optimal path in robot path planning. Various A* and D* methods arevariants of the the Dijkstra algorithm by adding some heuristic weight func-tions. The heuristic weight functions are different in different situations, andthus may improve or reduce the efficiency of the Dijkstra algorithm. Therefore,the Dijkstra algorithm adopted in Anastopoulos and Nikas [39] is implementedin our case studies as a benchmark.

For the Dijkstra algorithm and all four versions of the SA, the performance isoptimized for path length.

The control parameters of the SA are tabulated in Table 2. According toShakouri, et al. [40], a higher initial temperature can help the SA to step outof the local minimum problem and thus to improve the quality of the finalresults though it will increase the computation time. Because the heuristicinitial path selection process in the enhanced SA helps reduce the computationtime significantly, the initial temperature is set to big to enhance the qualityof the path planning results. The probabilities of choosing the Deleting andSwitching operators are set to be 78% and 22%, respectively.

4.2 Simulation Results for Environment One

Environment One contains two dynamic obstacles which appear simultane-ously as well as three static obstacles with ten vertices. It is depicted in Fig.5, where the black and fully filled blocks represent static obstacles, and thehollow triangles show the trajectories of the dynamic obstacles. The arrowsindicate the moving directions of the dynamic obstacles. The sequence of thepoints in the figure is the travel trajectory of the robot from the start to theend points.

All four versions of the SA and the Dijkstra can re-plan the path successfullywhen moving obstacles are detected, and thus no collision has occurred in Fig.5.

Table 3 lists the simulation results of off-line processing time, on-line process-ing time and path length. The results show that all approaches have similarpath length except the standard SA which gives the longest path length. Foroff-line and on-line processing times, The Dijkstra behaves beats all four SAimplementations; the SA MO and SA HIPS outperforms the standard SA; andthe enhanced SA performs slightly better than the the SA MO and SA HIPS.

14

Page 16: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

4.3 Simulation Results for Environment Two

Compared with Environment One, Environment Two also contains two dy-namic obstacles which appear simultaneously. However, the number of staticobstacles is doubled (i.e., six static obstacles altogether) in Environment Two.The total number of the vertices of the static obstacles is 25, compared to 10in Environment One.

Fig. 6 shows Environment Two and its simulation results for the four versionsof the SA and the Dijkstra. Again, as in Environment One, all five algorithmscan re-plan the path successfully when moving obstacles are detected. Thus,no collision has happened in Fig. 6.

Table 3 tabulates some quantitative performance results of off-line processingtime, on-line processing time and path length for Environment Two. It is seenfrom this table that the the standard SA behaves the worst in both processingtime and path length. The enhanced SA performs better than the SA MOand SA HIPS, which generate comparable results. In comparison with theDijkstra, the enhanced SA gives comparable path length but consumes muchmore time for off-line and on-line processing.

4.4 Simulation Results for Environment Three

Environment Three is more complicated than Environment Two. Additionalfour static and two dynamic obstacles are present in the environment. Thereare nine static obstacles and four dynamic obstacles altogether; and the num-ber of the vertices of the static obstacles reaches 53.

Unlike what we have simulated in the last two environments, the dynamicobstacles in Environment Three do not appear simultaneously. Furthermore,the trajectory of one dynamic obstacle is not a strait line, i.e., the dynamicobstacle changes its direction during movement.

Fig. 7 shows Environment Three and its simulation results. No collision hasoccurred in all simulated algorithms, implying that all these algorithms canre-plan the path successfully when moving obstacles are detected.

Some quantitative simulation results for Environment Three are given in Ta-ble 3. It is seen from this table that the standard SA behaves much worse thanall other algorithms in all three performance criteria: path length, off-line pro-cessing time and on-line processing time. The SA MO and SA HIPS improvesthe standard SA noticeably. Giving comparable performance, the enhancedSA and Dijkstra outperforms the SA MO and SA HIPS.

15

Page 17: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

4.5 Simulation Results for Environment Four

Modeling a more complicated scenario, Environment Four contains fourteenstatic obstacles and six dynamic obstacles altogether. The number of the ver-tices of the static obstacles is 82. The dynamic obstacles appear randomly atdifferent times and move in different directions. They also change their movingdirections during movement.

Fig. 8 shows Environment Four and its simulation results. Again, the robotdoes not collide with any obstacles in all five algorithms, implying that allthese five methods work well in re-planning of the robot path.

Quantitative results for Environment Four are summarized in Table 3. It isseen that the enhanced SA outperforms all other methods in off-line and on-line processing times while generating a path solution with comparable lengthto that from the Dijkstra algorithm. The standard SA gives the worst perfor-mance. The SA MO and SA HIPS improve the standard SA but are not asgood as the the enhanced SA and Dijkstra.

4.6 Simulation Results for Environment Five

Environment Five is the most complicated scenario in our case studies. Thereare twenty static obstacles and eight dynamic obstacles altogether in the en-vironment. The number of the vertices of the static obstacles is 107. Thedynamic obstacles appear randomly at different times and move in differentdirections.

Fig. 9 shows Environment Five and its simulation results. Again, all five im-plemented methods work well in-planning of the robot path when movingobstacles are detected, and consequently no collision has occurred in Fig. 9.

Quantitative results for Environment Five are depicted in Table 3. Onceagain, the standard SA behaves with the worst performance. The SA MOand SA HIPS improve the standard SA significantly. The Dijkstra algorithmgives the shortest path; and the enhanced SA consumes the shortest time foroff-line and on-line processing while achieving a path length quite comparablewith that from the Dijkstra algorithm.

16

Page 18: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

4.7 Further Performance Analysis

The performance of the five methods has been analyzed for each of the fiveenvironments. Further performance analysis is conducted below across the fiveenvironments. The analysis data are taken from Table 3.

Fig. 10 graphically compares the path length performance of the five methodsacross all five environments. It is seen from Fig. 10 that the path length per-formance of all four SA methods deteriorates when the environment becomesmore complicated. With the increase of the complexity of the environment,the improvement of the enhanced SA over the standard SA and other two SAsbecomes more evident. For example, in Enviromnent Five, the path lengthfrom the enhanced SA is about 12.9% shorter than that from the standardSA. As expected, the Dijkstra always gives the shortest path solution, whilethe enhanced SA can provide near optimal results.

Fig. 11 demonstrates the off-line processing time performance of the five meth-ods for all five environments. It is seen from Fig. 11 that the enhanced SAis significantly superior to all other methods when the environment becomesmore complicated. For example, for Environment Five, the enhanced SA im-proves the off-line processing time by 87.3%, 86.7%, 71.7% and 41.8% overthe standard SA, SA MO, Dijkstra and SA HIPS, respectively. Such improve-ments are dramatic.

Fig. 12 compares the on-line processing time performance of the five methodsin all five environments. It gives clear evidence of the superiority of the en-hanced SA to all other methods when the environment becomes complicated.For Environment Five, the enhanced SA consumes 90.8% less time to re-planthe path than the standard SA, 89.8% less time than the SA MO, 71.4% lesstime than the Dijkstra, and 58.1% less time than the SA HIPS.

Overall, when the environment becomes more complicated, the enhanced SAdeveloped in this work consumes much less processing time than all otherfour methods while providing a near-optimal path solution. Although the Di-jkstra algorithm always gives the shortest path length, its processing timeperformance becomes significantly worse than that of the enhanced SA in acomplicated dynamic environment. Among the five methods investigated inthe case studies, the standard SA does not behave well in all simulated envi-ronments, and thus is less useful than the others for robot path planning indynamic environments.

17

Page 19: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

5 Statistical Analysis of the Results

Because the SA algorithm is a stochastic optimization method that highlyrelies on the randomization of the solution candidates. Therefore, the meanvalue of the results from eighty runs in each case does not fully capture theglobal characteristics of the optimized results. Statistical analysis of the simu-lation results presented in Section 4 is carried out in this section to build ourconfidence on the enhanced SA approach for robot path panning in dynamicenvironments.

Ideally, the probability of extreme results, e.g., enormous huge or small off-lineprocessing time, should be small; and the experimental results should appearvery close to the mean value and form a normal distribution. This can beobserved through the distribution graph of the simulation results, and can bequantitatively evaluated through t-test, which is a statistical hypothesis test.

Fig. 13 shows the statistical histograms of the off-line processing time resultsof the enhanced SA. Each of the histograms is plotted from eighty runs. Allthese histograms look close to a normal distribution.

Quantitative t-test results using MATLAB’s ttest() routine show that for eachof the five environments, the null hypothesis that the simulation results comefrom a normal distribution with the mean value shown in Table 3 cannot berejected at the significance level of 5%.

Other t-test results at 5% significance level from eighty runs for the off-lineprocess time of the enhanced SA are tabulated in Table 3. The parameter Ciin Table 3 indicates the region into which 95% of the simulation results willfall.

Similarly, t-test statistical analysis at 5% significance level has also been con-ducted from eighty runs for the off-line processing time of the standard SA,SA MO and SA HIPS. The results are tabulated in Table 4 as well.

In addition, comprehensive statistical analysis has also been carried out for thepath length and on-line processing time results for the enhanced SA, SA MO,SA HIPS and standard SA in all five environments. Again, results from eightyruns are used for the analysis in each case. It shows that at 5% significancelevel, the null hypothesis that the simulation results come from a normaldistribution with the mean value shown in Table 3 cannot be rejected. Itfurther demonstrates that 95% of the simulation results in each case fall intoa small region around the mean value, implying that consistent results of pathlength and on-line processing time can be obtained from the enhanced SA,SA MO, SA HIPS and standard SA.

18

Page 20: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

6 Conclusions

An enhanced SA approach has been proposed in this paper for robot path plan-ning in dynamic environments with both static and dynamic obstacles. Com-pared with the standard SA, the enhanced SA integrates two additional math-ematical operators, i.e., deleting operator and switching operator, and initialpath selection heuristics into the standard SA, leading to much improved per-formance in both robot path solution and processing time. Comprehensivecase studies and statistical analysis have been carried out to demonstrate theproposed approach in five dynamic environments with different complexities.The enhanced SA has been shown to be capable of giving an optimal or near-optimal path solution in various dynamic environments, and to consume muchless processing time than the deterministic Dijkstra algorithm, the standardSA, the SA with two additional operators, and the SA with heuristic initialpath selection. As a result of the significant improvement in the computa-tional efficiency, real-time and on-line applications of the developed approachin dynamic path planning become possible.

Acknowledgments

The authors would like to thank the Australian Government’s Departmentof Innovation, Industry, Science and Research (DIISR) for its support un-der the International Science Linkages (ISL) Grant Scheme (Grant Number:CH070083), and the Natural Science Foundation of China (NSFC) for its sup-port under the International Collaboration Grant Scheme (Grant Number:40740420661).

References

[1] A. H. Borzabadi, A. V. Kamyad, M. H. Farahi, and H. H. Mehne. Solving someoptimal path planning problems using an approach based on measure theory.Applied Mathematics and Computation, 170(2):1418–1435, Nov 15, 2005.

[2] Y. Wang, J. Mulvaney, and P. Sillitoe. Genetic-based mobile robot pathplanning using vertex heuristics. In Proceedings of the Conference onCybernetics and Intelligent Systems, volume 1, pages 1–6, Bangkok, Thailand,June 7-9, 2006.

[3] Mahmoud Tarokh. Hybrid intelligent path planning for articulated rovers inrough terrain. Fuzzy Sets and Systems, 159(21):2927–2937, Feb 2008.

19

Page 21: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

[4] Chi-Tsun Cheng, Kia Fallahi, Henry Leung, and Chi K. Tse. An AUVspath planner using genetic algorithms with a deterministic crossover operator.In Proceedings of the 2010 IEEE International Conference on Robotics andAutomation (ICRA), pages 2995–3000, Anchorage, AK, May 3-8, 2010.

[5] Adem Tuncer and Mehmet Yildirim. Dynamic path planning of mobile robotswith improved genetic algorithm. Computers and Electrical Engineering,38(6):1564–1572, Nov 2012.

[6] A. C. Nearchou. Path planning of a mobile robot using genetic heuristics.Robotica, 16(5):575–588, Sept 1998.

[7] H. Kang, B. Lee, and K. Kim. Path planning algorithm using the particle swarmoptimization and the improved dijkstra algorithm. In Proceedings of the IEEEWorkshop on Computational Intelligence and Industrial Application, volume 2,pages 1002–1004, Wuhan, China, Dec 19-20, 2008.

[8] Y. Wei and M. Liu. Determination of optimal path algorithm in urban areabased on AI. In Proceedings of the IEEE Conference on Web Mining and Web-based Application, volume 1, pages 78–80, Wuhan, China, June 6-7, 2009.

[9] J. Norvig Russell. Artificial Intelligence: A Modern Approach. Prentice Hall,Berkeley, CA, 2003.

[10] L. Hu and Z. Q. Gu. Research and realization of optimum route planning invehicle navigation systems based on a hybrid genetic algorithm. Proceedingsof the Institution of Mechanical Engineers Part D – Journal of AutomobileEngineering, 222(D5):757–763, May 2008.

[11] J. Ayers. Underwater walking. Arthropod Structure and Development,33(3):347–360, July 2004.

[12] B. Williams and I. Mahon. Design of an unmanned underwater vehicle for reefsurveying. In Proceedings of the IFAC 3rd Symposium on Mechatronic Systems,Manly NSW, Australia, Sept 15, 2004.

[13] S. Chakravorty and J. L. Junkins. Motion planning in uncertain environmentswith vision-like sensors. Automatica, 43(12):2104–2111, Dec 2007.

[14] Behrang Mohajer, Kourosh Kiani, Ehsan Samiei, and Mostafa Sharifi. A newonline random particles optimization algorithm for mobile robot path planningin dynamic environments. Mathematical Problems in Engineering, Article no.491346, 2013. DOI: 10.1155/2013/491346.

[15] D. Nakhaeinia and B. Karasfi. A behavior-based approach for collisionavoidance of mobile robots in unknown and dynamic environments. Journalof Intelligent and Fuzzy Systems, 24(2):299–311, 2013.

[16] Charlie Irawan Tan, Chang-Min Chen, Wen-Kai Tai, and Chin-Chen Chang.Path planning for racing games. International Journal on Artificial IntelligenceTools, 19(5):679–702, Oct 2010.

20

Page 22: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

[17] Rahul Kala, Anupam Shukla, and Ritu Tiwari. Dynamic environment robotpath planning using hierarchical evolutionary algorithms. Cybernetics andSystems, 41(6):435–454, 2010.

[18] Y. Wang, P. W. Sillitoe, and J. Mulvaney. Mobile robot path planning indynamic environments. In Proceedings of the International Conference onRobotics and Automation, volume 1, pages 71–76, Roma, Apr 10-14, 2007.

[19] Chi-Ming Lin. Multicriteria-multistage planning for the optimal path selectionusing hybrid genetic algorithms. Applied Mathematics and Computation,180(2):549–558, Sept 15, 2006.

[20] Pei-Yan Zhang, Tian-Sheng Lu, and Li-Bo Song. Soccer robot path planningbased on the artificial potential field approach with simulated annealing.Robotica, 22(5):563–566, Aug 2004.

[21] Hong Liu, Weiwei Wan, and Hongbin Zha. A dynamic subgoal path plannerfor unpredictable environments. In Proceedings of the 2010 IEEE InternationalConference on Robotics and Automation (ICRA), pages 994–1001, Anchorage,AK, May 3-8, 2010.

[22] A. Stentz. Optimal and efficient path planning for partially-knownenvironments. In Proceedings of the IEEE International Conference on Roboticsand Automation, volume 4, pages 3310–3317, San Diego, CA, May 8-13, 1994.

[23] A. Yahja, A. Stentz, S. Singh, and B. Brummit. Framed-quadatree pathplanning for mobile robots operating in sparse environments. In Proceedingsof the IEEE Conference on Robotics and Automation, volume 1, pages 650–655, Leuven, Belgium, May 16–20, 1998.

[24] D. Ferguson and A. Stentz. Field D*: An interpolation-based path planner andreplanner. In Proceedings of International Symposium on Robotics Research,pages 239–253, San Francisco, CA, Oct 12, 2005.

[25] A. Stentz. The focussed D* algorithm for real-time replanning. In Proceedings ofthe International Joint Conference on Artificial Intelligence, pages 1652–1659,Montral, Quebec, Canada, Aug 20-25, 1995.

[26] A. Yahja, S. Singh, and A. Stentz. An efficient online path planner for outdoormobile robots operating in vast environments. Robotics and AutonomousSystems, 32:129–143, 2000.

[27] Jianming Guo and Liang Liu. A study of improvement of D* algorithms formobile robot path planning in partial unknown environments. Kybernetes,39(6):935–945, 2010. The 5th Workshop of the International Institute forGeneral Systems Studies, Wuhan, China, June, 2007.

[28] A. R. Willms and S. X. Yang. An efficient dynamic system for real-time robotpath planning. IEEE Transactions on Systems, Man, and Cybernetics, Part B,36(4):755–766, 2006.

21

Page 23: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

[29] A. R. Willms and S. X. Yang. Real-time robot path planning via a distance-propagating dynamic system with obstacle clearance. IEEE Transactions onSystems, Man, and Cybernetics, Part B, 38(3):884–893, June 2008.

[30] Yiannis Demiris and Aude Billard. Special issue on robot learning byobservation, demonstration, and imitation. IEEE Transactions on Systems,Man, and Cybernetics, Part B, 37(2):254–255, Apr 2007.

[31] Fabrizio Padula and Veronique Perdereau. An on-line path planner forindustrial manipulators. International Journal of Advanced Robotic Systems,10:Article No. 156, March 7 2013. DOI: 10.5772/55063.

[32] Quoc Huy Do, Seiichi Mita, Hossein Tehrani Nik, and Long Han. Dynamicand safe path planning based on support vector machine among multi movingobstacles for autonomous vehicles. IEICE Transactions on Information andSystems, E96D(2):314–328, Feb 2013.

[33] L. J. Xie and G. R. Xie. Solution to reinforcement learning problems withartificial potential field. Journal of Central South University of Technology,15(4):552–557, Aug 2008.

[34] Andreas Ess, Konrad Schindler, Bastian Leibe, and Luc Van Gool. Objectdetection and tracking for autonomous navigation in dynamic environments.International Journal of Robotics Research, 29(14):1707–1725, Dec 2010.

[35] J. Park, D. Nam, and C. H. Park. An empirical comparison of simulatedannealing and genetic algorithms on NK fitness landscapes. In Proceedings ofthe IEEE International Conference on Evolutionary Computation, pages 147–151, Indianapolis, IN, Apr 13-16, 1997.

[36] M. Haddad and T. Chettibi. A random-profile approach for trajectory planningof wheeled mobile robots. European Journal of Mechanics A - Solids, 26(3):519–540, July 2007.

[37] S. R. Balachandar and K. Kannan. Randomized gravitational emulation searchalgorithm for symmetric traveling salesman problem. Applied Mathematics andComputation, 192(2):413–421, Sept 2007.

[38] Hui Miao and Yu-Chu Tian. Robot path planning in dynamic environmentsusing a simulated annealing based approach. In Proceedings of the 10thInternational Conference on Control, Automation, Robotics and Vision –ICARCV’2008, pages 1253–1258, Hanoi, Vietnam, Dec 17-20, 2008.

[39] N. Anastopoulos and K. Nikas. Early experiences on accelerating dijkstra’salgorithm using transactional memory. In Proceedings of the IEEE Conferenceon Parallel and Distributed Processing, volume 1, pages 1–8, Rome, Italy, May23-29, 2009.

[40] G. H. Shakouri, K.Shojaee, and T. M. Behnam. Investigation on the choice ofthe initial temperature in the simulated annealing: A mushy state SA for TSP.In Proceedings of the IEEE Conference on Control and Automation, volume 1,pages 1050–1055, Makedonia Palace, Thessaloniki, Greece, June 24-26, 2009.

22

Page 24: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

List of Tables

Table 1. Five testing environments.

Table 2. Control parameters of the simulation annealing.

Table 3. Performance results (mean values from 80 runs for all SAs).

Table 4. T-test at 5% significance level for the off-line processing time of theenhanced SA, SA MO, SA HIPS and standard SA.

23

Page 25: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

List of Figiures

Fig. 1. A dynamic environment with static and moving obstacles.

Fig. 2. A dynamic environment with static and moving obstacles.

Fig. 3. Algorithm structure of the enhanced SA.

Fig. 4. Deleting operator.

Fig. 5. Environment One (from left to right: standard SA, SA MO, SA HIPS,and enhanced SA and Dijkstra). The enhanced EA and Dijkstra generatealmost the same path.

Fig. 6. Environment Two (from left to right: standard SA, SA MO, SA HIPS,and enhanced SA and Dijkstra). The enhanced EA and Dijkstra generatealmost the same path.

Fig. 7. Environment Three (from left to right: standard SA, SA MO, SA HIPS,and enhanced SA and Dijkstra). The enhanced EA and Dijkstra generatealmost the same path.

Fig. 8. Environment Four (from left to right: standard SA, SA MO, SA HIPS,and enhanced SA and Dijkstra). The enhanced EA and Dijkstra generatealmost the same path.

Fig. 9. Environment Five (from left to right: standard SA, SA MO, SA HIPS,and enhanced SA and Dijkstra). The enhanced EA and Dijkstra generatealmost the same path.

Fig. 10. Performance evaluation: path length.

Fig. 11. Performance evaluation: off-line processing time.

Fig. 12. Performance evaluation: on-line processing time.

Fig. 13. Statistical histograms of the off-line processing time for the enhancedSA (Horizontal axes: off-time processing time; vertical axes: percentage).

24

Page 26: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Table 1Five testing environments.

Environment Static Obstacles Dynamic Obstacles Static Vertices

1 3 2 10

2 6 2 25

3 9 4 53

4 14 6 82

5 20 8 107

Table 2Control parameters of the simulation annealing.

Initial Termination Cooling Deleting Switching

Temperature Temperature Rate Operator Operator

Rate Rate

999999999 555555555 0.97 78% 22%

25

Page 27: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Table 3Performance results (mean values from 80 runs for all SAs).

Enhanced SA SA HIPS SA MO Standard SA Dijkstra

Environment One

off-line (s) 0.1373 0.1338 0.1616 0.3589 0.0073

on-line (s) 0.1439 0.1511 0.1907 0.3613 0.0100

Path length 145.78 146.61 146.61 154.60 145.78

Environment Two

off-line (s) 0.2063 0.3730 0.3760 0.6750 0.0471

on-line (s) 0.2391 0.3991 0.3997 0.9871 0.0577

Path length 246.25 267.48 257.57 304.35 246.25

Environment Three

off-line (s) 0.3226 0.6232 0.9302 1.3201 0.3013

on-line (s) 0.3269 0.9791 1.0900 1.5320 0.3107

Path length 279.75 324.37 296.62 438.09 276.84

Environment Four

off-line (s) 0.3342 0.6746 1.5905 2.0860 1.2204

on-line (s) 0.4101 1.0120 1.9431 3.8910 1.2907

Path length 406.36 438.61 429.57 508.21 398.302

Environment Five

off-line (s) 0.7011 1.2036 5.2621 5.5146 2.4804

on-line (s) 0.7105 1.6970 6.9740 7.7350 2.6773

Path length 609.87 659.45 640.78 688.76 576.57

26

Page 28: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Table 4T-test at 5% significance level for the off-line processing time of the enhanced SA,SA MO, SA HIPS and standard SA.

Environment Mean Pass t-test Ci Variance

The enhanced SA

1 0.1373 Yes [0.1359, 0.1386] 3.6554e-005

2 0.2063 Yes [0.2043, 0.2094] 1.2797e-004

3 0.3226 Yes [0.3160, 0.3292] 8.7198e-004

4 0.3342 Yes [0.3261, 0.3423] 1.3000e-003

5 0.7011 Yes [0.6860, 0.7161] 4.5000e-003

The SA MO

1 0.1616 Yes [0.1595, 0.1638] 9.3836e-005

2 0.3760 Yes [0.3682, 0.3838] 0.0012

3 0.9302 Yes [0.8970, 0.9635] 0.0224

4 1.5905 Yes [1.5292, 1.6519] 0.0761

5 5.2621 Yes [4.9715, 5.5527] 1.7052

The SA HIPS

1 0.1338 Yes [0.1289, 0.1387] 4.8247e-004

2 0.3730 Yes [0.3633, 0.3828] 0.0019

3 0.6232 Yes [0.6079, 0.6384] 0.0047

4 0.6746 Yes [0.6438, 0.7055] 0.0192

5 1.2036 Yes [1.1713, 1.2359] 0.021

The standard SA

1 0.3589 Yes [0.3530, 0.3648] 6.9880e-004

2 0.6751 Yes [0.6639, 0.6862] 0.0025

3 1.3201 Yes [1.2902, 1.3499] 0.018

4 2.0860 Yes [2.0127, 2.1592] 0.1082

5 5.5146 Yes [5.2361, 5.7931] 1.5661

27

Page 29: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Fig. 1. A dynamic environment with static and moving obstacles.

Fig. 2. Calculation of the collision possibility (dotted lines: the original trajectoriesof the robot and dynamic obstacle; solid line: alternative robot path to avoid collisionwith the moving obstacle).

28

Page 30: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Fig. 3. Algorithm structure of the enhanced SA.

29

Page 31: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Fig. 4. Deleting operator.

Fig. 5. Environment One (from left to right: standard SA, SA MO, SA HIPS, andenhanced SA and Dijkstra). The enhanced EA and Dijkstra generate almost thesame path.

Fig. 6. Environment Two (from left to right: standard SA, SA MO, SA HIPS, andenhanced SA and Dijkstra). The enhanced EA and Dijkstra generate almost thesame path.

Fig. 7. Environment Three (from left to right: standard SA, SA MO, SA HIPS, andenhanced SA and Dijkstra). The enhanced EA and Dijkstra generate almost thesame path.

30

Page 32: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Fig. 8. Environment Four (from left to right: standard SA, SA MO, SA HIPS, andenhanced SA and Dijkstra). The enhanced EA and Dijkstra generate almost thesame path.

Fig. 9. Environment Five (from left to right: standard SA, SA MO, SA HIPS, andenhanced SA and Dijkstra). The enhanced EA and Dijkstra generate almost thesame path.

Fig. 10. Performance evaluation: path length.

Fig. 11. Performance evaluation: off-line processing time.

31

Page 33: c Consult author(s) regarding copyright matters Licenseeprints.qut.edu.au/62208/1/MiaoTianV11withPubInfo.pdf · The main goal of the robot path planning is to search a safe path for

Fig. 12. Performance evaluation: on-line processing time.

Fig. 13. Statistical histograms of the off-line processing time for the enhanced SA(Horizontal axes: off-time processing time; vertical axes: percentage).

32