APP下载

Rotary unmanned aerial vehicles path planning in rough terrain based on multi-objective particle swarm optimization

2020-02-26XUZhenZHANGEnzeandCHENQingwei

XU Zhen,ZHANG Enze,and CHEN Qingwei

1.School of Automation,Nanjing University of Science and Technology,Nanjing 210094,China;2.College of Information Engineering,Yangzhou University,Yangzhou 225009,China

Abstract:This paper presents a path planning approach for rotary unmanned aerial vehicles(R-UAVs)in a known static rough terrain environment.This approach aims to find collision-free and feasible paths with minimum altitude,length and angle variable rate.First,a three-dimensional(3D)modeling method is proposed to reduce the computation burden of the dynamic models of R-UAVs. Considering the length,height and tuning angle of a path,the path planning of R-UAVs is described as a tri-objective optimization problem.Then, an improved multi-objective particle swarm optimization algorithm is developed. To render the algorithm more effective in dealing with this problem,a vibration function is introduced into the collided solutions to improve the algorithm efficiency. Meanwhile,the selection of the global best position is taken into account by the reference point method. Finally, the experimental environment is built with the help of the Google map and the 3D terrain generator World Machine. Experimental results under two different rough terrains from Guilin and Lanzhou of China demonstrate the capabilities of the proposed algorithm in finding Pareto optimal paths.

Keywords: unmanned aerial vehicle (UAV), path planning, multiobjective optimization,particle swarm optimization.

1.Introduction

With the advancement of technology and the rise in labor price, humans are being replaced by autonomy from dangerous and heavy work.In various actual applications,such as forest patrol[1],electric power facilities diagnostic[2],fire dispatching[3],rescue after detection[4]and danger area detection [5], unmanned aerial vehicles (UAVs)have unmatchable advantages over ground robots due to their higher working space and degrees of freedom(DOF).Meanwhile, the free hovering and unconstrained movement features of R-UAVs have irreplaceable advantages over the fixed-wing UAVs.With the rapid development of battery technology and flight control technology, R-UAV has become one of the most popular development tendencies in the field of robotics[6,7].As one of the most important research themes of the mobile robotics field, the path planning problem of R-UAVs in rough terrains is studied in this paper.

The purpose of path planning is to find a superior path from an initial position to destination without any collision according to certain evaluation standards and constrains.The existing work can be classified into two main groups:classical and heuristic. Among the classical methods, the most representative ones are the skeleton approach [8],cell decomposition[9]and potential field approaches[10],etc.These approaches have their own advantages,however,most of them are computationally expensive and can possibly fall into local minima[11].Heuristic algorithms,which are based on the cognitive process in nature,have provided an alternative way to solve robot path planning problems.Part heuristic algorithms include genetic algorithms(GA)[12],ant colony optimization(ACO)[13],particle swarm optimization (PSO) [14], rapidly-exploring random trees(RRT) [15], etc. Recent work has demonstrated the superiority of these heuristic algorithms over classical ones in dealing with path planning problems,especially for an uneven rough terrain[16].

PSO,first introduced by Kennedy and Eberhart[17],is a population-based heuristic search technique inspired by the paradigm of birds flocking. Due to its simplicity, fast convergence and population-based feature, PSO has been successfully used for solving the path planning problems of UAVs [11,14,18]. Despite their efforts, these methodologies only consider one objective, or handle the path planning problem as a single-optimization problem by using the weighted sum method. However, multiple objectives such as the length, smoothness and safety of a path should be considered simultaneously in practical path planning problems. Moreover, the path planning aims at providing a set of equally optimal paths instead of a single one for decision makers to choose according to various tasks.Thus,the path planning in a known rough terrain is better to be considered as a multi-objective optimization problem.

Multi-objective PSO(MOPSO)has been applied to plan the path in different scenarios. Geng et al. [19] applied MOPSO in uncertain environments comparing with centralized algorithms. Geng and Gong [20] applied interval PSO by combining the local optimal criterion in multiple obstacle environments. MOPSO is applied in robot path planning for multi-survivor rescue in limited survival time[21]. Robot path planning is solved in an environment with terrains based on interval MOPSO [22]. From previous studies, we can conclude that even though the path planning problem has been studied for years,dealing with rough terrain scenarios is still an open problem.

In the current work, the path planning problem for R-UAVs is described as a tri-objective optimization problem,considering simultaneously length,height and tuning angle of a path. An improved MOPSO algorithm is proposed to tackle the problem. The major contributions of this study are as follows:

(i)A three-dimensional(3D)modeling method for trajectories is adopted. This model combines the polar coordinates with the continuous two-dimensional(2D) path planning method to reduce the particle dimension. In the meantime,the angles in this modeling method correspond to the pitch and yaw angles of R-UAV, thus reducing the computation burden and saving the information extraction time of R-UAV platforms.

(ii)A vibration function is introduced into the collided solutions to improve the algorithm efficiency.The collided fragment from an infeasible path is selected and adjusted according to the vibration factor which represents the infeasibility degree of a fragment.

(iii)The reference point method is adopted to guide the algorithm to move toward the preferred region of the objective space,thus providing Pareto optimal paths for decision makers to choose from according to the need of UAV tasks.

(iv) The effectiveness of the proposed approach is validated through experiments conducted in an environment based on true rough terrains.

The remainder of this paper is organized as follows.Section 2 provides details of the modeling of terrains,the encoding of the trajectories, and the evaluative functions for candidate trajectories. In Section 3, the working principle of PSO is described in the beginning,and we present the use of the vibration function and the reference point method respectively.In Section 4,two cases are discussed.This section demonstrates simulation results on the proposed algorithm, and the initial MOPSO algorithm and NSGA-II are used as contrastive experiments to validate the performance of the proposed algorithm.Section 5 concludes this paper.

2.Problem formulation

In 3D modeling of the path planning problem,two key issues need to be considered.First,there is no obvious shortcut in the terrain.Second,code the particle efficiently.Obviously, the two key issues have internal connections. In order to discuss them unambiguously,the two parts are interspersed with each other as shown below.It is worth mentioning that when we use R-UAV as the model, the flight space and angle will be unlimited in principle.Therefore,on the premise of setting aside a safe distance, the author regards R-UAV as a mass point without volume constraint.

2.1 Modeling of the terrain

Some authors use the satellite or radar in terrain modeling for reference, as shown in Fig. 1 [14]. This is a fantastic perspective different from the traditional Euclidean coordinate system and the earth’s curvature is considered when considering long voyages.In this paper, we discuss short distance flight, so the ground can be regarded as a plane.Based on this assumption,we adjust for the modeling approach to Fig.2 called decomposable polar method(DPM).

Fig.1 Sketch of the satellite model

Fig.2 Sketch of DPM

We can see from Fig.1 that the information in the third quadrant is least wanted, because we consider the path planning problem as a bounded convex optimized problem.Thus,we extract the information in the first quadrant to model the terrain which is shown in Fig.2.

On the other hand,the dynamics of R-UAV can be concluded as follows.

whereφ ∈Cis the roll angle which has no effect on the path planning problem;u1is the sum of the lift force;mis the mass of the R-UAV;gis the acceleration of the gravity,[X,Y,Z]is the location coordinates in Euclidean space.

In this case,pointPi=[xi,yi,zi]in theith surface,and we define it by two angles(ρi1,ρi2). Not only we reduce the dimension of the position matrix,but also the yawρi1and pitchρi2angles are in accordance with the attitude angles of R-UAV,which will be more convenient to call the compass information in the flight controller than extracting the location information from sensors. The modeling method greatly reduces the computation of iteration.

In order to find the terrains that can reflect the superiority of the algorithm,we use the Google map and World Machine software for help.The terrain example is shown in Fig.3 which gets from Guilin(25.07,110.61)in China with 25 km2in size.

In Fig.3(a),green and yellow represent vegetation coverage and gullies respectively.In Fig.3(c),we can acquire a gray level matrix[A]512×512in the floating-point type.The bright and dark parts represent ridge and valley topographies respectively,which is more realistic to show surface fluctuation.The matrixing method also simplifies the problems and improves the adaptability of the algorithm.

Fig.3 Satellite images and grayscale

2.2 Representation of trajectories

How to design a path as a solution in the search space is the key problem to solve the path planning successfully using PSO. Considering pointsOandJas the origin and destination respectively, they can represent a path combined with intermediate points[P1,...,Pi,...,Pn-1].

Thepathi= [O,P1,...,Pi,...,Pn-1,J]i ∈R3(n+1)can be shown in Fig.4.

Fig.4 Encoding of path

A solution is made up ofn+1 subcomponents,each of which corresponds to a polar position point.ris the unit length. According to (1), each bit of the subcomponents represents the yaw angle,pitch angle and polar axis length respectively.Fig.5 is a randomly generated particle corresponding to its position.

Fig.5 A randomly generated particle

In addition,when judging whether a path is safe without collision or not, we need to transform the angle information into the height information for contrasting with terrain information. Of course, that only exists in the judgment process, and has little influence on the increase of calculation.Pi(x(i),y(i),z(i))in Euclidean coordinate system can be calculated as below.

From the above analysis, the author describes the process of terrain modeling and representation of trajectories.The encoding method is simple and visualized,and establishes a reasonable mapping between the solution to the problem and the position of the particle.

This method has the following main advantages and disadvantages.

(i) Reduce the computation by reducing the dimension of the particle matrix.

(ii)The yaw and pitch angles are identical with the attitude angle of the R-UAV.It is convenient to call the compass information in the flight controller.

(iv)From the value of the path angles,we can determine the trend of the path effortlessly.

(v) The author only provides an idea and regards R-UAVs as a mass point without more constraint conditions,but the realistic algorithmic migration may be more complex according to the inertia,wind and GPS signals.

2.3 Objective functions

The searchers usually adopt three well-recognized objectives, path length, path smoothness and path safety, for the path planning problem.In this paper,we consider path length as power consumption and the time cost. Meanwhile, we should impose restrictions on large turning angles,which results in exponential consumption of electric power.In terms of security, the threat of radar search can be grouped with the terrain, and the higher the flight, the easier it is to find by radar.It is worth noting that we do not pay attention to the risk area from radar guided weapons.It will only increase the complexity of the calculation after formulation,which has no virtual help to the improvement of the algorithm.Therefore,we choose the length,the height and the turning angle of a path as the cost function of the MOPSO algorithm, and detailed threat targets and the wind field can be extended if you want to.

A path can be expressed in two coordinate systems according to the angle and the position as

path0i=((0,0,0)T,(ρ11,ρ12,r)T,...,(ρi1,ρi2,ir)T,...,(ρn-1,1,ρn-1,2,(n-1)r)T,(0,0,nr)T)path1i=((x0,y0,z0)T,(x1,y1,z1)T,...,(xi,yi,zi)T,...,(xn-1,yn-1,zn-1)T,(xn,yn,zn)T).

The length of the path is expressed as

where

represents the length between pointsPjandPj+1in Euclidean space.

The height of the path is expressed as

wherezi≥0 is the distance from the horizontal plane to the UAV.This objective we propose cannot be satisfied simultaneously with the length objective in most environments. In practice, the height has a positive effect on the length by highlighting the importance of low altitudes. It prevents the solutions which cross all obstacles along the lineOJdominating the other solutions.

The turning angle of the path is expressed as

The turning angle,which represents the rough degree of the path,contains two parts,the yawρi1and the pitch.For R-UAVs, up-and-down motion is easier than side-to-side one,soω0=0.5 is practicable.

In this part,we talk about three performance criterions,the height, length and turning angle. Completely conflict goals are not easy to find. It can be seen from the above description that, in most environments, the objectives we propose cannot be satisfied simultaneously and are representative to some extent.The specific performance will be expressed in the subsequent examples.

3.Improvement of the algorithm

In this part, dominance relation in Section 3.1 is used to update each particle’spbest and the external archive.The improvement of the algorithm is carried out from the following two points:

(i) Add in a vibration function to improve the collided solutions.

(ii)Choose an advisable solution asgbest to lead global particles with the reference point method.

3.1 PSO

PSO has been found to be successful in multiple objectives optimization,proposed by Eberhart and Kennedy[23].The algorithm,which is based on a metaphor of social interaction,searches a space by adjusting the trajectories of individual vectors. The position of each particle represents a candidate trajectory,and each iterative process is individually based on the previous velocity of the particle,the best position ever occupied by the particle and the best position ever occupied by all the particles in the swarm [24].Considering theith particle’s position and velocity in the swarm,thekth generation can be updated by the following rules:

whereω(inertia weight) takes a linear variable value to balance the relationship between exploitation and exploration;c1=c2= 1.496 2 control the influences of thepbesti(k) andgbest(k);r1,2∈[0,1];pbesti(k) is the personal best position that the particleihas had currently;gbest(k)is a value extracted from the archive.

The greatest challenge in extending the PSO to multiobjective problems is deciphering the notion of guide and selection ofpbest andgbest, as in multi-objective scenarios there is a set of optimal solutions rather than a unique optimum.It means that for each particle,there is more than one candidate for updating its global guidance (the candidates do not dominate each other). Thus we introduce an external archive to record all non-dominated candidates found during the search process and maintain it[25].The solutions are compared according to the dominance relation in Definition 1 as below.

Definition 1Pareto dominance:A vectorf(A)is said to dominateg(A)(denoted byf(A)≤g(A))if and only iff(A)is partially less thang(A),i.e.,

In this problem,P athi≤P athjif and only ifcosti≤costj,where

3.2 Vibration function

In the enhanced algorithm, a vibration function is introduced into the collided solutions to improve the algorithm efficiency.The vibration function is defined as below.

whereis the feasible fragment closest toρi;rileast = min(ri); rand1,2∈[1,2];kis the current iteration;ρi,1(gbest) andρi,2(gbest) are the angles of the global optimal solution.ρi,1(pbestj)andρi,2(pbestj)are the angles of the personal optimal solution.

3.3 Reference point method

The reference point method (RPM) was proposed by Wierzbicki in 1980s [27]. With the help of RPM, we build partially ordered relation rigorously among nondominance solutions.Not only can we distinguish any two non-dominated solutions according to the decision maker(DM)’s preference, but the dominance relation enhances the selection pressure of the algorithm which accelerates the convergence speed of the algorithm.The definition of the RD is shown as below.

Definition 3RD:The weighted Euclidean distance of a certain solutionpto the reference pointris defined as

The RD between two solutions is defined as

whereCq ∈P;cij ∈[0,1];

SolutionCpis said to dominate solutionCr, either all(cpi≤cri)&∃any(cpi < cri)orRD(Cp,Cq,Cr)<-δ,δ <[0,1],whereδis the exploitation pressure.

In order to prevent the loss of diversity of solutions under high selection pressure at the beginning of the iteration,the value ofδis transformed into a nonlinear form[27].

whereδDMis the minimum threshold value indicated by the DM;kis the current generation of the evolutionary cycle;kmaxis the terminal generation;p ∈[1,10] is the nonlinear coefficient.

In the initial stage,t= 0,δ= 1, we evaluate the individual solutions based on Pareto dominance relation which retains the exploration ability and ensures the diversity of the search process.With the slow decrease ofδ,the particles converge to the desired region faster.The above exponential method ensures the balance between the diversity of the particle group and the preference of the DM,which prevents the algorithm from falling into local optimization.

3.4 Implementation of the proposed algorithm

Based on the aforementioned study, the algorithm is described here.

Step 1Based on the environment and sensors data,model the landform and workspace by using the method introduced in Section 2.

Step 2Initialize the population POP and set up the parameters needed in the proposed algorithm.

(i)Fori= 1 toSp;/*Maximum number of population sizeSp*/

(ii)Initialize

POP[i]=[position,velocity,angle,cost,collide,pbest]

on the search space.

(iii) Take each particle as itspbest and update the recording of external population(REP).

The selection ofSpshould be based on the size of search space;ω=0.73 is a common choice,and its linear or nonlinear decrease can help to improve the convergence quality of the algorithm.c1=c2= 1.496 2 is recommended to set[17].

Step 3Follow the loop of the iterative process untilk=kmaxor the REP remains unchanged in successive ten generations:

(i)Fork=1 tokmax.

(ii)Fori=1 toSp;

(iii)Update POP[i],follow(vii);

(iv)POP[i]=μ(POP[i]),follow(viii);

(v)i=i+1;

(vi)Return to(ii)ifi≤Sp;

(vii) Update the global best positiongbest(k), follow(x);

(viii)Update external archive REP;

(ix)k=k+1;

(x)Return to(i)ifk≤kmax.

Step 4Transfer the solutions into optimal paths and guide the R-UAV to the target.

4.Case study

This section is devoted to demonstrating simulation results on the proposed algorithm, and the initial MOPSO and NSGA-II algorithm are used as contrastive experiments to validate the performance of the proposed algorithm[28–30]. The experiments are both coded in MATLAB R2014a software.

4.1 Steep mountain terrain

This terrain example is shown in Section 2.1.The first example considers the characteristic that a mountain blocks the connection between the start and the target, and how to circumvent it is concerned about.The parameters of the simulation are set as follows: the map resolutionres=512×512,the population size of the proposed algorithmSp=50,the maximum number of iterationskmax=100,ω= 0.73,c1=c2= 1.496 2, the nonlinear coefficientp= 6,δDM= 0.5,ωδ= (0.4,0.3,0.3). The reference point is(1 110,6 200,3.08).

The population size of NSGA-IISn= 50, the maximum number of iterationskmax= 100,and the crossover probabilitycp= 0.8.The dominated parameters are consistent with MOPSO.The cost values of the MOPSO and NSGA-II algorithm are shown in Fig.6 and Table 1.

Fig.6 Cost of the proposed algorithm and NSGA-II algorithm

Table 1 Typical costs of the proposed algorithm and NSGA-II algorithm

We can see from Table 1 that the proposed algorithm is significantly superior to NSGA-II in the meantime. Also,we note that the several solutions obtained by NSGA-II,shown in boldface, are obviously dominated by the solutions of the proposed algorithm. It indicates that the NSGA-II cannot absolutely guarantee the solutions to be the Pareto front in 100 iterations. The paths in the terrain are shown in Fig.7.

The experiments are repeated five times and the best results are given in Fig. 7. From Fig. 7(a), we observe two areas, the river valley and peak front,which affect the diversity of the algorithm significantly. The location points obtained by the proposed algorithm are more diverse than the NSGA-II algorithm,and it brings about the better balance of the paths around the mountain.

Fig.7 Solutions of the proposed algorithm and NSGA-II algorithm

It is worth mentioning that NSGA can get better solutions than before ifkmax>150.Because of the choice of reference points,the proposed algorithm has better convergence rate in its neighborhood.

4.2 Loess plateau hill-gully terrain

The terrain example in Fig. 8 is collected from Lanzhou(36.45, 102.71)in China. In order to compare it with the example in Section 4.1, the second example considers a characteristic that the terrains do not have obvious shortcut. No matter how to choose the path, the R-UAV needs to climb the ridges between the peaks many times.The parameters of this simulation are set as follows:the map resolutionres= 512×512, the population size of MOPSOSp1= 100, the proposed algorithmSp2= 100 and NSGA-IISn= 100. The maximum number of iterations arekmax= 500 equally,ω= 0.73,c1=c2= 1.496 2.The reference point is(1 135,60 000,4.1).The nonlinear coefficients and crossover probability coincide with the example in Section 4.1.

Fig.8 Satellite images and grayscale images

We can see from Fig.9 and Table 2 that the solutions in boldface of the proposed algorithm obviously dominate the solutions of MOPSO correspondingly.It is clear from the results that more than half the solutions of MOPSO need to be improved according to the reference point method or traditional dominance relation. On the other hand, when the particle quantity and iteration number are relatively large,the proposed algorithm takes the lead in mean time and the NSGA-II shows better performance in diversity and cost value. The paths in the terrain are shown in Fig.10.Different from the example in Section 4.1,this example has a sally port in area 1○at the beginning of the simulations which has a great impact on the diversity of solutions.The trajectories from NSGA-II are smooth and distributed evenly. The trajectories from the proposed algorithm, on the other hand,are better in reducing the length and mean time because of the selective pressure from preference.The cost values of the length confirm our conclusion.

Fig.9 Comparison of cost values

Table 2 Some typical costs of the three algorithms

Fig.10 Solutions of the three algorithms

5.Conclusions

In this paper, we present some advice to handle the path planning problem for known static terrains.The proposed algorithm is easy to use on R-UAV plants and it is fast with desirable performance proved by two representative cases.

First, the computation is reduced by designing a new modeling method. Second, the selection pressure is strengthened by introducing DM’s preference which can shorten the convergence time dramatically. To ensure the diversity of the algorithm, a vibration function is introduced which improves the collided solutions rather than forsaking them.

The following work is how to apply the fixed-wing UAV’s constraints into the algorithm,and we are also considering the possibility of extending the algorithm to multiple R-UAVs formation problems.