AbstractâAiming at robot path planning in an environment with danger sources, a global path planning approach based on multi-objective particle swarm ...
1554
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
Multi-objective Particle Swarm Optimization for Robot Path Planning in Environment with Danger Sources Dun-wei Gong1, Jian-hua Zhang1,2, Yong Zhang1 1.School of Information and Electrical Engineering, China University of Mining and Technology, Xuzhou, China 2.Department of Mechanical and Electrical Engineering, Xuzhou Institute of Technology, Xuzhou, China Email: dwgong@ vip.163.com, {jianhuazh, yongzh401}@126.com
Abstract—Aiming at robot path planning in an environment with danger sources, a global path planning approach based on multi-objective particle swarm optimization is presented in this paper. First, based on the environment map of a mobile robot described with a series of horizontal and vertical lines, an optimization model of the above problem including two indices, i.e. the length and the danger degree of a path, is established. Then, an improved multi-objective particle swarm optimization algorithm of solving the above model is developed. In this algorithm, a self-adaptive mutation operation based on the degree of a path blocked by obstacles is designed to improve the feasibility of a new path. To improve the performance of our algorithm in exploration, another archive is adopted to save infeasible solutions besides a feasible solutions archive, and the global leader of particles is selected from either the feasible solutions archive or the infeasible one. Moreover, a constrained Pareto domination based on the degree of a path blocked by obstacles is employed to update local leaders of a particle and the two archives. Finally, simulation results confirm the effectiveness of our algorithm. Index Terms—robot, path optimization, danger source
planning,
particle
swarm
I. INTRODUCTION Mobile robots have been widely used in many fields, such as industry, agriculture, architecture and military. As one of key issues in robot navigation, the problem of robot path planning, however, has not been solved well yet, especially the one in an environment with danger sources. In general, the problem of robot path planning [1]refers to generate a collision-free optimal or suboptimal path from a start point to a target point in an environment with obstacles, so it is a typical optimization problem with constraints in nature. Generally speaking, existing studies on robot path planning have two categories[2], i.e. classical and heuristic approaches, where the former includes such approaches as framework space, cell decomposition, potential fields and mathematical programming. The framework space approach regards a robot as a point with no size, and plans a path based on the expansion of an obstacle. In the cell decomposition algorithm, the
© 2011 ACADEMY PUBLISHER doi:10.4304/jcp.6.8.1554-1561
workspace of a robot is represented with a graph composed of a series of cells, and a graph-based search is employed to seek an optimal path. The potential fields approach generates an optimal path by using the sum of two forces, i.e. the attractive and the repulsive forces, where the attractive force is to pull the robot toward the target point and the repulsive force pushes the robot away from these obstacles. However, the approaches mentioned above have several drawbacks, e.g. large computation is required for the case with high dimensions and the path obtained is often not globally optimal. Heuristic methods for robot path planning include probabilistic roadmaps method (PRM), rapidly-exploring random tree (RRT), genetic algorithms (GAs), neural networks (NNs), ant colony optimization (ACO), particle swarm optimization (PSO), etc. The PRM method generates a feasible path in a graph planned by interconnecting a series of random nodes in the free space of a robot. The RRT approach represents the configuration space of a robot with a tree, and plans a robot path on condition of satisfying a constraint formulated with differential equations. These path planning methods generate a robot path by combining the model of an environment with various optimization mechanisms. Most techniques mentioned above, however, only study the problem of robot path planning in an environment with obstacles and the optimization index is only the length of a path. In fact, there are some danger sources in an environment besides obstacles. In addition, for a problem of robot path planning, the optimization indices are more than one, e.g. the length and the danger degree of a path. So it is significant to plan a robot path in an environment with danger sources and with several optimization indices. But, there have been few studies on multi-objective path planning in an environment with danger sources to date. A multi-objective PSO algorithm for the problem of robot path planning in an environment with danger sources is presented in this study. First, based on the environment map of a mobile robot described with a series of horizontal and vertical lines, an optimization model of the above problem including two indices, i.e. the length and the danger degree of a path, is established.
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
Then, an improved multi-objective PSO algorithm of solving the above model is developed. In this algorithm, techniques such as self-adaptive mutation operation based on the degree of a path blocked by obstacles, infeasible solutions archive and constrained Pareto domination based on the degree of a path blocked by obstacles are employed to enhance the performance of PSO when tacking the multi-objective path planning problem. The contributions of our study are as follows: (1) we study the problem of robot path planning in an environment with danger sources, and formulate the above problem as a multi-objective optimization problem with constraints; (2) we present a multi-objective PSO algorithm with self-adaptive mutation operation to solve the above problem effectively; (3) we confirm the effectiveness of our method by conducting simulations with various scenarios. The remainder of this paper is arranged as follows. We review related works on robot path planning in Section 2. The map of an environment with danger sources and the mathematical model of robot path planning are elaborated in Section 3. Our multi-objective PSO for robot path planning is given in detail in Section 4. Section 5 demonstrates our simulation results. Finally, we conclude this paper and point out some possible research topics in the future in Section 6. II. RELATED WORK As PSO algorithms have been successfully applied to various fields [3,4,5], robot path planning based on PSO arouses great interests from scholars. At present, these studies are classified into three categories: (1) a particle represents the candidate of a complete path and the globally optimal path can be derived by using PSO. In this algorithm, a path is composed of either some polar radii and polar angles in a polar coordination system [6,7]or some straight lines parallel to the longitudinal axis of a Cartesian coordinate system[8,9,10,11] or a series of grids[12,13]or some vertexes of obstacles[14]; (2) each particle represents a robot, and all the robots share the information of their globally optimal particles in a swarm to plan a robot path[15,16,17]; (3) Being a local path planning method, PSO is utilized to optimize the shortest path obtained by the Dijkstra algorithm or other intelligent optimization algorithms [18,19,20]. After the map of an environment between a start point and a target point through a coordinate system transformation is established [8], PSO is used to generate a globally optimal path w.r.t. the length of a path, and simulations in some specific environments show the robustness and the convergence of the proposed method. In Ref. [9], a novel environment model called the danger degree map is constructed. PSO with equidistant and nonequidistant distributions, whose fitness function is the weighted accumulation of the length of a path and its danger degree, is developed to get a globally optimal path. Ma et al. [10] employed a method similar to Ref. [8] to model the environment, and obtained a globally optimal path by using a PSO with a second-order oscillation after tackling constraints related to bounds and © 2011 ACADEMY PUBLISHER
1555
obstacles. In Ref. [11], a PSO method based on endocrine regulation mechanism was presented, in which a novel formula of updating a particle with a hormone update function calculated by individual, global and average information of a particle is utilized to plan a robot path. In Ref. [12], the grid theory is employed to describe the environment and a particle represents the candidate of a complete path. The globally optimal path w.r.t. the length of a path is derived by using PSO. In Ref. [14], a path is encoded with some vertexes of polygon obstacles in an environment, and a globally optimal path w.r.t. the length of a path is obtained by using a binary PSO method. In Ref. [15], a PSO method incorporating the potential fields approach is presented, and the robot evades an obstacle by using a potential field stream function while updating a particle. Aiming at the problem of searching for a radiation source with multi-robot[17], each robot is abstracted as a particle and an improved PSO is used to localize the radiation source based on the interface between human and the robot swarm. In Ref. [19,20], a two-stage method of robot path planning was given, in which an optimal path is improved by using PSO based on the one obtained by the Dijkstra method. We focus on the problem of robot path planning in an environment with both obstacles and danger sources. At the same time, these multiple indices considered here conflict with each other, so it is much necessary to present a novel multi-objective PSO method to solve the above problem. III. MATHEMATICAL MODEL OF ROBOT PATH PLANNING To describe the distribution of an obstacle in an environment with danger sources, a series of horizontal and vertical lines are employed to establish the map of an environment between a start and a target points. A multiobjective optimization model of robot path planning is developed based on these two indices, i.e. the length and the danger degree of a path. A. Environment modeling To search for an optimal robot path successfully, the model of an environment should be first constructed. At present, popular techniques mainly include grid method [12,13], Maklink graph [19,20], Voronoi graph [21], etc. In order to evaluate the degree of a path blocked by obstacles, we model the map of the environment by a series of horizontal and vertical lines based on the existing environment model in Ref. [8]. Assume that a robot moves in a two-dimensional space and is abstracted as a particle, shown as Fig. 1, where black polygons represent some obstacles, gray circular points represent some danger sources, S and T represent the start and the target points, respectively. The number of obstacles and danger sources are denoted as NO and NS , respectively. To establish the map of the environment, a global coordinate system XOY is built by setting S as the origin, the line between S and T as X axis and the line perpendicular to X axis as Y axis. The segment ST is evenly divided into m + 1 intervals by m points in X axis. Denote the line perpendicular to X axis
1556
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
crossing the i-th point as xli , the intersect point between the line and a robot path as pi , i = 1, 2,… , m , then the path, denoted as PH , can be uniquely determined by S , p1 , p2 , , pm , T .
p0 and pm +1 , respectively, then the length of a path can
be further represented as: m
D( PH ) = ∑ ( xi +1 − xi ) 2 + ( yi +1 − yi ) 2 i =0 m
(2)
=∑
Yup
i =0
d(S,T)2 ( ) + ( yi +1 − yi ) 2 m +1
p2 p1
p3
S O
Ylow
The danger degree of path PH relative to danger source DS j ( j = 1, 2, , NS ) , denoted as Fj , is formulated as follows:
T
pm
xl1 xl2
xlm xlm+1
Figure 1. Model of environment
Denote Yup and Ylow as the upper and the low bounds
⎧ 1 d(DS j ) ≤ d(DSj )min ⎪ d(DS j ) − d(DS j )min ⎪ Fj = ⎨exp(−β ⋅ ) d(DS j )min < d(DSj ) < d(DSj )max d(DS j )max − d(DS j )min ⎪ ⎪ 0 d(DS j ) ≥ d(DS j )max ⎩
of the robot path in Y axis, respectively, and evenly divide the segment YupYlow into n + 1 intervals. Similar to
where β is a constant positive value, d ( DS j ) represents
the method mentioned above, a series of parallel lines yl1 , yl2, , yln +1 are obtained. It is easy to observe that the workspace of the robot is divided into (m + 1) × (n + 1) grids. If a grid is occupied by some obstacles, its attribute value, denoted as GV , is set to be one; otherwise, the value is zero. The degree of path PH blocked by obstacles, denoted as cr ( PH ) , is formulated as follows:
and d ( DS j ) min are the upper and the lower bounds of the
cr ( PH )
=
GV ( PH ) GS ( PH )
(1)
where GS ( PH ) and GV ( PH ) are the number of grids and the sum of grid attribute values of PH , respectively.
B. Mathematical model of robot path planning To evaluate a path in an environment with danger sources, two conflict indices, i.e. the length and the danger degree of a path, are developed. We hope that the length of a path is as shorter as possible and, at the same time, the danger degree of a path is as lower as possible. The length of a path is the sum of Euclidean distances of these segments formed by the intersect points between a series of lines xli and a robot path. The danger degree of a path in the environment with multiple danger sources depends on the maximal one in the environment with a single danger source. Based on the environment model mentioned above, the length of a robot path, denoted as D ( PH ) , is formulated as follows:
the minimal distance between PH and DS j , d ( DS j ) max distance w.r.t DS j , respectively. When d ( DS j ) is larger than or equal to d ( DS j ) max , we say that the path is absolutely safe related to DS j . On the contrary, when d ( DS j ) is smaller than or equal to d ( DS j ) min , we say
that the path is absolutely dangerous related to DS j . For the case that d ( DS j ) is smaller than the upper bound and larger than the lower bound, the danger degree of PH depends on the magnitude of d ( DS j ) . For all NS danger sources, the danger degree of a path, denoted as DF ( PH ) , is formulated as follows: DF ( PH ) = max ( Fj ) j =1,2, , NS
(3)
Thus, the mathematical model of the above problem can be formulated as the following optimization problem with a constraint: min f ( PH ) = ( D( PH ), DF ( PH )) s. t . cr ( PH ) = 0
(4)
where the unique constraint cr ( PH ) = 0 indicates a collision-free between PH and some obstacles. IV. ROBOT PATH PLANNING BASED ON MULTI-OBJECTIVE PARTICLE SWARM OPTIMIZATION WITH SELF-ADAPTIVE MUTATION OPERATION
m −1
D( PH ) = d (S, p1 ) + ∑ d ( pi , pi +1 ) + d ( pm , T) i =1
where d (⋅, ⋅) is Euclidean distance of a segment formed by two points. Denote the start and the target points as
© 2011 ACADEMY PUBLISHER
To solve the above mathematical model of robot path planning, this section presents an improved multiobjective particle swarm optimization algorithm with self-adaptive mutation operator and preservation strategies of infeasible solutions archive. In this algorithm, a self-adaptive mutation operation based on
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
1557
the degree of a path blocked by obstacles is designed to improve the feasibility of a new path. To balance the performance of our algorithm in exploration and exploitation, an infeasible solutions archive is adopted to save infeasible solutions in each generation. And the global leader of particles is selected from either the feasible solutions archive or the infeasible solutions archive according to the same probability.
A. Encoding particles According to the environment model in Fig. 1, a robot path PH is represented as S , p1 , p2 , , pm , T . Since the abscissas of p1 , p2 , pm have been already known in a given environment, the path planning algorithm only seeks the ordinates of p1 , p2 , pm to minimize these objectives. Then a robot path is uniquely determined by a m-dimensional particle y1 , y2 ym .
B. Selecting locally optimal particles According to the definitions of the length and the danger degree of a path and the degree of a path blocked by obstacles in our study, a constrained Pareto domination relation is developed to update locally optimal particles and the infeasible solutions archive. Pareto domination [22] For a minimization problem, a decision vector X = ( x1 , x2 , , xn ) is said to dominate another vector Y = ( y1 , y2 ,
, yn ) , denoted as X ≺ Y , if
and only if for ∀i ∈ {1, 2, ..., n} ,
xi ≤ yi holds, and
∃j ∈ {1, 2, ..., n} , x j < y j holds.
Constrained Pareto domination For two particles X i and X j , X j is constrainedly dominated by X i if they meet the following two conditions: and ; f (Xi ) ≺ f (X j ) cr ( X i ) ≤ cr ( X j )
f (Xi )
f (X j )
where f ( X i )
and
cr ( X i ) < cr ( X j )
① ② ,
f ( X j ) means that X i and X j do not
dominate each other. Assume that X i (t ) and XPi (t ) denote the position of a particle and that of its locally optimal particle in the t-th generation, respectively. In the next generation, the offspring X i (t + 1) is chosen as its new locally optimal particle
if
XPi (t )
is
constrainedly
dominated
by X i (t + 1) . If X i (t + 1) and XPi (t ) do not dominate each other, its new locally optimal particle is randomly selected from X i (t + 1) and XPi (t ) [23].
C. Updating archives A particle in a population is called a feasible solution if its corresponding path is collision-free with all obstacles; otherwise, it is called an infeasible solution. Ref. [24,25] proved that several infeasible solutions may improve the diversity of a population and benefit to search for better feasible solutions. So an infeasible solutions archive is
© 2011 ACADEMY PUBLISHER
employed from which to select some globally optimal particles besides from a feasible solutions archive. When updating these archives, some feasible and infeasible solutions are stored into the feasible solutions archive and the infeasible one, respectively. New particles are first divided into the feasible and the infeasible solutions according to the degree of a path blocked by obstacles mentioned above. Then the non dominated particles from the feasible solutions are stored into the feasible solutions archive. If the number of the elements in the feasible solutions archive exceeds its capacity, denoted as N a , the N a solutions with larger crowding distance [26] are reserved into the feasible solutions archive. The similar method is applied to the non dominated particles from the infeasible solutions to get the infeasible solutions archive with a capacity of N a′ .
D. Selecting globally optimal particles As mentioned above, the globally optimal particles selected from the infeasible solutions archive may improve the diversity of a population and enhance the performance of an algorithm in exploration. And those globally optimal particles selected from the feasible solutions archive can guide the particles to exploit the searched feasible regions deeply and further increase the quality of existing feasible non dominated solutions. An improved method of selecting the globally optimal particles is presented based on the crowding distance in our study. If neither the feasible solutions archive nor the infeasible one is empty, the particle with the maximal crowding distance is selected as the globally optimal particle from either the feasible solutions archive or the infeasible one according to the same probability. If only the feasible solutions archive is empty, the particle with the maximal crowding distance from the infeasible solutions archive is selected as the globally optimal particle. If only the infeasible solutions archive is empty, the particle with the maximal crowding distance from the feasible solutions archive is selected as the globally optimal particle. E. Self-adaptive mutation based on degree of path blocked by obstacles To improve the feasibility of a new particle, i.e. the path, a self-adaptive mutation operation based on the degree of a path blocked by obstacles is presented in this study. On the basis of the degree of a particle blocked by obstacles, particle X i is endued with a mutation probability, denoted as pm (i ) . The larger the degree of a particle blocked by some obstacles is, the larger the mutation probability of the particle is. The mutation probability of particle X i is formulated as follows:
p m (i ) =
1 − e − γ ⋅cr ( X i ) 1 + e − γ ⋅cr ( X i )
(5)
1558
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
The pseudo code of the adaptive mutation operation is illustrated in Fig.2, where Tmax and t denote the
Step4 Calculate the velocity and the position of a particle according to the following equations [27]:
termination generation and the number of generations, respectively. If random number rand is smaller than or equal to pm (i ) in a generation, the forward and the reverse adaptive mutations are applied to the infeasible particles at the collision points according to the number of generations and the range of these mutations. And the non dominated particle is reserved based on the constrained Pareto dominance given above. We can conclude from Fig. 2 that a larger range of the mutations in early stage can guide a particle to avoid the obstacles in the global search. With the increase of the number of generations, the range of these mutations decreases for a particle to exploit in the local regions.
Vij (t + 1) = ωVij (t ) + c1r1 ( XPij (t ) − X ij (t )) + c2 r2 ( XGj (t ) − Xij (t ))
Function MUTATION FOR i = 1 to N IF rand ≤ pm (i ) j = collisionpoint (1, dim)
mutrange = [upper _ Bound ( j) − low _ Bound ( j)] ∗ pm (i)
XM ij = X ij + randn ∗ mutrange ∗ (1 − t XNij
= X ij − randn ∗ mutrange ∗ (1 −
ENDIF IF f ( XM ij ) ≺
Tmax
t Tmax
)
(6) where i = 1, 2, , N , and j = 1, 2, , m . c1 and c2 are non negative constants named acceleration coefficients. r1 and r2 are two random values within [0, 1]. ω is an inertia weight to control the performance of an algorithm in exploration. Vij ∈ [ −Vmax Vmax ] , where Vmax is set by a user in prior. Step5 Apply the self-adaptive mutation operation to infeasible particles at collision points by using the method in subsection 4.5. Step6 Update the locally optimal particles by using the method in subsection 4.2. Step7 Update the feasible and the infeasible solutions archives by using the method in subsection 4.3. Step8 Let t ← t + 1 . If t < Tmax , go to Step3; otherwise, stop the algorithm and output the optimal robot path.
)
V. EXPERIMENTS f ( XN ij )
X ij = XM ij
Else X ij ENDIF ENDFOR
Xij (t + 1) = Xij (t ) + Vij (t + 1)
= XN ij
Figure 2. Pseudo code of self-adaptive mutation operation
F. Steps of algorithms The steps of the multi-objective PSO for robot path planning in an environment with danger sources are described as follows. Step1 Set the values of population size N, adjustable parameter γ , termination generation Tmax , size of the feasible and the infeasible solutions archives N a and N a′ . Let the number of generations be one, i.e., t = 1 .
Step2 Initialize the population randomly and let the initial values of the locally optimal particles XPi (t ) be themselves. Calculate the fitness and the degree of a path blocked by obstacles for each particle according to the methods in Section 3. Initialize the feasible and the infeasible solutions archives with the feasible and the infeasible non dominated solutions in the population, respectively. Step3 Seek the globally optimal particle, denoted as XGi (t ) , according to the method in subsection 4.4.
© 2011 ACADEMY PUBLISHER
To confirm the effectiveness of our algorithm, the following two experiments are conducted with the simulation environment of E5500 2.80 GHz CPU, 2G RAM and MATLAB 7.0. One is that two danger sources and six convex obstacles exist in an environment; the other is that two danger sources and six obstacles exist in an environment, among these obstacles, two are traps. Robot path planning based on the multi-objective PSO with and without the self-adaptive mutation operation, denoted as MPSO and WMPSO, respectively, is given for the two cases above. In our experiments, the parameters of the multiobjective PSO are set as follows: N = 50 , c1 = 2 ,
c2 = 2 , β = 3 , γ = 7 , N a = 8 , N a′ = 8 , Tmax = 50 * NO ,
ω = ωmax − t / Tmax ⋅ (ωmax − ωmin ) , i.e., the inertia weight decreases linearly in accordance with the number of generations[28], where ω max is equal to 0.9, ω min equal to 0.4. The start and the target points of the robot is S(0,0) and T(100,0), respectively. Three metrics are employed to evaluate the optimization results [29,30]. The C metric, denoted as C (⋅, ⋅) , is used to measure the coverage of two sets. The spacing metric, denoted as SP (⋅) , aims at assessing the distribution of vectors. The hyper-volume metric, denoted as S ( M , r ) , reflects the diversity and the convergence of the solutions. The reference point of S ( M , r ) is (200, 2) in this study.
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
A. Experiment 1 Six convex obstacles and two danger sources exist in an environment. The coordinates of the two danger sources are DS1 ( 40.014, -9.6416 ) and DS 2 ( 69.971 ,6.3993) , respectively. The vertex coordinates
of these six obstacles are as follows:
⎡ 20.043 14.078 ⎤ ⎡ 40.014 -17.491⎤ ⎢ 20.185 -9.9829 ⎥ ⎢ ⎥ ⎥ , OB2 = ⎢ 50.000 -44.113 ⎥ , OB1 = ⎢ ⎢ 29.886 -9.8123 ⎥ ⎢ 59.843 -35.922 ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 50.285 -15.956 ⎦ ⎣ 29.601 14.078 ⎦ ⎡50.143 10.495 ⎤ ⎡ 50.000 44.283 ⎤ ⎢ 60.128 -5.3754 ⎥ ⎢ 40.014 29.778 ⎥ ⎥ , ⎥ , OB4 = ⎢ OB3 = ⎢ ⎢ ⎢ 50.000 23.464 ⎥ 70.257 0.0853 ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 60.271 35.410 ⎦ ⎣ 60.414 12.713 ⎦ ⎡ 70.257 36.092 ⎤ ⎡ 79.815 -14.761 ⎤ ⎢80.100 18.345 ⎥ ⎢ 69.971 -30.29 ⎥ ⎥ . ⎥ , OB6 = ⎢ OB5 = ⎢ ⎢89.943 23.635 ⎥ ⎢80.243 -45.819 ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 79.957 43.430 ⎦ ⎣89.943 -35.751 ⎦ Each of these two algorithms is run for 30 times independently. Fig. 3 and 4 illustrate some optimal robot paths with the maximal value of S ( M , r ) . It can be observed that both algorithms can find several non dominated robot paths, the values of and C(MPSO, WMPSO) = 0.500 C(WMPSO, MPSO) = 0.444 in Table I, however, mean that the convergence of MPSO are superior to that of WMPSO. In addition, the values of SP (MPSO)=0.552 and SP(WMPSO)=0.708 in Table I indicate that the distribution of MPSO is better than that of WMPSO.
1559
TABLE I C METRIC AND SPACING METRIC OF TWO ALGORITHMs Algorithm MPSO WMPSO
C(A,B) 0.500 0.444
SP 0.552 0.708
Statistical results of S ( M , r ) and the average run time are listed in Table II. Though the average run time of MPSO is longer than that of WMPSO, the values of S ( M , r ) in MPSO is larger than those in WMPSO, the latter suggests that the diversity and the convergence of MPSO are better than those of WMPSO. TABLE II STATISTICAL RESULTS OF S ( M , r ) AND AVERAGE RUNNING TIME OF TWO ALGORITHMS (UNIT: SECOND)
Algorithm MPSO WMPSO
Maximum
Minimum
Average
S (M , r )
S (M , r )
S (M , r )
183.337 170.964
94.144 93.611
165.155 150.677
Average running time 8.238 6.980
B. Experiment 2 Two danger sources and six obstacles exist in an environment, among these obstacles, two are traps. The coordinates of two danger sources are DS1 ( 40.014, -9.471) and DS2 ( 50.000 ,10.154 ) , respectively. The coordinates of six obstacles are as follows:
vertex
⎡30.171 40.017 ⎤ ⎡ 49.857 -17.833 ⎤ ⎢ 40.014 -31.997 ⎥ ⎢ 40.157 21.928 ⎥ ⎥ , ⎥ , OB2 = ⎢ OB1 = ⎢ ⎢ 50.428 -46.502 ⎥ ⎢50.000 24.488 ⎥ ⎢ ⎥ ⎢ ⎥ ⎣ 60.414 -35.068 ⎦ ⎣ 40.300 44.966 ⎦ ⎡79.815 41.724⎤ ⎡ 79.815 -16.809 ⎤ ⎢69.971 35.068⎥ ⎢ 70.257 -29.949 ⎥ ⎢ ⎥, , ⎥ OB3 = ⎢ ⎢ ⎥ ⎢80.243 -43.771 ⎥ OB4 = ⎢70.257 22.099⎥ ⎢ ⎥ ⎢80.1 17.321 ⎥ ⎣89.658 -38.993 ⎦ ⎢⎣90.086 29.949⎥⎦
⎡20.043 29.886 30.171 19.757 20.185 29.458 28.317 19.757 ⎤′ , OB5 =⎢ ⎥ ⎣11.007 11.177 -10.836 -10.495 -5.7167 -4.6928 6.3993 6.7406 ⎦ Figure 3. Optimal robot paths of MPSO
Figure 4. Optimal robot paths of WMPSO
© 2011 ACADEMY PUBLISHER
⎡60.128 69.971 69.829 60.414 60.414 68.117 67.689 60.556⎤′ OB6 =⎢ ⎥ ⎣9.8123 10.154 -10.154 -9.9829 -6.058 -4.6928 4.6928 6.058 ⎦ .
For this case, each of these two algorithms is still run for 30 times independently. Fig. 5 and 6 illustrate some optimal robot paths with the maximal value of S ( M , r ) . It can be observed that both algorithms jump out of these traps and find several non dominated paths. The values of C(MPSO,WMPSO) = 0.333 and C(WMPSO,MPSO) = 0.500 in Table III mean that WMPSO is superior to MPSO in convergence. The values of SP(MPSO)=0.057 and SP(WMPSO)=0.122 in Table III, however, indicate that the distribution of MPSO is better than that of WMPSO.
1560
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
problem with a constraint; finally, a multi-objective PSO is presented to solve the problem above with such techniques as the self-adaptive mutation based on the degree of a path blocked by obstacles, the infeasible solutions archive and the constrained Pareto domination based on the degree of a path blocked by obstacles. It should be noted that the position of a danger source in our algorithm has already been known in advance. In fact, some unknown danger sources often exist in an environment. In addition, dynamic obstacles in an environment are not considered in this study. For the case that the position of a danger sources is unknown or dynamic obstacles exist in an environment, the problem of robot path planning is our future research topic.
Figure 5. Optimal robot paths of MPSO
ACKNOWLEDGMENT This work is jointly supported by National Natural Science Foundation of China with granted No. 61005089 and Natural Science Foundation of Jiangsu Province with granted No. BK2008125.
REFERENCES Figure 6. Optimal robot paths of WMPSO
TABLE III C METRIC AND SPACING METRIC OF TWO ALGORITHMs Algorithm MPSO WMPSO
C(A,B) 0.333 0.500
SP 0.057 0.122
Statistical results of S ( M , r ) and the average run time are listed in Table IV. Though the average run time of MPSO is longer than that of WMPSO, the values of S ( M , r ) in MPSO is larger than those in WMPSO, the latter suggests that the diversity and the convergence of MPSO are better than those of WMPSO. TABLE IV STATISTICAL RESULTS OF S ( M , r ) AND AVERAGE RUNNING TIME OF TWO ALGORITHMS (UNIT: SECOND)
Algorithm MPSO WMPSO
Maximum
Minimum
Average
S (M , r )
S (M , r )
S (M , r )
180.416 175.520
96.225 86.226
160.219 148.974
Average running time 8.432 7.188
VI. CONCLUSIONS We focus on the problem of robot path planning in an environment with danger sources and obstacles, and propose a global path planning approach based on the multi-objective PSO with self-adaptive mutation operation. Different from previous algorithms of robot path planning, our algorithm has the following characteristics. First, a series of horizontal and vertical lines are employed to encode a path and describe the distribution of obstacles in an environment map; second, the problem of robot path planning in an environment with danger sources is formulated as a multi-objective optimization
© 2011 ACADEMY PUBLISHER
[1] H. J. Liu, J. Y. Yang, J. F. Lu, Z. M. Tan, C. X. Zhao, W. M. Cheng, “Research on mobile robots motion planning: a survey,” Journal of Engineering Science, Vol. 8, No. 1, pp. 85-94, 2006. [2] E. Masehian, D. Sedighizadeh, “Classic and heuristic approaches in robot motion planning-a chronological review ,” World Academy of Science, Engineering and Technology, No. 29, pp. 101-106, 2007. [3] J. Kennedy, R. C. Eberhart, “Particle swarm optimization ,” Proceedings of IEEE International Conference on Neural Networks, Perth, Australia, pp.1942-1948, November ,1995. [4] T. Zhang, J. D. Cai, “A novel hybrid particle swarm optimisation method applied to economic dispatch,” International Journal of Bio-Inspired Computation, Vol. 2, No. 1, pp. 9-17, 2010. [5] J. G. Lu, L. Zhang, H. Yang, D. Jie, “Improved strategy of particle swarm optimisation algorithm for reactive power optimization”, International Journal of Bio-Inspired Computation, Vol. 2, No. 1, pp. 27-33, 2010. [6] Y. L. Hao, W. Zu, Y. X. Zhao, “Real-time obstacle avoidance method based on polar coordination particle swarm optimization in dynamic environment,”Proceedings of IEEE Conference on Industrial Electronics and Applications, Harbin, China, pp.1612-1617 ,May, 2007. [7] W. Zu, G. Li, Z. X. Qi, “Study on path planning method based on improved particle swarm optimization ,” Journal of Projectiles, Rockets, Missiles and Guidance, Vol. 28, No. 4, pp. 68-70, 2008. [8] B. Sun, W. D. Chen, Y. G. Xi, “Particle swarm optimization based global path planning for mobile robots,” Control and Decision, Vol. 20, No. 9, pp. 10521060, 2005. [9] Y. H. Xue, G. H. Tian, B. Huang, “Optimal robot path planning based on danger degree map,” Proceedings of IEEE International Conference on Automation and Logistics, Shenyang, China, pp.1040-1045 ,August , 2009. [10] Q. Z. Ma, X. J. Lei, Q. Zhang, “Mobile robot path planning with complex constraints based on the second-order oscillating particle swarm optimization algorithm,”
JOURNAL OF COMPUTERS, VOL. 6, NO. 8, AUGUST 2011
[11]
[12]
[13]
[14]
[15]
[16]
[17]
[18]
[19]
[20]
[21]
[22]
Proceedings of World Congress on Computer Science and Information Engineering, Los Angeles/Anaheim, USA, pp. 244-248, March, 2009. D. B. Chen, C. X. Zhao, “ Particle swarm optimization based on endocrine regulation mechanism,” Journal of Control Theory and Applications, Vol. 24, No. 6, pp. 10051009, 2007. G. Z. Tan, G. J. Liu, “Global optimal path planning for mobile robots based on particle swarm optimization,” Applications Research of Computers, Vol. 24, No. 11, pp. 210-212, 2007. Y. Wang, Q. B. Zhu, “Path planning for mobile robot based on binary particle swarm optimization,” Journal of Nanjing Normal University (Engineering and Technology Edition), Vol. 9, No. 2, pp. 72-78, 2009. Q. R. Zhang, G. C. Gu, “Path planning based on improved binary particle swarm optimization algorithm ,”Proceedings of IEEE International Conference on Robotics, Automation and Mechatronics, Chendu, China, pp.462-466, September , 2008. S. Bashyal, G. K. Venayagamoorthy, “Human swarm interaction for radiation source search and localization,” Proceedings of IEEE Swarm Intelligence Symposium, St. Louis ,MO, USA, pp.1–8, September , 2008. J. M. Hereford, M. Siebold, S. Nichols, “Using the particle swarm optimization algorithm for robotic search applications ,” Proceedings of IEEE Swarm Intelligence Symposium, Honolulu, Hawaii, USA, pp.53-59 April , 2007. C. Y. Hu, X. N. Wu, Q. Z. Liang, Y. J. Wang, “Autonomous robot path planning based on swarm intelligence and stream functions,” Lecture Notes in Computer Science, Springer-Verlag, pp. 277-284, September, 2007. H. Kang, B. Lee, K. Kim, “Path planning algorithm using the particle swarm optimization and the improved Dijkstra algorithm,” Proceedings of Pacific-Asia Workshop on Computational Intelligence and Industrial Application, Wuhan,China, pp.1002-1004 ,December, 2008. G. S. Li, H. B. Shi, “Path planning for mobile robot based on particle swarm optimization,” Chinese Control and Decision Conference, Yantai,China, pp.3290-3294, July, 2008. Qin, Y. Q., Sun, D. B., Li, N., Ma, Q. (2004) ‘Path planning for mobile robot based on particle swarm optimization’, Robot, Vol. 6, No. 3, pp. 222-225. B. Gao, W. S. Yan, F. B. Zhang, Y. T. Wang, “A method of constructing complete graph for multi-objects path planning in complex environment,” Proceedings of IEEE International Conference on Information and Automation, Zhuhai/Macau, China, pp.403-407 ,June, 2009. M. Reyes-Sierra, C. C. A. Coello, “Multi-objective particle swarm optimizers: a survey of the state-of-the-art,” International Journal of Computational Intelligence Research, Vol. 2, No. 3, pp. 287-308, 2006.
© 2011 ACADEMY PUBLISHER
1561
[23] Y. H. Shi, R. C. Eberhart, “Particle swarm optimization with fuzzy adaptive inertia weight,” Proceedings of the Workshop on Particle Swarm optimization, Indianapolis, IN, USA, pp.101-106 ,April , 2001. [24] Z. X. Cai, Y. Wang, “A multiobjective optimization-based evolutionary algorithm for constrained optimization,” IEEE Transactions on Evolutionary Computation, Vol. 10, No. 6, pp. 658-674 ,December, 2006. [25] Y. G. Woldesenbet, B. G. Tessema, G. G. Yen, “Constraint handling in multiobjective evolutionary optimization,”Proceedings of IEEE Congress on Evolutionary Computation, Singapore, pp.3077-3084, September , 2007. [26] K. Deb, A. Pratap, S. Agarwal, T. Meyarivan, “A fast and elitist multiobjective genetic algorithm: NSGA-II,” IEEE Transactions on Evolutionary Computations, Vol. 6, No. 2, pp. 182-197 ,April, 2002. [27] Y. H. Shi, R. C. Eberhart, “A modified particle swarm optimizer,” Proceedings of IEEE Congress on Evolutionary Computation, Anchorage, AK, USA, pp.6973 ,May , 1998. [28] Y. H. Shi, R. C. Eberhart, “Empirical study of particle swarm optimization,” Proceedings of IEEE Congress on Evolutionary Computation, Washington, DC, USA, pp.1945-1950, July , 1999. [29] E. Zitzler, L. Thiele, “Multiobjective evolutionary algorithm: a comparative case study and the strength pareto approach,” IEEE Transactions on Evolutionary Computations, Vol. 3, No. 4, pp.257-271 ,November, 1999. [30] E. Zitzler, K. Deb, L. Thiele, “Comparison of multiobjective evolutionary algorithms: empirical results,” Evolutionary Computation, Vol. 8, No. 2, pp.173-195, 2000.
Dun-wei Gong is a Professor at the School of Information and Electronic Engineering, China University of Mining and Technology, Xuzhou, China. He obtained his PhD from China University of Mining and Technology in 1999. Since 2000, he has been researching in intelligence optimization and control.
Jian-hua Zhang is a PhD candidate at the School of Information and Electronic Engineering, China University of Mining and Technology, Xuzhou, China. His current research interests include robot path planning.
Yong Zhang is currently a Lecturer at the School of Information and Electronic Engineering, China University of Mining and Technology, Xuzhou, China. He received his PhD in Control Theory and Control Engineering from China University of Mining and Technology in 2009. His current research interests include particle swarm optimization.