Abstract

This paper proposes a physics-inspired method for unmanned aerial vehicle (UAV) trajectory planning in three dimensions using partial differential equations (PDEs) for application in dynamic hostile environments. The proposed method exploits the dynamical property of fluid flowing through a porous medium. This method evaluates risk to generate porosity values throughout the computational domain. The trajectory that encounters the highest porosity values determines the trajectory from the point of origin to the goal position. The best trajectory is found using the reaction of the fluid in porous media by the way of streamlines obtained by numerically solving the PDEs representing the fluid flow. Constraints due to UAV dynamics, obstacles, and predefined way points are applied to the problem after solving for the best trajectory to find the optimal and feasible trajectory. This method shows near-optimality and much reduced computational effort when compared to the other typical numerical optimization methods.

1 Introduction

Unmanned air vehicles (UAVs) have been used in military operations for a number of years. Recently, UAVs have generated increased interest in civilian domains due to their lower cost and potential applications such as emergency management, law enforcement, precision agriculture, package delivery, and imaging/surveillance. The most fundamental problem for any of these applications is trajectory planning or solving for the shortest path between two points. Trajectory planning is an imperative task required for the navigation and control of UAVs, where the objective is to obtain an optimal or near-optimal flight trajectory between an initial position and the desired goal location under dynamic conditions with environmental constraints [1,2]. There are several important characteristics of an ideal trajectory planner that includes optimality and completeness. Additionally, the trajectory planners need to be computationally efficient since trajectory planning has to occur quickly due to fast vehicle dynamics for many applications using on-board computer resources [3]. The trajectory planning in a large mission area is a typical large-scale optimization problem and several methods have been proposed for solving this problem in the literature. In 1959, Dijkstra introduced his famous method for finding the shortest trajectory using a weighted directed graph [4]. Since then many other analytical solutions to the trajectory planning problem have been proposed using methods such as A*, Dynamic Programming, Gradient Algorithms, and Newton Algorithms.

Although these algorithms promise to find the most optimal solution, they are impossible to be implemented in many real world applications due to the amount of computer memory and computational time required [5]. To address these issues, many heuristic methods for trajectory planning have been proposed such as artificial potential field (APF), Genetic Algorithm (GA) [6], fuzzy logic [7,8], Ant Colony Algorithm, Particle Swarm Optimization [9], and Gray Wolf Optimization [10]. Many of these methods implement random sampling of the many trajectory solutions in the search space and through an iterative manner improve the search process. The fundamental issue with these methods is that they cannot guarantee the optimal solution. These methods are advantageous because they require less time and computational effort to solve trajectory planning problems [5]. Real-world applications require very fast algorithms that can handle the complexity of the large-scale problem [11]. Furthermore, the real world complexities induced due to topographical features of the terrain, size of area, and time constraints make the problem even more challenging. The topographical map shown in Fig. 1 represents the typical geographical domain, size, and scale used in this optimization problem.

Fig. 1
Typical topographical map considered in this paper
Fig. 1
Typical topographical map considered in this paper
Close modal

Partial differential equations (PDEs) are typically used to model system properties related to fluid mechanics and thermodynamics. They have also been proven useful in areas of modeling of mechanical and biological systems [12]. Several studies regarding the application of PDE equations and PDE modeling for control purposes have appeared in the recent literature. For example, Barooha et al. has studied vehicular platooning by applying decentralized bidirectional control [13]. In this study, each vehicle is modeled as a double integrator and then a PDE approximation is derived for the discrete platoon dynamics. Then, the derived PDE model is used to explain the stability of the closed-loop system while adding more vehicles in platoon. Similarly, Frihauf and Krstic [14] introduced a stable deployment method of agents using a PDE-based approach. In their method, the agents' dynamics are modeled by reaction-advection-diffusion class of PDEs. By introducing a feedback law, the agents are allowed to deploy into a family of geometric curves and the stability of the method is then guaranteed by enabling a leader approach. In Ref. [15], Sarlette and Sepulcher proposed a descritized system of agents with local interactions modeled using PDEs. In their study, they found that for coordination of subsystems through local interactions, by assuming the symmetry in translation of subsystems value, distributed control systems can benefit from the discrete approximation of one-dimensional PDEs. Pimenta et al. [16] designed feedback control laws for swarm of robots based on models from fluid dynamics. By applying the in-compressible fluid model, a solution for pattern generation task is generated. In their study, using smoothed-particle hydrodynamics technique and Kernell equations, they aimed to devise a decentralized controller. Similarly, flocking of autonomous agents using a PDE based on Cucker–Smale model is proposed in Ref. [17]. Furthermore, based on the analysis of particle flow, which is a result of PDE Cucker–Smale technique, the stability of the technique is proven. In other study [18], stochastic mapping and coverage strategy using robotic ensembles by PDE-based optimization is studied. In their study, by using an advection–diffusion–reaction PDE model, they task the agents to gather the data and identify the region of interest. Mapping task is then solved as a convex optimization problem using a spatially dependent coefficient in the PDE model. Furthermore for the coverage problem, their study suggests an optimal control problem formulation in which the generated PDE model is expressed as a bilinear control system with the agents' states as the control inputs. In another study, an advection–diffusion equation, which is originally based on Kolmogorov forward PDE equations, is studied for spatio-temporal evaluation of the swarm of agents [19]. Another application of PDE equations in multi-agent systems is introduced by Galstyan et al. [20]. In their paper, they have addressed swarm of chemotactic microscopic robotics based on the diffusion model, introduced by PDE equations and showed the result of their study in one-dimension solution. In Ref. [21], Prorok et al., represented the agents' spatial dynamics over time by PDE based Fokker–Planck diffusion model in a swarm of robots. Another study of swarm, using the same PDE based Fokker–Planck technique, inspired from the honeybee behavior in nature, is addressed in Ref. [22].

Analysis of PDEs, particularly ones representing fluid motion, has been used in the literature for finding optimal vehicle trajectories. For example, stream functions representing motion of fluid particles have been used to produce potential functions for navigation purposes [23,24]. In these studies, after formulating an APF for trajectory planning problem, for a single robot, a simple noncompressible flow equation is implemented to find the global minimum of the APF function. Implementation of a similar concept for path planning of a single UAV in three-dimensional (3D) is provided in Ref. [25].

This paper focuses on the UAV trajectory planning problem in complex environments and discusses the tradeoff between the optimality of path and time of computation. In this paper, a novel 3D trajectory planning method has been proposed which has been inspired by the use of PDEs in fluid mechanics, thermodynamics, circuits, and heat transfer. Particularly, the primary contribution of this paper is formulating and solving the trajectory planning problem in the framework of PDEs that are used to model the fluid flow in porous medium. Partial resistance of fluid flow is among the primary characteristics of the porous media considered in this paper. The fluid particle finds the trajectory from a source to a sink point based on the potential gradient while accounting for the highest permeability zones that provide the least resistance. The nonporous part in the fluid medium is considered to be analogous to threats in UAV environment where UAVs cannot pass through. A risk function is used in this method to model the threats that includes fixed obstacles, detected threats, exclusion zones, fuel limits, required way points, UAV dynamics, and time constraints. The prediction of other aircraft in the airspace is based on their translational movement assumption. The predicted points of collision with the UAV have been weighted appropriately in the risk function. A number of flight simulations were used to generate the results which indicate the robustness of the proposed solution in large and complex domains.

1.1 Paper Outline

This paper integrates the finite element method for solving PDEs fluid flows in porous medium to motion control policy for multi-UAV system. Hence, for clarifying the structure of this paper, we add the following key to explain the organization and contribution of each of the sections:

  • In Sec. 2, the clear formulation for the problem is provided. The constraints and the cost function of the problem are further explained in details.

  • Section 3 provides the scheme of PDE solver and the fluid analogy which further assists to understand the proposed approach. General approach in this section is further simplified and a postprocessing section is dedicated to explain how the problem constraints would be enforced on the proposed solution. Since this section provides the solution in a numerical fashion, a theorem is then proved to support the convergence of the solver.

  • This paper models the threats and risks encountered by the UAVs as nonporous part of the porous medium. Section 4 is dedicated to present the model of finding the porosity of the environment.

  • Section 5 provides an algorithm for further smoothing the trajectory generated by the solver. This section is aimed to manipulate the trajectories to make the resulting paths followable by the UAVs.

  • Section 6 provides the flight scenarios used to demonstrate the effectiveness of the proposed algorithm.

2 Problem Statement

This paper considers a problem in which a UAV originates from point (x0,y0,z0) at time t0 and needs to travel to the goal point (xf,yf,zf). The objective is to reach to the goal position with minimal risk while navigating through a dynamic, uncertain, and risky environment.

2.1 Cost Function.

The trajectory with minimal accumulated risk is determined through optimization of a cost function that integrates the risk function throughout the trajectory. It may be noted that multiple solution trajectories may exist due to the nature of PDE solutions. For a trajectory R in 3D domain C, the total accumulated risk value, FR, can be found via Eq. (1) where represents the risk function
(1)
The optimized trajectory, R*, is found through solving the optimization problem formulated as
(2)

The two simple UAV constraints considered in this function are maximum trajectory length and largest achievable trajectory curvature (ψ). The term t is assigned to show that the trajectory R is continuously differentiable function to the degree t. Other constraints can be added to Eq. (2) to further formulate the optimization problem. The risk R(x,y,z) is evaluated using a discrete representation of the risk function for C.

3 Approach Based on Partial Differential Equations and Fluid Flow Model

Based on the fluid analogy, the fluid tends to flow from a higher potential to a lower potential in a field. For instance, consider a water tap. By opening the valve, the water runs from a higher potential (i.e., tap) to a lower potential (i.e., sink), in an optimized manner. Figure 2 represents a schematic of stream lines.

Fig. 2
Schematic diagram showing the flow, stream lines, and boundary condition of computational domain
Fig. 2
Schematic diagram showing the flow, stream lines, and boundary condition of computational domain
Close modal

To make the problem more clear, we will introduce the following key for the rest of the paper.

  • The UAV is considered as a fluid particle in a flow. The equations of fluid flow govern the motion of the UAV from the initial point to the final point in an optimal fashion [26]. The equations governing the fluid motions and the solution method are provided in this section.

  • Each stream line represents a potential path for the UAV. The postprocessing, as explained in Sec. 5 [26], is carried out to ensure the path can be followed by the UAV under its kino-dynamic constraints.

  • Potential functions f, originated from the fluid analogy, is designed to represent the higher potentials at the starting point and lower potential at the goal locations.

The continuity equation of fluid mechanics is used as the basis function f for generating all of the possible trajectory solutions in the porous domain C. This is represented in Eq. (3) where ϕ is the porosity of the evaluated three-dimensional point, ρ is the density of the fluid, and u is the velocity of the fluid
(3)
Darcy's law is applied to Eq. (4) to describe the flow of the fluid through the porous domain. The steady-state solution of Eq. (3) is applied to obtain
(4)
In Eq. (4), κ represents the permeability of the medium C. The second-order centered difference method is applied for each spatial point that interpolates the value using only the values of the cell before and after the current evaluated cell to approximate each cells porosity. To do that, Eq. (4) is discretized in x, y, and z directions using finite difference method [27]. The substitution in four results in Eq. (5). The indices in Eq. (5) represent the grid-points. The variables hx, hy, and hz are the step sizes in terms of x, y, and z directions, respectively. They are specifically defined differently because the x, y, and z grid intervals are not equidistant. O(he2) is the error of estimation and can be neglected [28]
(5)

The variables (i, j, k) in Eq. (5) represent the cell labels of the tessellated area. Equation (5) is solved for the entire domain C while accounting for the boundary conditions.

3.1 Postprocessing of Partial Differential Equation.

The results of Eq. (5) are multiple streamlines with varying fluid velocity u at every grid point. Since there is only one starting point and one final point in the domain, the number of solutions are reduced by applying the flux boundary conditional constraints which require that solutions start at t0 at (x0,y0,z0) and finish at tf at (xf,yf,zf). The process is explained below.

In the domain C, multiple streamlines or flow trajectories from the origin to the goal position are generated. Incompressible flow dynamics represented by Eq. (5) dictates that the streamlines follow the velocity fields and finish at the goal position. The streamlines are evaluated with the optimization criteria indicated in Eq. (2) and are converted to arrays of (x, y, z) points using the Runge–Kutta method. Explicit one-step time-stepping schemes of Eq. (2) can be expressed as
(6)
where S(Z) can be written as
(7)
It is noted that m is the number of functional evaluations and is also called the number of Runge–Kutta stages. In this paper, we are using the second-order accurate scheme (i.e., Eq. (8)), developed by Jameson et al. [29,30]
(8)

Equation (6) returns all the routes that travel from the initial point to the goal position and have acceptable risk values.

3.2 Minimal Risk Constraint.

The cost function, represented in Eq. (1), is evaluated in the discrete domain during the computation of every trajectory R. Equation (9) produces the accumulated risk for trajectory R
(9)

Variable v represents the cells in trajectory R. The Runge–Kutta method process restricts trajectory length and eliminates undesirable trajectories.

3.3 Constraints on Trajectory Length.

Undesirable trajectories are eliminated by using constraint shown in Eq. (10). This constraint eliminates several trajectories resulting from the trajectory generation process
(10)

3.4 Boundary Conditions of Partial Differential Equation.

Shown in Eq. (11), zero flux boundaries, also known as homogeneous Neumann boundary conditions, are used in problems with domains of extensive size
(11)

The variable n is the unit vector along x, y, or z direction. These conditions force the generated streamlines to become parallel to the boundaries of domain C when they become sufficiently close to them. This eliminates the chances of trajectories going out of the domain.

After adding the boundary conditions to Eq. (12), the PDE now becomes
(12)
The homogeneous Neumann conditions implemented on the complete boundary of the domain causes fluctuating streamlines near the boundary as possible solutions for linear system of equations. Dirichlet boundary conditions shown by Eq. (13) can solve this issue
(13)

In Eq. (13), f1(x,y,z) is a function of absolute values on the boundary of the domain C. However, as a result of using Dirichlet conditions on the boundary, the flux conditions are not satisfied. Therefore, the streamlines are allowed to enter and exit from the domain, causing errors in numerical solution over the domain C.

3.5 Computational Domain C and Error Evaluation.

The computational domain is a uniform tessellated area in xy plane and is of varying size in the z direction. Another possible method for discretizing the domain is based on finite element methods for obtaining the solution in an unstructured grid. These methods, however, may generate many erroneous results and are computationally expensive [31].

Theorem 3.1. If the topographical function, defining the surface on which the fluid flows, is considered as piecewise flat in domainC, the error associated with the numerical solution is negligible.

Proof. The optimal trajectory is computed on a regular x, y grid where elevation is added as the z component. As a requirement of a numerical solution, the error needs to be quantified and proved to be the negligible. In order to prove this theorem, we assume that there is no pressure gradient in y direction. It may be noted that this assumption does not lose generality because the proof for y direction can be obtained in the same way as for the x direction as shown below.

The Poisson equation can be derived from Eq. (12) to reduce the effect of quantified error by assuming constant permeability (e.g., κ = 1) on domain C and is considered in the following formulation:
(14)

The error is evaluated without losing the problem's generality by solving the equation in a two-dimensional domain.

Equation (14) is transformed by using Green's relation for the Laplacian and an arbitrary test function b can be written in the following equation [12]:
(15)
Equation (15) is formed to Sobolev space of Sob01(C)
(16)
This problem formulation is transferred into a reference domain Ĉ as u(x,z)û(ζ,η) where (ζ,η) represents a point in Ĉ. Gradient of the flow in the reference domain can be calculated as the following equation:
(17)
where
(18)
The variables are transformed to the reference domain using a Jacobian transformation matrix. We define matrix G as the following equation:
(19)
By using matrix G, Eq. (16) is combined with 19 and rewritten as
(20)
The variable is defined as in the equation given below:
(21)
Equation (22) represents the mapping function used for transforming the data to the reference domain
(22)
In Eq. (22), gC1(C) is the topographical profile and is assumed to be continuous. The following equation is a result of implementing the mapping function on Eq. (20):
(23)
The topographical function g is an important factor in calculating the integral of Eq. (20). By considering a flat surface, i.e., g =0, 23 can be written as in the equation given below:
(24)
Equation (25) defines the error in the numerical solution
(25)
Equation (25) can be written as below:
(26)
From Eq. (26), the following result can be obtained:
(27)

Equation (26) shows the result of the algorithm and provides the sufficient proof to the theorem. In this case, the method gives us zero error as g0 and g0. From this theorem, it is clear that the result of implementing a nonsmooth topographical map (g1) causes Δ>1, which is undesirable. For nonflat topographical maps, a solution is presented as follows:

  • Tessellation of an area must be done in a way to generate group of cells with flat and smooth surface.

  • For solution, the undesired cells which cause a nonsmooth topographical map must be removed.

  • A combination of unstructured cells near surface and structured cells above surface should be maintained.

It may be noted that each of the above items affects the computational time requirement of the algorithm, positively.▪

4 Risk Evaluation

The risk function, R, is analogous to terms representing permeability in Eq. (4) in an opposite fashion. Since low risk areas are more favorable, the permeability values are higher in those areas. The fluid moves more freely through the cells with higher permeability values. The following equation modifies the permeability as follows:
(28)
The function κ transforms the risk values of function R into the permeability function. In the problem considered in this paper, the function κ is considered as
(29)
The variable α is considered constant and βR+ (i.e., β is a positive real number). Physical values of κ are used to generate the optimal trajectory. If the risk value is very small, it may be neglected from the analysis. Hence, the following equation can be written as:
(30)

LCR+ represents a small constant and is considered in this paper to be small value near 0.

4.1 Fixed Obstacles.

The presence of a fixed obstacle must be represented as an extremely high value in the risk function. In this case, an array O(x,y,z) which represents the obstacles is subjected to change the cell weights as shown in the following equation:
(31)

where UC represents an upper bound of risk value.

4.2 Intruder Aircraft.

In this paper, the intruder aircrafts (IAs), based on their collaborative nature with the UAV, are treated in two different ways associated with two different risk functions. The first category, identified as “cooperative IA,” is considered as the IAs equipped with Automatic Dependent Surveillance Broadcast (ADS-B) and is continuously reporting their flight data to the other air vehicles. The second category, the noncooperative aircraft, do not share their flight data with other aircraft and the UAV is responsible for predicting the movement of them based on the onboard sensory data. Here, we provide our approach separately for the cooperative and noncooperative IAs.

4.2.1 Cooperative Intruder Aircraft.

The overall approach to avoid collision with a cooperative IA is to develop a repulsive force function based on a PDE. In this approach, for an IA with coordinates of γ(t)=(p(t),q(t),w(t))T, we use a Gaussian kind of repulsive force as a time-dependent risk function given by the following equation:
(32)

where ϱ and φ are two positive constants, and Rc(x,y,z,t) is the risk associated with the cell located at (x, y, z) at time t due to presence of cooperative IA.

4.2.2 High Risk Areas.

This section focuses on the regions which provide risk to the flights of UAV. The examples could include high population area or regions closely monitored by radars in adversarial environment. These areas can be identified by the expert user. Once identified, higher risk values needs to be assigned for the cells within this area. In this paper, the value of the risk associated with the cells in these areas, has been set to uC and can be obtained by the following equation:
(33)

where the RH(x,y,z) is the risk function associated with the cell located at (x, y, z) due to the high risk area locations.

4.2.3 Noncooperative Intruder Aircrafts.

This section considers the IAs which are identified by the sensors onboard the UAV. These IAs do not report the flight data to the UAV. For every IA, the movement prediction is carried out using a Kalman filter where the position, velocity, and acceleration of the IAs are estimated using the sensory data [32].

After the IA movement prediction, higher risk values need to be assigned for the cells where the specific IA might occupy in the next time steps. The value UC is assigned for these cells and shown in the following equation:
(34)

and RNC(x,y,z) is the risk function associated with the cell located at (x, y, z) due to the presence of noncooperative IA. It is important to notice that uC is quantified less than UC.

Overall risk function is evaluated by the following equation:
(35)

4.2.4 Way-Point Navigation.

The UAV has predefined way-points to visit during its mission before reaching the goal position. The priority of the way-points is defined a priori. The way-points are handled via successively setting each way-point as the goal location, and the analysis is repeated iteratively for each consecutive way point.

The nature of the problem and the boundary conditions determine some properties of the linear set of equations. The aim is to define appropriate Dirichlet boundary conditions on C so that an efficient solver can be found by just considering the symmetric and positive definite values in PDE solutions. The method implemented in this paper is multigrid method with v-cycles. We direct the reader to Ref. [33] for further details on the obtaining an efficient solution of PDEs.

5 Postprocessing of the Trajectory

The risk function (R) is adjusted based on the new waypoint parameters. In this paper, the UGV is considered as a vehicle capable of following all possible trajectories but for the UAV, the trajectory needs to have certain criteria to be considered as “achievable trajectory.” Due to the dynamics of each vehicle, the trajectories obtained using the proposed technique may be impossible for the vehicle to follow. The algorithm for smoothening the trajectory is utilized after implementing the vehicle dynamics model. Dubins trajectory Model as represented in Ref. [34] is used to generate a trajectory which is achievable by the UAV/UGV. The postprocessing of the trajectory is desirable but it does not guarantee the trajectory will visit every predefined waypoint. Algorithm 1, described ahead, moves the cells responsible for low radius curvatures in a trajectory which a fixed-wing UAV with limitations on turning radius may not be able to follow effectively, generated in domain C as the solution, to achievable positions.

Table 3

Algorithm 1 Relocating undesirable waypoint and smoothing the trajectory

Step1: Consider the number of way-points generated for UAV to follow;
Step2: Indicate the maximum turning rate of the vehicle due to Dubins trajectory;
Step3: For All the waypoints
If: Turning rate required for the trajectory is lower than the maximum turning rate of the vehicle and number of waypoints is greater than K
Generate splines with the existing waypoints;
Else: Relocate the critical waypoint;
Then Update the located waypoint in the trajectory.
Step4: Go to next waypoint;
Step1: Consider the number of way-points generated for UAV to follow;
Step2: Indicate the maximum turning rate of the vehicle due to Dubins trajectory;
Step3: For All the waypoints
If: Turning rate required for the trajectory is lower than the maximum turning rate of the vehicle and number of waypoints is greater than K
Generate splines with the existing waypoints;
Else: Relocate the critical waypoint;
Then Update the located waypoint in the trajectory.
Step4: Go to next waypoint;

6 Results and Discussion

6.1 First Scenario: Cost of Elevation.

In simulation, a real-world scenario was used to test the proposed method. The topographical area considered is near Salt Lake City, Utah. The cost function considers the elevation risk for the UAV in addition to the risk given by Eq. (35). The risk function has a direct relationship to the altitude of the UAV. It is desirable for scenarios where the UAV to travel at lower altitude to avoid detection by radars. Equation (36) represents the cost function considered for this scenario
(36)

where z(x, y) is the elevation from the surface of ground. However, the altitude is also governed by topographical features (or obstacles on the terrain). The satellite map and processed map (that shows the risk function) of the environment have been shown in Figs. 3(a) and 3(b), respectively. Figure 3(b) shows the risk as the values along the z dimension. Furthermore it is not preferred for the UAV to fly in open areas such as roads and lakes since the chance of detection by radar increases enormously in these areas. Total area of the region in Fig. 3 is 25×108ft2. Size of the cells in this area is considered as 402ft2. For generating the risk process image from the satellite map, sketch-up software was used.

Fig. 3
Map of the scenario: (a) topographical map of the problem and (b) processed model with the elevation risk values
Fig. 3
Map of the scenario: (a) topographical map of the problem and (b) processed model with the elevation risk values
Close modal

In Fig. 4, there are three areas indicated by white color. The two areas on the left-hand side are no-fly-zones over which the UAV is not allowed to fly. The area on the right-hand side is indicated as the area with high probability of UAV colliding with an IA. One way-point is set for the UAV to visit which is indicated by red color in the map. The result of trajectory planning is shown in Fig. 4.

Fig. 4
Solution trajectory obtained using the proposed method. The rectangle represents a way-point for the UAV and the red circles, represent the no fly zones.
Fig. 4
Solution trajectory obtained using the proposed method. The rectangle represents a way-point for the UAV and the red circles, represent the no fly zones.
Close modal

6.2 Optimality and Computation Time.

There are several alternative approaches to solve the presented trajectory planning problem. In this paper, we include a comparative study of our proposed method with respect to: GA, Dynamic Programming, and Dijkstra algorithm. The performance is evaluated by comparing the optimality of the solutions obtained from each method. As it is known, dynamic programming represents the exact solution while the GA is a metaheuristic method that can obtain the solution faster. Table 1 represents the average results obtained from 25 runs of the code. The simulations have been performed on a computer with the following specifications:

Table 1

Overview of solution characteristics for each method

MethodNormalized costTime of solution (TS) ×101(s)
GA1.121058.0251
Dynamic programming12465.0142
Dijkstra1.081945.8561
A*1.1891.9978
PDE (proposed method)1.08921.2517
MethodNormalized costTime of solution (TS) ×101(s)
GA1.121058.0251
Dynamic programming12465.0142
Dijkstra1.081945.8561
A*1.1891.9978
PDE (proposed method)1.08921.2517
  • Operating System: Windows 8 enterprise 64-bit

  • Program Language: matlab R2014a

  • Processor: Intel(R) Core(TM)i7 -2500 CPU @ 3.30 GHz

  • (2 CPUs)

  • Memory: 8.00 GB RAM

In Table 1, the normalized cost is defined as the average of the cost, calculated by each of the algorithm, running for 25 times, divided by the exact (optimal) cost, found by dynamic programming which is 356927.2.

6.3 Second Scenario: Cost of Fuel.

In this section, the cost function has been modified to include cost of fuel. It is assumed that the cost of fuel is related to the acceleration of the UAV. The overall cost is considered as in below:
(37)

where Γ>0 is the penalty weight and 0<ς1 is a constant. 0M is the maximum acceleration of the UAV and a(t)=x¨(t)2+y¨(t)2+z¨(t)2 represents the acceleration of the UAV at time t. Parameter b is the binary variable which would be equal to 1 if a(t)M. Otherwise, it is considered as 0. The cost for acceleration exhibits a behavior shown in Fig. 5. Since dealing with is a problem in PDEs, ς is set to be very small and then the cost of acceleration passing from M would be extremely high.

Fig. 5
The effect of parameter M on cost function
Fig. 5
The effect of parameter M on cost function
Close modal

The result for a two-dimensional formation scenario is shown in Fig. 6. In this scenario, three UAVs and two IAs are flying in an environment full of uncertainties. The map indicating the unidentified regions has been provided. There is a cost which linearly adds toward the cost function upon entering the uncertain environment. This scenario is based on the real-world scenarios in which the UAVs operate in fully identified regions rather than unidentified regions. The UAVs start from a triangular formation in positions of (50,75),(50,25), and (0,75) and constrain to remain in the triangular formation.

Fig. 6
Result of 2D scenario provided in Sec. 6.3. Yellow circles represent the unidentified areas. The dotted red triangle is showing the position of the IA at ten time steps after starting the mission while the position of the UAV formation is shown in the dotted blue triangle at the same time-step. Fixed obstacles are shown as red rectangles in the area.
Fig. 6
Result of 2D scenario provided in Sec. 6.3. Yellow circles represent the unidentified areas. The dotted red triangle is showing the position of the IA at ten time steps after starting the mission while the position of the UAV formation is shown in the dotted blue triangle at the same time-step. Fixed obstacles are shown as red rectangles in the area.
Close modal

The results obtained from the proposed PDE-based method have been verified using the MILP method [32,35] that provides the exact solutions. The results indicate less than 1% error in two-dimensional (2D) analysis.

6.3.1 Large-Scale Scenarios in Two-Dimensional.

In order to carry out extensive evaluation and to demonstrate the effectiveness, the proposed technique was applied to several cases in 2D with scenarios of increasing complexity. The results obtained from this study have been provided in Table 2. Here, case IDs represent the scenario descriptions where the first three characters represent the number of obstacles, and the last four characters represent number of UAVs. For instance, “O02U004” means there are two fixed obstacles and four UAVs. Each of the cases was run for 100 instances, and the results shown in the table represent the mean obtained from those runs.

Table 2

TS and cost function for MILP and PDE-based method for different cases

CaseNo. of UAVsTS MILPMCostTS PDEPDE-Cost
O02U00220.41125.140.63127.12
O03U00330.41175.240.67179.97
O05U00330.41210.320.70217.325
O02U00770.49869.010.73879.12
O04U00770.49898.360.74910.86
O04U025250.742987.090.893058.20
O02U050501.676420.121.696484.24
O05U1001004.2113340.754.1913256.78
O05U1501509.1217256.329.0317569.21
CaseNo. of UAVsTS MILPMCostTS PDEPDE-Cost
O02U00220.41125.140.63127.12
O03U00330.41175.240.67179.97
O05U00330.41210.320.70217.325
O02U00770.49869.010.73879.12
O04U00770.49898.360.74910.86
O04U025250.742987.090.893058.20
O02U050501.676420.121.696484.24
O05U1001004.2113340.754.1913256.78
O05U1501509.1217256.329.0317569.21

As highlighted in table, PDE method represented a better TS in large number of UAVs.

As the results demonstrate, the proposed PDE-based method fares better in computational time as the scenarios get bigger while the optimality of solution does not degrade as much (over 98% optimality accuracy).

6.3.2 Three-Dimensional Results.

This section presents a comparison in results obtained using two cost functions (Eqs. (36) and (37)) for trajectory planning in 3D. The geographical area of the study is Sevilleta National Wildlife Refuge, Albuquerque, NM. The trajectory has been generated by cost functions (36) and (37) have been shown in Fig. 7 by white and black color, respectively. It may be noted that since cost function represented by Eq. (37) represents fuel cost, the trajectory obtained is shorter. While the trajectory obtained by optimizing cost function (36) represents a safer trajectory, it is longer. The result represents the robust performance of the proposed method.

Fig. 7
Result of trajectory planning with two different cost functions. The white path represents the UAV trajectory with fuel consumption cost function and the black path is representing the trajectory of UAV, with cost of elevating from ground.
Fig. 7
Result of trajectory planning with two different cost functions. The white path represents the UAV trajectory with fuel consumption cost function and the black path is representing the trajectory of UAV, with cost of elevating from ground.
Close modal

Overall, the results indicate the benefits of utilizing the proposed PDE-based method. Comparisons provided in this paper suggest that the PDE method is capable of finding the acceptable near-optimal solution for large-scale, realistic environments. Previous research indicated the ability of MILP solutions in finding the optimal trajectories for UAVs [32,36], but as it can be seen in Table 2, as the complexity of the problem become larger, the efficiency of the proposed numerical PDE method becomes more pronounced.

As explained in this paper, the proposed PDE method relies on solving PDE equations in an iterative manner. This results in more computational time requirement for cases involving smaller number of UAVs as compared to the other existing methods, such as MILP, for solving similar problems. As it was presented in Table 2, for complex problems, the proposed PDE method becomes more computationally efficient as compared to the MILP.

7 Conclusion

The paper presents the formulation of UAV trajectory planning within the framework of PDEs and obtains the near-optimal solution via solving the PDE using an efficient numerical method. The presented method utilizes the theory of fluid flow in porous media to solve the problem of UAV trajectory planning in region filled with moving and stationary obstacles. The proposed method has proven desirable as it is numerically solved and shown to provide acceptable solutions that require less computational time. The method is compared to several different methods and is shown to provide computational advantage without much compromise in the optimality of the solution. Specifically, the proposed method is applied to actual flight scenarios in large-scale problems and the results show that the method has better performance than the GA and Dijkstra in terms of optimality and computational time. Furthermore, in comparison with the Dynamic Programming and MILP, the method provides solution in much less computational time at a small sacrifice in optimality.

The problem studied in this paper involves a dynamic environment with moving obstacles and intruder aircraft. As a part of future work, a number of steps can be performed to make the computations faster. These include parallelizing the solver [37] and multikernel learning [38]. Future works also include generating the decentralized law based on the dynamical behavior of fluid particles for the purpose of computational efficiency. This would allow such methods to be used for more complex scenarios. Another future direction of research would be to incorporate a human-in-the-loop study for the scenarios such as area coverage problems.

References

1.
Choi
,
H.-L.
, and
How
,
J. P.
,
2010
, “
Continuous Trajectory Planning of Mobile Sensors for Informative Forecasting
,”
Automatica
,
46
(
8
), pp.
1266
1275
.
2.
Duan
,
H.
, and
Li
,
P.
,
2014
, “
UAV Path Planning
,”
Bio-Inspired Computation in Unmanned Aerial Vehicles
,
Springer
, Berlin, pp.
99
142
.
3.
Yang
,
G.
, and
Kapila
,
V.
,
2002
, “
Optimal Path Planning for Unmanned Air Vehicles With Kinematic and Tactical Constraints
,”
Proceedings of the 41st IEEE Conference on Decision and Control
, Vol.
2
, Las Vegas, NV, Dec. 10–13, pp.
1301
1306
.
4.
Cormen
,
T. H.
,
2009
,
Introduction to Algorithms
,
MIT Press, Cambridge, MA
.
5.
Duan
,
Y.
,
Ji
,
X.
,
Li
,
M.
, and
Li
,
Y.
,
2014
, “
Route Planning Method Design for UAV Under Radar ECM Scenario
,”
IEEE 12th International Conference on Signal Processing (ICSP)
, Hangzhou, China, Oct. 19–23, pp.
108
114
.
6.
Tuncer
,
A.
, and
Yildirim
,
M.
,
2012
, “
Dynamic Path Planning of Mobile Robots With Improved Genetic Algorithm
,”
Comput. Electr. Eng.
,
38
(
6
), pp.
1564
1572
.
7.
Ernest
,
N.
, and
Cohen
,
K.
,
2015
, “
Fuzzy Logic Based Intelligent Agents for Unmanned Combat Aerial Vehicle Control
,”
J. Def. Manage.
,
6
(
139
), pp.
2167
0374
.
8.
Kurnaz
,
S.
,
Cetin
,
O.
, and
Kaynak
,
O.
,
2010
, “
Adaptive Neuro-Fuzzy Inference System Based Autonomous Flight Control of Unmanned Air Vehicles
,”
Expert Syst. Appl.
,
37
(
2
), pp.
1229
1234
.
9.
Masehian
,
E.
, and
Sedighizadeh
,
D.
,
2010
, “
A Multi-Objective PSO-Based Algorithm for Robot Path Planning
,”
IEEE International Conference on Industrial Technology
(
ICIT
), Vina del Mar, Chile, Mar. 14–17, pp.
465
470
.
10.
Radmanesh
,
M.
, and
Kumar
,
M.
,
2016
, “
Grey Wolf Optimization Based Sense and Avoid Algorithm for UAV Path Planning in Uncertain Environment Using a Bayesian Framework
,” International Conference on Unmanned Aircraft Systems (
ICUAS
), Arlington, VA, June 7–10, pp.
68
76
.
11.
Engebretsen
,
S.
,
2014
, “
A PDE Based Approach to Path Finding in Three Dimensions: Solving a Path Finding Problem for an Unmanned Aerial Vehicle
,”
Master thesis
, Institutt for matematiske fag.https://core.ac.uk/download/pdf/52106385.pdf
12.
Quarteroni
,
A.
, and
Quarteroni
,
S.
,
2009
, Numerical Models for Differential Problems, Vol. 2, Milan: Springer, Berlin.
13.
Barooah
,
P.
,
Mehta
,
P. G.
, and
Hespanha
,
J. P.
,
2009
, “
Mistuning-Based Control Design to Improve Closed-Loop Stability Margin of Vehicular Platoons
,”
IEEE Trans. Autom. Control
,
54
(
9
), pp.
2100
2113
.
14.
Frihauf
,
P.
, and
Krstic
,
M.
,
2011
, “
Leader-Enabled Deployment Onto Planar Curves: A PDE-Based Approach
,”
IEEE Trans. Autom. Control
,
56
(
8
), pp.
1791
1806
.
15.
Sarlette
,
A.
, and
Sepulchre
,
R.
,
2009
, “
A PDE Viewpoint on Basic Properties of Coordination Algorithms With Symmetries
,”
Proceedings of the 48th IEEE Conference on Decision and Control, 2009 Held Jointly With the 2009 28th Chinese Control Conference
,
CDC/CCC 2009
, Shanghai, China, Dec. 15–18, pp.
5139
5144
.
16.
Pimenta
,
L. C.
,
Pereira
,
G. A.
,
Michael
,
N.
,
Mesquita
,
R. C.
,
Bosque
,
M. M.
,
Chaimowicz
,
L.
, and
Kumar
,
V.
,
2013
, “
Swarm Coordination Based on Smoothed Particle Hydrodynamics Technique
,”
IEEE Trans. Rob.
,
29
(
2
), pp.
383
399
.
17.
Piccoli
,
B.
,
Rossi
,
F.
, and
Trélat
,
E.
,
2015
, “
Control to Flocking of the Kinetic Cucker–Smale Model
,”
SIAM J. Math. Anal.
,
47
(
6
), pp.
4685
4719
.
18.
Elamvazhuthi
,
K.
,
Kuiper
,
H.
, and
Berman
,
S.
,
2018
, “
PDE-Based Optimization for Stochastic Mapping and Coverage Strategies Using Robotic Ensembles
,”
Automatica
,
95
, pp.
356
367
.
19.
Karthik
,
E.
,
Kuiper
,
H. J.
,
Kawski
,
M.
, and
Berman
,
S.
,
2018
, “
Bilinear Controllability of a Class of Advection-Diffusion-Reaction Systems
,”
IEEE Trans. Autom. Control
,
64
(
6
), pp.
2282
2297
.
20.
Galstyan
,
A.
,
Hogg
,
T.
, and
Lerman
,
K.
,
2005
, “
Modeling and Mathematical Analysis of Swarms of Microscopic Robots
,”
Proceedings 2005 IEEE Swarm Intelligence Symposium (
SIS 2005
), Pasadena, CA, June 8–10, pp.
201
208
.
21.
Prorok
,
A.
,
Correll
,
N.
, and
Martinoli
,
A.
,
2011
, “
Multi-Level Spatial Modeling for Stochastic Distributed Robotic Systems
,”
Int. J. Rob. Res.
,
30
(
5
), pp.
574
589
.
22.
Correll
,
N.
, and
Hamann
,
H.
,
2015
, “
Probabilistic Modeling of Swarming Systems
,”
Springer Handbook of Computational Intelligence
,
Springer
, Berlin, pp.
1423
1432
.
23.
Jeffrey
,
S.
,
Stephen
,
W.
, and
Mark
,
C.
,
2003
, “
Using Stream Functions for Complex Behavior and Path Generation
,”
AIAA
Paper No. 5008.
24.
Waydo
,
S.
, and
Murray
,
R. M.
,
2003
, “
Vehicle Motion Planning Using Stream Functions
,”
IEEE International Conference on Robotics and Automation
, Vol.
2
, Taipei, Taiwan, Sept. 14–19, pp.
2484
2491
.
25.
Wang
,
H.
,
Lyu
,
W.
,
Yao
,
P.
,
Liang
,
X.
, and
Liu
,
C.
,
2015
, “
Three-Dimensional Path Planning for Unmanned Aerial Vehicle Based on Interfered Fluid Dynamical System
,”
Chin. J. Aeronaut.
,
28
(
1
), pp.
229
239
.
26.
Radmanesh
,
M.
,
Guentert
,
P. H.
,
Kumar
,
M.
, and
Cohen
,
K.
,
2017
, “
Analytical PDE Based Trajectory Planning for Unmanned Air Vehicles in Dynamic Hostile Environments
,”
American Control Conference
(
ACC
), Seattle, WA, May 24–26, pp.
4248
4253
.
27.
Mitchell
,
A. R.
, and
Griffiths
,
D. F.
,
1980
, “
The Finite Difference Method in Partial Differential Equations
,”
Number Book
,
Wiley, New York
.
28.
Ferziger
,
J. H.
, and
Peric
,
M.
,
2012
,
Computational Methods for Fluid Dynamics
,
Springer Science & Business Media, Berlin
.
29.
Cabuk
,
H.
,
Sung
,
C.-H.
, and
Modi
,
V.
,
1992
, “
Explicit Runge-Kutta Method for Three-Dimensional Internal Incompressible Flows
,”
AIAA J.
,
30
(
8
), pp.
2024
2031
.
30.
Jameson
,
A.
,
Schmidt
,
W.
, and
Turkel
,
E.
,
1981
, “
Numerical Solution of the Euler Equations by Finite Volume Methods Using Runge Kutta Time Stepping Schemes
,”
14th Fluid and Plasma Dynamics Conference
,
Palo Alto, CA
, June 23–25.
31.
Pinder
,
G. F.
, and
Gray
,
W. G.
,
2013
,
Finite Element Simulation in Surface and Subsurface Hydrology
,
Academic Press, New York
.
32.
Radmanesh
,
M.
, and
Kumar
,
M.
,
2016
, “
Flight Formation of UAVs in Presence of Moving Obstacles Using Fast-Dynamic Mixed Integer Linear Programming
,”
Aerosp. Sci. Technol.
,
50
, pp.
149
160
.
33.
Li
,
J.
, and
Chen
,
Y.-T.
,
2008
,
Computational Partial Differential Equations Using MATLAB
,
Chapman and Hall/CRC, Boca Raton, FL
.
34.
Shanmugavel
,
M.
,
Tsourdos
,
A.
,
White
,
B.
, and
Zbikowski
,
R.
,
2006
, “
3D Dubins Sets Based Coordinated Path Planning for Swarm of UAVs
,”
AIAA
Paper No. 2006-6211.
35.
Radmanesh
,
M.
,
Kumar
,
M.
,
Nemati
,
A.
, and
Sarim
,
M.
,
2015
, “
Dynamic Optimal UAV Trajectory Planning in the National Airspace System Via Mixed Integer Linear Programming
,”
Proc. Inst. Mech. Eng.
, Part G: J. Aerosp. Eng., 230(9), pp. 1668-1682.
36.
Radmanesh
,
M.
,
Kumar
,
M.
,
Guentert
,
P. H.
, and
Sarim
,
M.
,
2018
, “
Overview of Path-Planning and Obstacle Avoidance Algorithms for UAVs: A Comparative Study
,”
Unmanned Syst.
,
6
(
2
), pp.
95
118
.
37.
Ganesan
,
S.
,
John
,
V.
,
Matthies
,
G.
,
Meesala
,
R.
,
Shamim
,
A.
, and
Wilbrandt
,
U.
,
2016
, “
An Object Oriented Parallel Finite Element Scheme for Computations of PDEs: Design and Implementation
,” IEEE 23rd International Conference on High Performance Computing Workshops (
HiPCW
), Hyderabad, India, Dec. 19–22, pp.
106
115
.
38.
Gönen
,
M.
, and
Alpayd
,
E.
,
2011
, “
Multiple Kernel Learning Algorithms
,”
J. Mach. Learn. Res.
,
12
, pp.
2211
2268
.http://www.jmlr.org/papers/volume12/gonen11a/gonen11a.pdf