Simulation
A meta-heuristic based three-dimensional path planning environment for unmanned aerial vehicles
Simulation: Transactions of the Society for Modeling and Simulation International 89(8) 903–920 Ó 2012 The Society for Modeling and Simulation International DOI: 10.1177/0037549712456419 sim.sagepub.com
Isil Oz1, Haluk Rahmi Topcuoglu1 and Murat Ermis2
Abstract Unmanned Aerial Vehicles (UAVs) are used for many missions, including weather reconnaissance, search and rescue assisting operations over seas and mountains, aerial photographing and mapping, fire detection, and traffic control. Autonomous operation of UAVs requires the development of control systems that can work without human support for long time periods. The path planners, which generate collision-free and optimized paths, are needed to provide autonomous operation capabilities to the UAVs. The optimization of the flight trajectory is a multi-objective problem dealing with variable terrain features as well as dynamic environment conditions. This paper presents a simulation environment for offline path planning of unmanned aerial vehicles on three-dimensional terrains. Our path planner aims to identify the shortest path and/or flight envelope in a given line of sight by avoiding terrain collisions, traveling on a path that stays within the restricted minimum and maximum distances above the terrain, traveling far from the specified threat zones, and maneuvering with an angle greater than the minimum curvature radius. We present two metaheuristics (genetic algorithms and hyper-heuristics) in order to construct the paths for UAV navigation and compare our results with a reference work given in the literature. A comparative study over a set of terrains with various characteristics validates the effectiveness of the proposed meta-heuristics, where the quality of a solution is measured with the total cost of a constructed path, including the penalties of all constraints.
Keywords unmanned aerial vehicles, path planning, genetic algorithms, hyper-heuristics
1. Introduction Unmanned Aerial Vehicles (UAVs) are remote-controlled or self-controlled aircraft that can carry cameras or sensors to gather information about the environment. They have been used both in commercial and military applications for various missions, including weather reconnaissance, target acquisition, border patrol, search and rescue assisting operations, and environmental monitoring. The teaming of UAVs also provides cooperative tasking of UAVs to perform more complex tasks.1 Autonomous operation of UAVs requires a control system that decides on the actions and maneuvers of the vehicle to allow it to achieve its mission. The use of these automated systems reduces the human personnel requirement, which should operate the vehicle motion. They allow for operation at longer times and at higher altitudes without human support. Once the vehicle is programmed by the control system, it can operate its mission
automatically without any interference. Path planning of a UAV is a multi-objective optimization problem that takes into account various constraints, including technical, environmental, and mission-specific constraints. Moreover, UAVs have different missions in different environmental conditions. The aim of this study is to develop a simulation environment and an offline path planner for UAVs flying over three-dimensional (3-D) terrains. Since it is not an efficient approach to represent the path line of a UAV by straight line segments as in mobile robot applications, each 1
Computer Engineering Department, Marmara University, Turkey Industrial Engineering Department, Turkish Air Force Academy, Turkey
2
Corresponding author: Haluk Rahmi Topcuoglu, Computer Engineering Department, Marmara University, Goztepe ampusu, Kuyubasi 34722, Istanbul, Turkey. Email:
[email protected]
904
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
path is represented with continuous parametrized B-spline curves.2 Our framework considers the following four constraints in order to generate feasible flight trajectories: (i) collision-free trajectory; (ii) paths within the desired minimum and maximum distance above the terrain; (iii) paths that the UAV can maneuver with an angle greater than allowable minimum curvature radius; and (iv) paths that avoid threat zones on the terrain. By considering these constraints, the objective of our path planner is either to minimize the length of the path from source to destination or to provide a flight envelope for a given line of sight. Since path planning problems for UAVs have high computational complexities due to a set of several hard constraints and can be classified as NP-hard,3,4 various heuristic techniques can be proposed as the alternative approaches. Meta-heuristics in general provide efficient or better solutions for complex optimization problems.5,6 In this study, we present two novel meta-heuristics for UAV path planning problems, including Genetic Algorithms (GAs) and hyper-heuristics (HHs). GAs are natureinspired population-based meta-heuristic optimization algorithms.7,8 They use techniques inspired by natural evolution, such as selection, crossover, and mutation. In our study, we have designed and implemented problemspecific operators in order to improve the quality of the solutions for the generated terrains. On the other hand, HHs are meta-heuristic techniques for automating the process of selecting, combining, generating, or even adapting multiple simple low-level heuristics to solve hard computational search problems.9–11 HHs are problem independent; therefore, they have been successfully applied to various problems from different domains. The proposed knowledge-based operators and basic mutation operators, which do not have problem specific approaches, have been used as low-level heuristics in HH method. As part of this study, we developed a 3-D synthetic terrain generator tool that executes different terrain generation algorithms with the corresponding environmental parameters. A comparative study with a reference GA from the literature is conducted using synthetic 3-D terrains to demonstrate the effectiveness of our meta-heuristic techniques. The results of the experimental study clearly validate that our meta-heuristic approaches are very successful in constraint-free path planning of UAVs for various problem missions and terrain characteristics. The rest of the paper is organized as follows: Section 2 summarizes related works on a UAV path planning problem in the literature. In Section 3, the problem definition and mathematical modeling of the constraints are introduced. The details of terrain and path representations on our simulation environment are presented in Section 4. Proposed path planning algorithms are explained in Section 5. Section 6 introduces simulation results, performance evaluation, and output analysis of our work.
Finally, conclusions and future work are presented in Section 7.
2. Related work Path planning of UAVs has become an emerging research area, and various methods has been proposed in the literature. The A-star algorithm (which is a heuristic graph search method) has been applied to find the shortest path for the UAV.12 A potential fields-based algorithm has been implemented in a task planning and control system developed for multi UAVs in order to be able to detect the burnability risk of the terrain.13 Each cell of the ground is associated with a potential, initiated to a maximum value, and decreasing with time according to a specific law. There have been probabilistic methods in exploring the diversities of non-stationary environments. The principle of these methods is to construct a probabilistic map that defines the risk of threat for the vehicles. For instance, the depth map constructed by Sinopoli et al.14 provides information about the distance between the agent and the obstacles. The conditional probability that a UAV is defeated by a threat, under the condition that it follows a path, is defined and formulated based on the probabilistic map of the area.15 There are also Mixed Integer Linear Programming (MILP)-based approaches in the literature for UAV navigation.16,17 The vehicle is characterized by a discrete, linear model in a coordinate frame and additional linear inequalities representing dynamic and kinematic safety constraints.16 In a multi-vehicle team control system,17 trajectory optimization is handled by using a MILP-based receding horizon planner, which provides the arrival of the UAVs at the target on time. The task assignment problem of UAVs has also been studied by using MILP.18 Dynamic programming techniques are also considered for UAV navigation, such as task assignment19 and path planning.20 A path planning on an unknown environment problem has been modeled as an adaptive control of a Markov Decision Process (MDP),20 which is characterized by a set of states. In each state, there are several actions from which the decision maker must choose.21 The transition probabilities of the underlying Markov chain are estimated, and the control is applied based on the most recent estimate of the transition probabilities, which is known as certainty equivalence principle. Nature-inspired methods have been applied to UAV navigation problem. Considering a number of UAVs at different known initial locations, 2-D trajectories formed by successive way-points with a specified velocity distributions along each vehicle’s trajectory and arriving at a common target by satisfying route constraints have been generated by the Differential Evolution (DE) method.22 Using the same approach, the Radial Basis Functions
Oz et al. Artificial Neural Network (RBF-ANN) assisted DE algorithm has been used for UAV path planning design.23 The path planning of UAVs using Particle Swarm Optimization (PSO) method has been studied on 3-D24 as well as 2-D environments.25 Both research approaches ensure the avoidance of threat zones by representing the UAV paths as swarm particles. A new variant of PSO, named phase angle-encoded and quantum-behaved particle swarm optimization, was proposed in a recent study.26 Since straight lines are not sufficient and efficient representations, different types of geometries have been selected to represent trajectories. One is segment representation, which consists of many segments and encoding of the paths, is a sequence of simple splines. There are two types of segments, including straight segments to represent climbs, descents, and lines as well as curved segments to represent turns.27 On the other hand, B-spline curve representation is used to represent the flight path of the UAVs,28 where they generate terrain using only mathematical functions that require a large set of experimentally predefined constants. GAs have provided successful results for the 3-D UAV path planning problem29–31 by considering different encoding schemes to represent the candidate path solutions. Different path mutation mechanisms have been proposed in GA-based solutions.29 They have implemented different operators, including mutate and propagate, crossover, go to goal, mutate and match, which change the parameters of curve segments. In another study,30 non-uniform mutation is considered, in which the search space for the new gene is not constant, but it approaches the previous value of the corresponding gene as the algorithm converges. In our previous work,32 we proposed knowledge-based mutation operators that consider different objectives together, including the construction of feasible paths without collision, within the desired safety distance, with an angle greater than the minimum radius of curvature, which minimizes the length of the path for the UAV path planning problem. We also updated the safety distance calculation given by Nikolos et al.30 by considering the semi-sphere region below the UAV and selecting the minimum one. Another difference between our previous work and the study given by Nikolos et al.30 was the presentation of mission-specific goal definitions, such as sweeping flights and flight envelopes in a given line of sight. We considered a more realistic model for the maneuver capability and technical specifications of UAVs. Specifically, a maximum altitude constraint was considered as part of the fitness function evaluation. We also presented knowledge-based mutation operators, which alter the number or the position of the control points according to the fitness of the control point under consideration in order to create better individuals. Genetic Algorithms have also been used to assign tasks on a multi-UAV environment.33 In that study, a matrix
905 representation has been proposed to represent multivehicles and multi-targets. This paper proposes a complete simulation environment for path planning of a UAV by extending the findings of our previous study. Our simulation environment generates 3-D synthetic terrains with different characteristics for different goals and constraints by considering various path planning algorithms that were designed. Specifically, this work presents a novel knowledge-based crossover operator for a GA-based path planner and proposes a novel HHbased path planner for UAV navigation trajectory. The simulation environment facilitates running various scenarios and corresponding output analysis.
3. Problem definition Since straight line segments, which are used in mobile robot applications,34 or simple splines35 are not efficient methods representing the path line of a UAV, the path is represented by using B-spline curves.2 B-spline curves are suitable for representing the path of the UAVs, since they require few variables to define complicated curve paths. Moreover, a change/update in one control point only changes the part of the curve segments that is near the changing control point, which is due to its local effect. When compared with Be´zier curves, B-spline curves require more information but provide more control flexibility. We can change the position of a control point of a B-spline curve without globally changing the shape of the whole curve without sharp turns. As a result, B-Splines have been used to represent UAV paths in the previous work as well.28 In our path representation, the coordinates of the control points, which have floating point values, form a solution. The first (source) and the last (destination) points of the curve are fixed. The dynamic control points between these points, which form the route of the UAV, are used to construct the structure of the solution. It should be noted that an update in one of control points only changes the area near the updated control point due to its local effect. In the following section, we present hard constraints and objective functions for the UAV path planning problem. Although the same set of constraints are also considered in the literature,29,30 we present modifications on function calculations related to constraints in order to provide a more realistic representation.32 In addition, our work also considers an additional objective in order to provide different mission-specific cases.
3.1 Mathematical formulation of the UAV path planning problem The problem of determining the optimum navigation trajectory of an UAV is formulated as a minimization issue.
906
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
The terms in this problem can be classified into two categories: hard constraints (or technological constraints) that must be satisfied at the generated flight path, and objectives that are evaluated in terms of the given measure for the quality of the solution. The first four terms listed below are technological constraints and the remaining terms are the mission-specific objectives that are considered in our study. We either consider the single objective case (Obj1 or Obj2) or a multi-objective case, which considers both in computational experiments: • • • • • •
C1, Constructing a collision-free trajectory; C2, Providing a trajectory within the desired minimum and maximum distance above the terrain; C3, Constructing a path that allows the UAV to maneuver with an angle greater than the minimum radius of curvature; C4, Avoiding threat zones of different shapes, if any; Obj1, Minimizing the length of the path; Obj2, Providing a flight envelope in a given line of sight.
In this paper, we aim to minimize the total or the unified cost function by penalizing the four constraints. Therefore, the total cost of the constructed path by considering the above constraints is measured by the sum of five (or six) different cost terms as follows: f=
n X
ð1Þ
wi * fi
i=1
where each fi represents the cost function terms described below; n is equal to 5 or 6 based on the mission considered, and wi are the weights of each function that determine the priority of the function. Note that each fi is associated with the corresponding constraint given above. The term f1 represents the number of curve points inside the solid boundary. Therefore, the penalty value is proportional to the number of discretized curve points located under the solid surface. All n path segments of the flight path are assessed to determine whether or not they pass through the terrain by computing the distance between the curve point and the terrain using heightmap data. If this is true for a discrete point of the path line, then a constant penalty is added to term f1 . Consequently, this term allows the construction of the collision-free paths by giving high penalty values to the curves with more points inside the solid boundary. The formulation of the cost f1 is as follows: f1=
n X i=1
yi , where yi =
1 0
if di ≤ 0 otherwise
ð2Þ
where di is the distance between the curve point and the terrain, and i is the index of curve points. The term f2 is relevant to the distance penalty of the curve. This term actually consists of two penalty values, including the safety distance penalty (keeping a safety distance between UAV and the ground) and maximum distance penalty (maximum altitude because of technological restrictions or mission-specific constraints). The safety distance penalty aims to provide a flight path far from the specified minimum distance. The distance for each discretized curve point is checked for the safety distance and penalty value that is proportional to the difference between the distance and the desired safety distance is calculated. The penalty value for each curve point forms the cost function value. However, calculation of the distance of the curve point for only one terrain point is not sufficient on a 3-D environment since the curve point can be closer to any of the other points than the corresponding terrain point. Therefore, for each curve point, the distance between the corresponding terrain point and its neighbor points is calculated; the maximum penalty value of the neighboring terrain point distances is considered for each curve point as the safety distance penalty value. The maximum distance penalty provides a flight path that is in the range of specified maximum altitude of the UAV. If this term is ignored, then the generated path might be the shortest one, but that path cannot occur with respect to technical specifications of the UAV. The penalty value is calculated as proportional to the difference between distance to the ground and allowed minimum or maximum altitudes. The term f2 given below is represented in two separate terms, f2, 1 and f2, 2 , which are formulated below: f2, 1 = yi =
n P
max f(dmin di, k )=dmin g * yi ,
i = 1 kN (:)
1 0
if di,k < = dmin otherwise
where ð3Þ
and f2, 2 =
n P
f(di dmax )=dmax g * yi , i=1 1 if di ≥ dmax yi = 0 otherwise
where ð4Þ
with f2 = f2, 1 + f2, 2
ð5Þ
where N(:) is the neighbor set of the specific terrain point, di, k is the distance between the curve point and the terrain point, and dmin and dmax are the minimum and maximum safety distance from the terrain, respectively. The term f3 indicates the minimum radius of curvature penalty of the path. It is designed to prevent the UAV from exceeding the lateral and vertical acceleration limits,
Oz et al.
907
since the flight envelope determines the maximum radius of turns for the UAV. It is aimed to achieve a flight path with a specified minimum curvature angle by this term. To obtain the penalty value, the angle between two line segments of the curve is calculated for each three neighbor curve points. As in the previous terms, a penalty value is added that is proportional to the difference between the angle and the specified minimum angle. The term f3 can be formulated as follows: f3 =
n X
f( θi )=g * yi , i=1 1 if θi < = yi = 0 otherwise
where ð6Þ
where θi is the angle between the control point and the neighbors, and is the minimum curvature angle. The term f4 is relevant to the threat penalty. In our study, we consider the threat as a sphere with a given center point and radius (R). The distance between the center of the threat and each discretized curve point is checked for the threat safety distance, and the penalty value that is proportional to the difference between the distance and the radius of the threat is calculated. If the distance is greater than the radius, which means that the curve point is outside the threat, then no cost value is formed. Otherwise, the penalty value for each curve point, which is proportional to the difference between the radius and the distance, forms the cost function value. Here f4 is formulated as follows: f4 =
n X
f(R di )g * yi , i=1 0 if d i > R yi = 1 otherwise
where ð7Þ
where R is the radius of the threat in the shape of a sphere, and di is the distance between the curve point and the center of the sphere. The term f5 is the length of the flight path calculated by adding the distance of two neighbor curve points for each discretized point. This term is used in order to minimize the flight path lengths and can be formulated as follows:
the line of sight between the source point of the terrain and the curve points that represent the path. Let b be a point pi on the terrain, and ! n i is the normal vector of pi . Let us assume that an UAV is flying on a predefined trajectory and recently positioned on a specific point x. In ! this case, V x, b is the vector from x to b. UAV can have visual contact with point b, if the angle between the norn i ), where b is located and the vector mal vector of pi (i.e. ! ! V x, b is between 90 and 180 , and the angle between the ! normal vector of x (i.e. ! n x ) and the vector V x, b is between 0 and 90 . Then, f6 is formulated as f6 =
1, 0,
! ! if ! ni : Vx, b < 0 and ! n x : Vx, b > 0 otherwise:
ð9Þ
In order to evaluate cost function value, all fi are normalized by using Equation 10 to obtain values in the same range after their values are calculated. This normalization transforms fi values into the range of ½0, 1. normalized value =
value valuemin valuemax valuemin
ð10Þ
where value is the real value of the function, valuemin is the minimum value for which the function can take, and valuemax is similarly the maximum value for which the function can take. We assume zero for the minimum values for each function, while we take the maximum values in the current population as the maximum value that the function can take. The maximum value for each term is updated for each generation according to the individual values. The weights (wi ) given in the main equation can be experimentally determined or can be set according to different aspects, such as terrain specifications or missionspecific goal definitions (i.e. sweeping flights, flight envelope in a given line of sight, etc.). As the main objective is to obtain feasible flight paths, weights may be determined in such a way that the corresponding term (one of the fi ) dominates the rest. Figure 1 visualizes the constraints (represented in terms of related function terms) of a UAV path over a sample terrain.
1=2 n X 2 2 2 f5 = (xi + 1 xi ) + (yi + 1 yi ) + (zi + 1 zi ) i=0
ð8Þ
where n is the curve discretization number, and x, y, and z values are discrete coordinates of the points on the curve. The term f6 indicates the number of discretized curve points, which are not located in the line of sight of an observation point. The line of sight indicates the visibility of the path from a specific point. In our study, we consider
Figure 1. A typical simulation result of the UAV path planner on a sample terrain.
908
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
4. Simulation environment In this section, we present our simulation environment constructed for the path planning problem of UAVs by including terrain and path representations.
4.1 Terrain representation Our simulation environment represents the terrain information, which the UAV flies over, by heightmap structures. A heightmap is generally represented by a two-dimensional matrix, of which dimensions represent coordinate axis, mostly X and Z. The value of the matrix entry gives the height value, or Y coordinate, of the corresponding point. The scale of the matrix that gives the point intervals may be changed by setting appropriate values. The height value of a point may be determined by using the following formula: height = heightmap½(column + row * size)
ð11Þ
where column and row are dimensions of the heightmap matrix, and size is the size of the matrix. The height values of the points that are not stored in the heightmap matrix due to the scale may be found with linear interpolation by using the following equation: height = H1 +
P P1 * (H2 H1 ) P2 P1
ð12Þ
where P is the point of which the height value to be calculated but not stored in the heightmap, P1 and P2 are the closest points to the desired point stored in the heightmap matrix, and H1 and H2 are the height values of P1 and P2 , respectively. In order to simulate a 3-D environment, we use jME (jMonkey Engine),36 which is a Java scenegraph API based on OpenGL. We adapt jME API to generate and visualize terrains for UAV navigation. The terrain generation phase creates heightmap data using different methods in different sizes. We consider two different algorithms, including the Midpoint Displacement algorithm37,38 and Hill algorithm38,39 in order to generate terrains: •
Figure 2. Sample terrains: (a) Terrain 1 (generated by the Midpoint Displacement algorithm); and (b) Terrain 2 (generated by the Hill algorithm).
Midpoint displacement algorithm. This algorithm creates terrain by displacing the center of a polygon multiple times. It subdivides triangles, squares, and diamond-shaped areas. One-dimensional midpoint displacement algorithm starts with a horizontal line and continues by dividing the lines from the midpoint. There are different versions of the algorithm based on triangle, square, and diamond shapes. We consider the diamond–square algorithm in our environment. The two-dimensional diamond–square algorithm starts with a plane and subdivides the plane by calculating the midpoint of the grid, which
•
is called the diamond step, and calculating the midpoint of the sides of the plane, which is called the square step. Hill algorithm. This algorithm creates random circular displacements stacked on one another, which culminate in the resemblance of a hilly landscape. It starts with a flat terrain. After it picks a random point C with coordinates Cx , Cy , and Cz on the terrain as well as a random radius size r, it raises a hill on the terrain centered at the point C, having the given radius r. The height of a sample point A with coordinates Ax , Ay , and Az , which is located on the hill can be calculated as:38 Ay = r2 ((Ax Cx )2 + (Az Cz )2 ):
ð13Þ
This process is repeated as many times as needed. Two sample terrains given in Figure 2 are among the sample terrains considered in our comparison study, where the first terrain is generated by using Midpoint Displacement algorithm and the second terrain is generated by using Hill algorithm. We include threat zones on our terrains to simulate potential risky areas (e.g. radar), which UAV should avoid entering. Since one of our objectives is to keep the vehicle away from the threats, a new model for the threatening area is developed as a part of our simulation environment. We consider the threat zones as areas represented by spheres. We randomly select a point (x, y, and z
Oz et al.
909
coordinates) on the generated terrain and assign it to the center of the threat. We also randomly determine the radius of the sphere, which represents the threatening area. Namely, our threat zones are represented by a vector threat = ½x, y, z, R. Our experimental study includes one threat zone for each terrain representation.
4.2 Path representation In our study, the flight path that the UAV would follow is represented by B-spline curves. B-spline curves are piecewise polynomial curves that are differentiable to a specified order.2 These are parametric curves constructed by calculating basis functions. Mathematically, given n + 1 control points P0 , P1 , . . . , Pn and a knot vector U = u0 , u1 , . . . , um , a B-Spline curve of degree k defined by these control points and knot vector is C(u) =
n X
Ni, k (u) * Pi
ð14Þ
i=0
where Ni,k (u) are B-Spline basis functions of degree k. The degree of a B-Spline curve determines the smoothness of the curve. When the value of k becomes higher, it will cause smoother curves. In this study, the degree is taken as three in order to provide the required smoothness. With coordinates (x0 , y0 , z0 ), . . . , (xn , yn , zn ), the coordinates of B-Spline can be written as X (t)
=
n X
Ni,k (u) * xi ,
ð15Þ
Ni,k (u) * yi ,
ð16Þ
Ni,k (u) * zi :
ð17Þ
i=0
Y (t)
=
n X i=0
Z(t)
=
n X i=0
B-spline basis functions are used as weights, similar to Be´zier curves. The function domain is divided by knots and the basis function values always have non-zero values. The basis functions Ni,k are defined recursively with an algorithm (called the de Boor recursion formula) using the knot values. The details of B-Spline curve constructions, including the recursion formula, can be found in Farin.2
5. Proposed meta-heuristics for the UAV path planning problem In this section, we briefly explain the details of our GA and HH approaches for generating a collision-free 3-D UAV navigation trajectory on a given terrain.
5.1 Details of GA-based approach GAs, which are inspired from nature, operate by iteratively generating a population of chromosomes that are encoded forms of candidate solutions. In order to reach a near-optimum or a good solution, a GA typically uses various genetic operators including crossover and mutation, by applying the survival of the fittest principle. GAs have been efficiently utilized in a wide variety of applications in the engineering and science,5,6,8 as well as simulation environments.40,41 A path of a UAV (i.e. a chromosome in the population) is represented by a set of B-spline curve control points that have x, y, and z coordinates with floating point values for a 3-D environment in our proposed meta-heuristics. The first and the last points of a solution represent the source and destination points, respectively. These two points are fixed and the other free-to-move control points change during the execution of our GA-based approach. In addition, the number of control points may increase or decrease during the execution as well. In our study, the selection of individuals for mating is carried out by the tournament selection method with a tournament size of five. We consider a steady-state population model with an elitism-based survivor selection mechanism. At each iteration or generation, crossover and mutation operators are applied to selected individuals in order to generate two offspring. Then, the best offspring among them is selected and put in place of the worst individual in the population.7 5.1.1 Generating the initial population. The initial population of the GA is generated randomly by considering the boundaries of the terrain. The x and z coordinates are selected randomly from the range ½0::TerrainSize 1, and the y coordinate of the point, which will draw the height of the individual, is set randomly by considering the feasibility in that case. To provide the feasibility of the curve, the y coordinates of the control points are generated on the upper side of the terrain. If a non-feasible point that collides with the terrain is created, then its y coordinate is re-generated by a random number generator until it provides the feasibility of the point. This does not guarantee the collision-free B-spline curve, since its curve points may collide with the terrain, although its control points are feasible. However, this method increases the probability of the feasibility of the curves. 5.1.2 Crossover operators. Three crossover operators are considered in our study. The first is simple one-point crossover that simply cuts the parents from one point randomly and splits both parents at the same point. It then creates two new individuals by exchanging the portions that remain (see Figure 3(b)). The other crossover operator is a
910
Simulation: Transactions of the Society for Modeling and Simulation International 89(8) to the next crossover point in the same parent (i.e. the next control point) until it finds an appropriate one. The same procedure is applied for each offspring. Therefore, the crossover point may be different for two mates. The knowledge-based crossover operator is especially helpful for mates having a different number of points, due to the distinct distribution of the control point locations. The last crossover operator (random crossover) randomly selects the operator to be applied among two other crossover operators, namely one-point crossover and knowledgebased crossover. 5.1.3 Mutation operators. Knowledge-based mutation operators that work on the control points of the individual that are free to move are considered in our study.32 The operators alter the number or the position of the control points according to the fitness value of the considered control point. The B-spline curve is divided into segments, which are the separated parts between the control points. In general, the operator starts working by finding the worst segment, namely the segment that has the minimum fitness value (maximum cost) of the individual curve. When calculating the fitness value of the curve segments, the length term in the objective function is not considered, since it does not affect the feasibility of the curve. We consider the following three different mutation operators in our experiments. •
Figure 3. Applying crossover operators: (a) parents; (b) offspring after one-point crossover; and (c) offspring after knowledge-based crossover.
novel knowledge-based crossover operator that aims to shorten the length of the curve by considering the locations of the crossover point (see Figure 3(c)). This operator is applied after deciding on the appropriate crossover points for two individuals. If the selected crossover point in the parent causes, in the construction of a curve, a segment that reverses the direction back to the starting point of the path, then this crossover point is skipped, and it is shifted
Update operation. This operation updates the worst control point of the individual. The quality of each control point is computed by the aggregate cost of the curve points on the two neighbor curve segments. For instance, the cost of the control point 2 is calculated by adding the cost of the segment 1 and segment 2, where segment 1 is the piece of B-spline curve that is between the control points one and two, and segment 2 is the piece of B-spline curve that is between the control points two and three. After the control point that has the maximum cost value is found, and if it is not the source or the destination point, this control point is replaced by a new one in order to increase the fitness of the curve. In order to achieve this objective, the new point is created in a feasible region. The x and z coordinates of the new point are set by considering the following equations: xi *
=
xi1 + k * (xi + 1 xi1 ) +
ð18Þ
zi *
=
zi1 + k * (zi + 1 zi1 ) +
ð19Þ
where k and are terrain-specific parameters and assigned randomly between 0 and 1. The xi * and
Oz et al.
•
•
zi * are the new coordinates of the updated point, while xi1 , xi + 1 and zi1 , zi + 1 are the x and z coordinates of the neighbor control points, respectively. The new point should be in a location between the previous and following points in order to prevent UAV from going back and lengthening its path. The y coordinate of the new control point is randomly set from the feasible region generated by using the new x and z values. The y coordinate is set by adding a displacement to the current value of y so that the final value will be within the minimum and maximum safety distances. Insert operation. This operation increases the number of the control points in a given individual and aims to increase the quality of the individual. After obtaining the fitness values of each curve segment, the segment that has the lowest value is established. Although the update operator considers aggregate values of segments in order to update a control point, the insertion operator considers individual segments in order to insert a new control point. In this operator, the worst curve segment is first determined. Then, by using the first and last control points of this segment, the new control point is created in the same manner as the update operator. Delete operation. This operation also alters the number of the control points in the individual. It determines the worst control point in the B-spline curve (by considering aggregate fitness values of segments as in the update operator) and simply deletes this point from the curve. Therefore, this individual has one less control point number.
Figure 4 shows examples of update, insertion, and deletion operations on a selected control point CP3. It is possible that a newly inserted control point may not be on the path (see Figure 4) due to the characteristics of the B-spline curve.
5.2 Details of our HH-based approach HHs represent emerging meta-heuristic techniques that are defined as ‘heuristics to choose heuristics’9,42 HHs aim to determine optimal or quasi-optimal solution for the problem addressed in the search space of heuristics rather than the search space of the solutions. Since a HH-based approach has no knowledge of the domain by working a level of abstraction, it has a set of low-level heuristics to call. Low-level heuristics either help for transforming the state of the given problem (constructive strategy) or provide an improvement step (a perturbation strategy).43 The former category starts with an empty solution and gradually builds a complete solution by intelligently selecting an appropriate low-level heuristic. On the other hand, in
911
Figure 4. Mutation operations on a sample B-spline curve.
the latter category, a low-level heuristic is selected and applied iteratively until a stopping condition met. The heuristic selection mechanism and the criteria for move acceptance are the two major components of HH techniques. There are a large number of heuristic selection mechanisms proposed in the literature. Hyper-heuristics considered in our study are random methods, which include Simple Random (SR), Random Descent (RD), Random Permutation Descent (RPD), a Greedy Approach (GR), and Choice Function (CF).10,42 The SR approach randomly selects a low-level heuristic at each iteration based on a uniform distribution, and it is applied once. On the other hand, RD selects a low-level heuristic at random and continuously applies it until there is no improvement in the solution. Both Random Permutation (RP) and RPD methods select a random permutation of low-level heuristics. The selected permutation is repeated until a termination condition is satisfied for the former, and is repeated until there is no improvement in the solution for the latter. In GR, the change in the objective function in the solution is evaluated by applying each
912
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
low-level heuristic at each iteration. The best low-level heuristic is then applied, as long as there is improvement.10 The CF of each low-level heuristic (Nj ) is calculated by using information concerning individual effectiveness (f1 (Nj )), information concerning recent performance of consecutive pairs of heuristics ( f2 (Nj , Nk )) and information concerning amount of time ( f3 (Nj )) since the heuristic was last called:10 f1 (Nj ) =
X
α(n1)
In (Nj ) Tn (Nj )
ð20Þ
β(n1)
In (Nj , Nk ) Tn (Nj , Nk )
ð21Þ
n
f2 (Nj , Nk ) =
X n
f3 (Nj ) = τ(Nj )
•
•
ð22Þ
where In (Nj ) is the change in the fitness function, Tn (Nj ) is the amount of time taken the nth last time heuristic Nj was called, In (Nj , Nk ) is change in the fitness function the nth last time heuristic Nk was called after heuristic Nj , α and β parameters show the importance of the recent performance. After defining the elements of the choice function, the resulting choice function used can be defined as f (Nj ) = αf1 (Nj ) + βf2 (Nj , Nk ) + δf3 (Nj ):
•
ð23Þ
In this study, we consider three different methods for using the choice function, which are Straight Choice Function (SCF), Ranked Choice Function (RCF), and Roulette Choice Function (OCF). SCF method simply chooses the low-level heuristic that gives the best value of choice function, at each iteration. RCF method ranks the low-level heuristics according to the choice function values and evaluates the change in the objective function by applying a proportion of the highest ranked heuristics. Finally, OCF method selects a low-level heuristic at each iteration with its share proportional to the total value. Three different acceptance criteria are used in our study, including All Moves (AM), Only Improving (OI), and Improving or Equal (IE).42 We apply each of these acceptance criteria (AM, OI, and IE) for each of the 7 heuristic selection mechanisms (SR, RD, RPD, GR, SCF, RCF, and OCF) in order to measure their effectiveness on the quality of the solutions, which generate a total of 21 different combinations. We consider a perturbation strategy where it works on complete solutions during its execution and the set of low-level heuristics are used to improve the quality of the solution. We briefly summarize the set of low-level heuristics in the following section. 5.2.1 Low-level heuristics for the perturbation strategy. Various combinations of the three mutation operators (given in Section 5.1) of our GA-based solution are considered as the first set of low-level heuristics, which are given below.
• •
•
K1: Knowledge-based update. In this low-level heuristic, the selection and removal of the worst control point of the B-spline curve as well as creating a new control point to locate instead is handled in a similar manner as in the update mutation operator (given in Section 5.1.3). K2: Knowledge-based insert. In this case, after the worst segment of the B-spline curve is established by the method described above, a new control point is inserted into the B-spline curve. The new control point is formed by considering safety distance constraints similar as in to in the update operator. K3: Knowledge-based delete. This low-level heuristic selects the worst control point by considering the fitness value, as in the update operator, and deletes this point from the curve. K4: Knowledge-based insert–delete. One of the knowledge-based insert or delete operators is selected randomly and applied to the individual. K5: Knowledge-based insert–delete–update. It selects the operator type to be applied among the knowledge-based insert, delete, and update operator types. K6: Knowledge-based threshold. In this case, minimum and maximum threshold values are used to decide the operation type to be applied. It selects the knowledge-based insert operator if the individual’s number of control points is less than the minimum value specified; however, it selects the knowledge-based delete if the number of control points is more than the maximum value. Otherwise, if the number of control points is between the minimum and maximum threshold values, then the operator type is selected randomly among three knowledge-based operators including update, insert, or delete.
We also include the following set of low-level heuristics in our framework, which do not consider any restrictions or knowledge. •
•
•
R1: Random update. In this low-level heuristic, one of the control points in the B-spline curve representing the individual is selected and replaced by a randomly created point on the terrain. R2: Random insert. In this low-level heuristic, a randomly created point on the terrain is appended to the B-spline curve as a new control point. This mechanism increases the number of control points at each iteration. R3: Random delete. In this low-level heuristic, one of the control points in the curve is chosen randomly as in the update operation, and this control
Oz et al.
•
•
•
point is removed from the individual by decreasing the number of control points of the B-spline curve. R4: Random insert–delete. To keep the number of control points in the individual in a reasonable range, one of the random insert or delete operator types that are selected randomly is applied to the individual. R5: Random insert–delete–update. In this case, one of the random insert, update, or delete operator types are selected randomly and applied to the individual. R6: Random threshold. This one also behaves similar to the knowledge-based threshold mechanism. If the number of control points is less than the specified minimum threshold value, then the random insert operator is applied. If it is more than the specified maximum threshold value, then the random delete operator is applied to decrease the number of control points to the desired range. Otherwise, one of the insert, delete, or update operator types are selected. Thus, the number of control points of the individuals in the population remains between the specified minimum and the maximum values.
6. Experimental study In this section, we present the results of our simulation runs and computational experiments in order to demonstrate the effectiveness of the algorithms used for the UAV path planning problem. The algorithms of the UAV path planner and simulation environment are coded in the Java programming language, and the computational experiments have been conducted on a cluster of machines, each of which has an Intel Xeon 2.33 GHz processor running the Linux operating system. The default values of general parameters listed in Table 1 are considered in our study, unless otherwise stated. The experimental study presented in this section is divided into two parts. In the first part, the experiments are performed to determine the most appropriate parameters of each meta-heuristic considered. In the second part, we present the results of computational experiments to evaluate the effectiveness of our GA-based and HHbased solutions. In addition, we validate our techniques by comparing their results with a GA-based reference study.
6.1 Experiments for setting the GA parameters The first set of experiments identifies the values of algorithm-specific parameters for the GA. The six algorithm-specific parameters, including the population size, crossover rate, crossover type, mutation rate, mutation type, and mutation point selection mechanism with their sets of values are presented in Table 2. Those tests
913 Table 1. Default settings of selected parameters of experimentation. Parameter
Value
Terrain size Safety distance Maximum distance Minimum curvature radius for knowledge-based update mutation Number of control points for initial population Number of curve points to be considered in the fitness calculation Threshold values for number of control points (min, max) w1 , w2 , w3 , w4 , w5 , w6
128 × 128 5 40 50 0.5 8 50 (3, 15) 0.2, 0.2, 0.2, 0.2, 0.2, 0
are performed 5 times for each 4 terrains by obtaining 1000 generations. After deciding the values for these parameters, the effect of the generation size in the performance advance is examined and the best value is used in the subsequent testing phases. As shown in Table 2, there are 648 combinations, each of which is run with 30 replications. In each complete replication of the experiments, all possible combinations of the level of factors given in this table are examined. Therefore, we involve a full factorial design in this study.44 In addition, we validate the feasibility of our results on two different terrains. Individual feasibilities of the best solution (with respect to four constraints of the given objective) are measured at each generation (see Figure 5). We observe that collision penalty and threat zone penalty values are all zero beginning from the first generation, i.e. it constructs feasible paths without terrain collision where UAV navigates far from the threat zone specified. On the other hand, the curvature radius penalty decreases to a zero value after some iteration. However, the safety distance penalty (which is set when the constructed path is not within the desired minimum distance to the terrain and maximum distances to the sea level) does not have zero value during the GA run. Although the safety distance penalty does not reach a zero value, it decreases as generation size increases and has lower values at the end of the 1000th generation. The number of control points in the B-spline structure is also varied in order to measure its effect on the solution quality. For smooth terrains, a smaller number of control points have higher performance, and the fitness value of the best individual in a population generally decreases as the number of control points increases. Between 5 and 11 control points are tested. We find that a smaller number of control points is enough to provide better paths. As the number of control points increases, the path becomes more
914
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
Table 2. Parameter settings for the GA approach. Population Size (A)
Crossover Rate (B)
Crossover Operator (C)
Mutation Rate (D)
Mutation Operator (E)
Mutation Point in Selection Mechanism (F)
1. 50 2. 100 3. 200
1. 0.70 2. 0.80 3. 0.90
1. One-Point 2. Knowledge-Based 3. Random (one-point versus knowledge-based)
1. 0.05 2. 0.10 3. 0.15
1. Update 2. Random insert–delete 3. Random insert–delete with threshold 4. Random insert–delete–update
1. Random 2. Heuristic-based
Based on the pre-experimentation phase, the population size is set to 200, and the random crossover and insert/ delete/update mutation types are selected. The number of control points is set to 5 for smooth terrain, while the best fitness value is set with 8 control points for rough terrain. In addition, the mutation and crossover rates are set to 0.10 and 0.90, respectively.
6.2 Experiments for setting HH parameters
Figure 5. Feasibility of the best solution in each generation by considering four constraints of the unified objective for two different terrains given in Figure 2.
complex and, in particular, the length of the path increases resulting in worse cost values. However, as terrain structure becomes harder, more control points are necessary to deal with the difficulty. Better results are observed in our experiments for a larger number of control points. Generally, individuals that have seven or eight control points give the best fitness in the population, while less or more control points result in a fitness decline for rough terrains. The performance of mutation and crossover types for different terrain structures has also been examined in our pre-experimentation phase. The mutation and crossover types behave in the same manner on different terrains.
In the second set of experiments, we measure the effects of various parameters of our HH-based approach on the quality of the solutions. The first important factor is the heuristic selection mechanism, which decides how to determine which low-level heuristic is applied to the individual. In this study, we consider seven heuristic selection mechanisms as explained in Section 5.2, which are SR, RD, RPD, and GR, and three CF implementations, including SCF, RCF, and OCF. A second factor is the acceptance criteria of the generated solutions, which can be OI, AM, and IE. Moreover, the number of control points in each path is also tested with four different values: 5, 7, 10, and 15. Our HH-based solutions generally perform similar to the GAbased case, when the number of control points are varied. Therefore, we consider five control points for smooth terrains and seven control points for rough terrains. Table 3 presents the set of values considered for each parameter of our HH-based solution in the performance evaluation phase. In each complete replication of the experiments, all possible combinations of the levels of factors given in Table 3 are examined (full factorial design). Based on the analysis of variance (ANOVA) of the total cost value, terrain type, objective weight, and mission are the main effects. This relation is strongly proven with the ‘predicted R2 ’ of 0.922, which is in reasonable agreement with the ‘adjusted R2 ’ of 0.920. The normalized average cost values of HH cases at the end of the generation of 1000 are given in Table 4. The table provides 21 HH combinations due to 7 different heuristic selection mechanisms and 3 different acceptance criteria.
Oz et al.
915
Table 3. Parameter settings for the HH approach. Terrain Type
Objective Weights
1. Smooth 2. Smooth 3. Rough 4. Rough
1. w1 = 0:30, w3 = 0:30, w5 = 0:10 2. w1 = 0:30, w3 = 0:30, w5 = 0:10 3. w1 = 0:20, w3 = 0:20, w5 = 0:20
w2 = 0:10, w4 = 0:15,
Mission
HH Learning Mechanism
Acceptance Criteria
1. Shortest Path 2. Line of Sight
1. SR 2. RD 3. RPD 4. GR 5. SCF 6. RCF 7. OCF
1. OI 2. AM 3. IE
w2 = 0:15, w4 = 0:15 w2 = 0:20, w4 = 0:20,
Table 4. Performance results of various heuristic selection mechanism and acceptance criteria combinations. Method
SR-OI SR-AM SR-IE RD-OI RD-AM RD-IE RPD-OI RPD-AM RPD-IE GR-OI GR-AM GR-IE SCF-OI SCF-AM SCF-IE RCF-OI RCF-AM RCF-IE OCF-OI OCF-AM OCF-IE
Smooth terrains
Rough terrains
A
B
C
D
0.050866 0.357393 0.047180 0.045310 0.345818 0.077422 0.056459 0.389912 0.072452 0.190661 0.244594 0.364430 0.077666 0.188607 0.039236 0.090062 0.388654 0.063940 0.115617 0.236298 0.098018
0.113197 0.550951 0.168060 0.132330 0.546300 0.160925 0.094894 0.537905 0.139177 0.393703 0.297539 0.353737 0.227836 0.220226 0.188039 0.154903 0.310685 0.094581 0.213261 0.338874 0.198870
0.051072 0.341367 0.113349 0.220417 0.379887 0.082062 0.124165 0.347339 0.108926 0.373611 0.362993 0.342888 0.190976 0.190458 0.243409 0.099861 0.460876 0.049109 0.220292 0.318568 0.186435
0.066495 0.403325 0.113527 0.075613 0.437596 0.061243 0.061691 0.470409 0.116994 0.332378 0.245191 0.262177 0.092692 0.222814 0.131056 0.203870 0.389910 0.058953 0.190607 0.167330 0.228415
As shown in Table 4, choice function-based approaches with improving or equal (IE) acceptance criteria are found to be better than the other approaches for all terrains. In general, the all moves (AM) acceptance method gives the worst results with the maximum cost values. Random approaches do not have the same performance as choice function-based approaches. Based on the preexperimentation phase, the heuristic selection mechanism is set to SCF or RCF with IE acceptance criteria, unless otherwise stated. As in the GA-based approach, 5 and 7 control points are considered for smooth and rough terrains, respectively.
6.3 Performance evaluation and discussion The first part of our experimental study is to compare the quality of the solutions generated by our two
meta-heuristic-based solutions. The terrain set is extended with additional terrains created by Midpoint and Hill algorithms. Each meta-heuristic is executed 30 times for each terrain generated. The average normalized cost values and standard deviations of 30 different runs of each algorithm for the terrains are shown in Table 5. It is determined that most of the best results are achieved by GAs. While the average cost values of the GA are the lowest for most of the terrain structures used in our experimental study, HHs provides better results for the most of the rough terrains. To deal with rough terrain structures, HHs are generally found to be better than the other meta-heuristics due to its set of low-level heuristics with different characteristics. Figure 6 presents simulation results for the two different test cases (smooth and rough terrains) using the GA-based path planner. The path for Terrain 1 has 5 control points,
916
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
Table 5. Average cost and standard deviation values of proposed meta-heuristics. GA
Smooth Terrains
Rough Terrains
HH
Mean
Standard deviation
Mean
Standard deviation
0.07388747 0.07989536 0.06415956 0.02902435 0.09512903 0.06406619 0.11393455 0.12092739 0.08514292 0.12724021
0.04528386 0.04999550 0.03784570 0.04647378 0.03256975 0.03852906 0.04560835 0.05251748 0.05357843 0.04058415
0.11644246 0.20056592 0.20296123 0.13001969 0.10855423 0.14800588 0.07490808 0.11748002 0.20185281 0.05565815
0.11158013 0.13459508 0.13615052 0.14567411 0.08944678 0.09494684 0.09830751 0.10833708 0.10285532 0.06888966
while the other path generated for Terrain 2 has 7 control points including source and destination points. Our second set of experiments compares the performance of our HH- and GA-based UAV path planner approaches with a GA-based reference study proposed in the literature.30 In the reference study, the initial
population is created randomly by considering feasible path lines represented by B-spline curves. That study considers floating-point coding in order to represent path line control points. The initial population is created randomly by considering lower and higher constraints on each gene. The selection scheme starts with the truncation model that chooses T % of elements with the best fitness for the next generation. These individuals are then used for a new population generation process by the roulette wheel procedure of traditional genetic algorithms. The threshold value (T ) provides different schemes and is also an algorithmic parameter of this implementation. A threshold value of 0:5 was used in those experiments, unless otherwise stated. The GA-based reference work considers a non-uniform mutation operator and a heuristic crossover operator. The non-uniform mutation selects the gene to be mutated randomly and updates it with a new point close to the former value as algorithm evolves. Using this approach, search space is shrunk from one generation to another. Similarly, the heuristic crossover provides the search in the most promising direction by generating a new child close to the parent with higher fitness. Two parents x1 and x2 generate an offspring x3 if x2 is not worse than x1 as follows:30 x3
Figure 6. Sample paths for Terrain 1 and Terrain 2 given in Figure 2.
=
r(x2 x1 ) + x2
ð24Þ
where r is a random number between 0 and 1. Although the authors consider classic crossover and mutation operators in addition to heuristic crossover and non-uniform mutation operators, the probability of proposed operators was kept higher in order to provide feasible solutions after a small number of generations. In our experiments, we consider optimum GA parameters acquired by the experimental study of Nikolos et al.30 The parameter setting of the genetic algorithm is as follows: population size = 100, threshold (T ) = 0.5, heuristic crossover probability = 0.75, classical crossover probability = 0.15, non-uniform mutation probability = 0.15, uniform mutation probability = 0.05, and generation size = 50.
Oz et al.
917
Figure 7. Normality plot of total cost of the best individual for the GA-based solution.
Figure 7 presents the normality plot of the total cost of the best individual of a simulation run of the GA-based path planning algorithm. As can be seen from this figure, the p-value is equal to 0.726. Similar plots are observed for the other scenarios for both GA- and HH-based runs. The resulting p-values strongly validate the normality assumption. One-way ANOVA and Tukey tests are performed to determine whether the pair-wise performance between our meta-heuristic algorithm and reference GA are statistically significant, or not. As shown in the ANOVA table (Tables 6 and 7), differences are significant at the α = 0:05 level, and according to the Tukey test, our GA algorithm outperforms both our HH approach and the reference GA algorithm, with respect to the total cost of the best individual, for both smooth and rough terrains. In addition, our HH approach outperforms the reference study according to the Tukey test.
7. Conclusion In this study, we have presented a 3-D simulation environment for offline path planning of UAV on 3-D synthetic terrains. Our path planner is designed with meta-heuristic techniques, including GA and HHs. Our framework considers technical constraints as well as mission-specific objectives to construct the flight path, which is represented by B-spline curve structures. Specifically, the generation of flyable paths with no terrain collisions, within the desired minimum and maximum distance to terrain, which allow UAVs to maneuver with an angle greater than allowable minimum curvature radius, and that avoid the threat zone on a terrain are the set of constraints that minimize the length of the path from the source to destination and provide a flight envelope in a given line of sight are the objectives in our study. Our 3-D path planner was tested for different scenarios, and the simulation results
Table 6. Pair-wise Comparison of Hyper-heuristics and the GA for Smooth and Rough Terrains. Method
Mean Variance Degrees of freedom t Statistic P(T ≤ t) one-tail t Critical one-tail P(T ≤ t) two-tail t Critical two-tail
Smooth terrain
Rough terrain
HH
GA
HH
GA
0.096646 0.000569 48 14.51011 0.000000 1.677224 0.000000 2.010635
0.022587 0.000212
0.094284 0.00093 47 10.79936 0.000000 1,677927 0.000000 2,001174
0.024397 0.000326
918
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
Table 7. Pair-wise comparison of HHs and reference GA for smooth and rough terrains. Method
Mean Variance Degrees of freedom t Stat P(T ≤ t) one-tail t Critical one-tail P(T ≤ t) two-tail t Critical two-tail
Smooth terrain
Rough terrain
HH
Ref. GA
HH
Ref. GA
0.096646 0.000569 57 –5.722034 0.000000 1,672028 0.000000 2,002465
0.135153 0.000789
0.094283 0.000930 58 –7.87729 0.000000 1,671552 0.000000 2,001717
0.15736 0.000993
validate the ability of our approach to produce near optimal trajectories without violating the constraints. We also compared the quality of the solutions generated by our HH-based and GA-based techniques with a reference study developed for UAV navigation. The results we obtained indicate the effectiveness of our meta-heuristicbased path planner for various test cases. Funding This research received no specific grant from any funding agency in the public, commercial, or not-for-profit sectors.
References 1. US Department of Defense. Unmanned Aircraft Systems (UAS) Roadmap, 2005–2030. Office of the Secretary of Defense, 2005. 2. Farin G. Curves and Surfaces for Computer Aided Geometric Design: A Practical Guide. New York: Academic Press, 2001. 3. Tang Z and Ozguner U. Motion planning for multi-target surveillance with mobile sensor agents. IEEE Transactions on Robotics 2005; 21: 278–283. 4. Lavalle SM. Planning Algorithms. Cambridge: Cambridge University Press, 2006. 5. Raidl G. Hybrid Evolutionary Algorithms for Combinatorial Algorithms. Habilitation Thesis, Vienna University of Technology, 2002. 6. Back T, Fogel DB and Michalewicz Z. Handbook of Evolutionary Computation. Oxford: Oxford University Press, 1997. 7. Eiben AE and Smith JE. Introduction to Evolutionary Computing. New York: Springer, 2003. 8. David E. Goldberg. Genetic Algorithms in Search, Optimization, and Machine Learning. Addison Wesley, 1989. 9. Burke E, Kendall G, Newall J, Hart E, Ross P and Schulenburg S. Handbook of Metaheuristics. Dordrecht: Kluwer Academic Publishers, 2003. 10. Cowling P, Kendall G and Soubeiga E. A Hyperheuristic Approach to Scheduling A Sales Summit ( Lecture Notes In Computer Science, vol. 2079). New York: Springer, 2001, pp.176–190.
11. Burke EK, Hyde M, Kendall G, Ochoa G, Ozcan E and Qu R. A Survey of Hyper-heuristics. Technical Report No. NOTTCS-TR-SUB-0906241418-2747, School of Computer Science and Information Technology, University of Nottingham, Computer Science, 2009. 12. Qu YH, Pan Q and Yan JG. Flight path planning of UAV based on heuristically search and genetic algorithms. In 31st Annual Conference of IEEE Industrial Electronics Society, 2005, pp.45–46. 13. Gancet J, Hattenberger G, Alami R and Lacroix S. Task planning and control for a multi-UAV system: architecture and algorithms. In IEEE/RSJ International Conference on Intelligent Robots and Systems, 2005, pp.1017–1022. 14. Sinopoli B, Micheli M, Donatot G and Koo TJ. Vision based navigation for an unmanned aerial vehicle. In Proceedings of the IEEE International Conference on Robotics and Automation, 2001. 15. Dogan A. Probabilistic path planning for UAVs. In Proceedings of the 2nd AIAA Unmanned Unlimited Systems, Technologies, and Operations - Aerospace, 2003. 16. Schouwenaars T, How J and Feron E. Receding horizon path planning with implicit safety guarantees. In Proceeding of the American Control Conference, 2004. 17. King E, Kuwata Y and How JP. Experimental demonstration of coordinated control for multi-vehicle teams. International Journal of Systems Science 2004; 37: 385–398. 18. Schumacher C, Chandler PR, Pachter M and Pachter LS. Optimization of air vehicles operations using mixed-integer linear programming. Journal of the Operational Research Society 2007; 58: 516–527. 19. Alighanbari M and How JP. Cooperative task assignment of unmanned aerial vehicles in adversarial environments. In Proceedings of the American Control Conference, 2005. 20. Chakravorty S and Junkins JL. A methodology for intelligent path planning. In Proceedings of the 2005 IEEE International Symposium on Intelligent Control, 2005. 21. Lawler GF. Introduction to Stochastic Processes, 2nd edn. New York: Chapman and Hall/CRC, 2006. 22. Nikolos IK and Brintaki AN. Coordinated UAV path planning using differential evolution. In Proceedings of the 13th Mediterranean Conference on Control and Automation, 2005. 23. Zografos ES, Nikolos IJ and Brintaki AN. Uav path planning using evolutionary algorithms. Studies in Computational Intelligence 2007; 70: 77–111.
Oz et al. 24. Foo JL, Knutzon JS, Oliver JH and Winer EH. Three-dimensional path planning of unmanned aerial vehicles using particle swarm optimization. In AIAA/ISSMO Multidisciplinary Analysis and Optimization Conference, 2007. 25. Li S, Sun X and Xu Y. Particle swarm optimization for route planning of unmanned aerial vehicles. In Proceedings of IEEE International Conference on Information Acquisition, 2006. 26. Yangguang F, Mingyue D and Chengping Z. Phase angleencoded and quantum-behaved particle swarm optimization applied to three-dimensional route planning for UAV. IEEE Transaction on Systems Man and Cybernetics Part A Systems and Humans 2012; 42: 511–526. 27. Rathbun D, Kragelund S, Pongpunwattana A and Capozzi B. An evolution based path planning algorithm for autonomous motion of a uav through uncertain environments. In Digital Avionics Systems Conference Proceedings, 2002. 28. Rubio Torroella JC. Long Range Evolution-based Path Planning for UAVs through Realistic Weather Environments. PhD thesis, Aeronautics and Astronautics, University of Washington, 2004. 29. Nikolos IK, Tsourveloudis NC and Valavanis KP. Evolutionary algorithm based 3-D path planner for UAV navigation. In Proceedings of the 9th Mediterranean Conference on Control and Automation, 2001. 30. Nikolos IK, Valavanis KP, Tsourveloudis NC and Kostaras AN. Evolutionary algorithm based offline/online path planner for UAV navigation. IEEE Transactions on Systems, Man and Cybernetics - Part B: Cybernetics 2003; 33: 898–912. 31. Pehlivanoglu YV. A new vibrational genetic algorithm enhanced with a Voronoi diagram for path planning of autonomous UAV. Aerospace Science and Technology 2012; 16: 47–55. 32. Hasircioglu I, Topcuoglu HR and Ermis M. 3-D path planning for the navigation of unmanned aerial vehicles by using evolutionary algorithms. In Proceedings of the 10th Annual Conference on Genetic and Evolutionary Computation, 2008. 33. Shima T and Schumacher C. Assigning cooperating UAVs to simultaneous tasks on consecutive targets using genetic algorithms. Journal of the Operational Research Society 2009; 60: 973–982. 34. Burchardt H and Salomon R. Implementation of path planning using genetic algorithms on mobile robots. In Congress on Evolutionary Computation, 2006. 35. Rathbun D and Capozzi B. Evolutionary approaches to path planning through uncertain environments. In Proceedings of the AIAA Unmanned Unlimited Conference, 2002. 36. jme graphics. jMonkey Engine. http://www.jmonkeyengine. com. 37. Shankel J. Fractal Terrain Generation - Midpoint Displacement, Game Programming Gems. Charles River Media, 2000. 38. Grumet M. Terrain Modeling. Technical Report, Institute of Computer Graphics and Algorithms Vienna University of Technology, 2004. 39. Terrain generation tutorial: Hill algorithm. http://www.robotfrog.com/3d/hills/hill.html. 40. Topcuoglu H, Ermis M, Bekmezci I and Sifyan M. A new three-dimensional wireless multimedia sensor network
919
41.
42.
43.
44.
simulation environment for connected coverage problems. Simulation: Transactions of The Society for Modeling and Simulation International 2012; 88: 110–122. Topcuoglu HR, Ermis M and Sifyan M. Positioning and utilizing sensors on a 3-D terrain part II-solving with a hybrid evolutionary algorithm. IEEE Transactions on Systems, Man, and Cybernetics, Part C - Applications and Reviews 2011; 41: 470–480. Soubeiga E. Development and Application of Hyperheuristics to Personnel Scheduling. PhD thesis, School of Computer Science and Information Technology The University of Nottingham, 2003. Burke EK, Hyde M, Kendall G, Ochoa G, Ozcan E and Woodward JR. Exploring hyper-heuristic methodologies with genetic programming. In Mumford C and Jain L (eds.), Computational Intelligence: Collaboration, Fusion and Emergence. Intelligent Systems Reference Library, 2009, pp.177–201. Montgomery DC. Design and Analysis of Experiments. New York: John Wiley and Sons, 2009.
Author biographies Isil Oz received B.Sc. and M.Sc. degrees in computer engineering from Marmara University, Istanbul in 2004 and 2008, respectively. She is a research assistant in the same department and she is currently working toward her Ph.D. degree in computer engineering at Bogazici University, Istanbul, Turkey. Her research interests include computer architectures, chip multiprocessing, and software-based hardware reliability. Haluk Rahmi Topcuoglu is currently a professor in the computer engineering department at Marmara University, Turkey. He received B.S. and M.S. degrees in computer engineering from Bogazici University, Istanbul, Turkey in 1991 and 1993, respectively. He received his Ph.D. degree in computer science from Syracuse University, Syracuse, NY in 1999. His research interests mainly include task scheduling and mapping for multicore architectures, multithreading, parallel programming, HHs and evolutionary algorithm-based techniques for solving dynamic optimization problems. He is a member of the IEEE, the IEEE Computer Society, and the ACM. Murat Ermis received his B.S. and M.S. degrees in industrial engineering from Bogazici University and Middle East Technical University, respectively. He received his Ph.D. degree in industrial engineering from Istanbul Technical University, Turkey in 2005. He is an assistant professor in the department of industrial engineering at the Turkish Air Force Academy. His research interests are in the areas of optimization, meta-heuristics, multi-criteria decision making, and location analysis.
Appendix In this appendix, we present the pseudo-code of crossover and mutation operators used in our GA-based method (Algorithms 1– 3). The mutation operators are also considered within our HH approach (see Section 5.2).
920
Simulation: Transactions of the Society for Modeling and Simulation International 89(8)
Algorithm 1 Knowledge-based Crossover Operator select crossover points for parent1 and parent2 cp1 ⇐ crossover point of parent1 cp2 ⇐ crossover point of parent2 d ⇐ destination point D1 ⇐ Distance(cp1 . d) D2 ⇐ Distance(cp2 . d) while D1 > D2 do cp1 ⇐ cp1 + 1 end while while D2 > D1 do cp2 ⇐ cp2 + 1 end while apply crossover to the parents Algorithm 2 Knowledge-based Update Mutation Operator cpk ⇐ control point with the lowest fitness cpnew ⇐ new control point initialize new control point cp ⇐ randomly selected parameter cpnew .x ⇐ cpk−1 x + (cpk+1 .x − cpk−1 .x) ∗ k + cpnew .z ⇐ cpk−1 z + (cpk+1 .z − cpk−1 .z) ∗ k + cpnew .y ⇐ randomly selected feasible coordinate update the control point cpk with cpnew
Algorithm 3 Knowledge-based Insert Mutation Operator find the worst segment on B-spline curve cupworst ⇐ the worst curve point on the segment cpnew ⇐ new control point initialize new control point cp cpnew .x ⇐ cupworst .x cpnew .z ⇐ cupworst .z cpnew .y ⇐ randomly selected feasible coordinate insert the control point cpnew to the curve