+ All Categories
Home > Documents > ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to...

ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to...

Date post: 03-Jul-2020
Category:
Upload: others
View: 0 times
Download: 0 times
Share this document with a friend
15
ENCOUNTER AWARE FLIGHT PLANNING IN THE UNMANNED AIRSPACE Maxim Egorov, Vanessa Kuroda, Peter Sachs, Airbus UTM, San Francisco, CA Abstract Ensuring safe and efficient operations for un- manned aircraft is vital to their integration into the civil airspace. This paper proposes a set of encounter- based metrics that can be used to estimate the complexity and thus the capacity of an unmanned airspace. We show that these metrics are able to provide a more detailed view of safety failure charac- teristics in the airspace than traditional metrics. The encounter-based metrics are used to formulate a novel path planning algorithm that combines 4D trajectory optimization with a flight scheduling heuristic in order to reduce the number of difficult to solve encounters in the airspace. The proposed algorithm is distributed in nature and can be applied to an airspace managed by multiple service suppliers that are capable of gen- erating flight plans. Through simulation, we show that this approach is able to outperform other distributed flight planning methods and can perform nearly as well as a centralized approach that jointly optimizes flight plans simultaneously. We also demonstrate that this approach can scale to high operational volumes and is able to efficiently handle spikes in airspace usage. Introduction From delivery drones to autonomous vertical take-off and landing (VTOL) passenger aircraft, ap- plications of unmanned aircraft systems (UASs) have become a key part of the discussion about the fu- ture of our skies [1]. It is estimated that the num- ber of UAS will dramatically increase within the next 20 years [2]–[4], and new approaches will be needed to manage this influx of aircraft outside of traditional air traffic management (ATM) systems. A number of proposals exist for modernizing the traffic management process for UAS under a single framework [5]–[7]. NASA refers to this framework as UAS Traffic Management (UTM) [5], and we adopt their terminology in this paper for consistency. While UTM is a complex system of systems and has many technological challenges that need to be overcome, safe and efficient path planning for flight trajectories is one of the most critical. Path planning has been studied extensively in a number of applications from robotics [8] and au- tonomous cars [9] to drones [10] and commercial aircraft [11]. However, the path-planning work done in the context of UTM has been limited to low vehicle encounter densities [12]–[14] or standalone algorithms [15]. In both cases, it is not clear how well the approaches will scale to an airspace with high density UAS operations in a real world setting. In addition to difficult scalability requirements, path planning in the context of UTM may need to be performed in a distributed setting. In the NASA UTM architecture, unmanned flight operations may be managed by different UAS Service Suppliers (USSs) [5]. This would require a distributed approach to flight planning, and would make it more difficult to achieve a globally optimal airspace utilization. In that architecture, strategic deconfliction is defined by the requirement that a UTM operation should be free of 4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem. We focus on a class of motion-planning algo- rithms known as trajectory optimization [17]. At a high level, trajectory optimization methods attempt to design a trajectory by minimizing a generalized cost function and meeting a set of constraints. A number of trajectory optimization methods have been developed in recent years that are able to compute collision- free trajectories from a naive straight line initializa- tion [18]–[20]. These methods translate well to path planning in UTM, because prior to optimization a flight-request for a UAS can be modeled as a point to point 3D trajectory that may not be collision-free. We approach the flight planning problem by first identifying the limitations of existing methods in airspace with large numbers of operations. We focus on unstructured airspace with free-flight me- chanics where the only means of traffic manage- ment is through flight planning. By first focusing
Transcript
Page 1: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

ENCOUNTER AWARE FLIGHT PLANNING IN THE UNMANNED AIRSPACE

Maxim Egorov, Vanessa Kuroda, Peter Sachs, Airbus UTM, San Francisco, CA

AbstractEnsuring safe and efficient operations for un-

manned aircraft is vital to their integration into thecivil airspace. This paper proposes a set of encounter-based metrics that can be used to estimate thecomplexity and thus the capacity of an unmannedairspace. We show that these metrics are able toprovide a more detailed view of safety failure charac-teristics in the airspace than traditional metrics. Theencounter-based metrics are used to formulate a novelpath planning algorithm that combines 4D trajectoryoptimization with a flight scheduling heuristic in orderto reduce the number of difficult to solve encountersin the airspace. The proposed algorithm is distributedin nature and can be applied to an airspace managedby multiple service suppliers that are capable of gen-erating flight plans. Through simulation, we show thatthis approach is able to outperform other distributedflight planning methods and can perform nearly aswell as a centralized approach that jointly optimizesflight plans simultaneously. We also demonstrate thatthis approach can scale to high operational volumesand is able to efficiently handle spikes in airspaceusage.

IntroductionFrom delivery drones to autonomous vertical

take-off and landing (VTOL) passenger aircraft, ap-plications of unmanned aircraft systems (UASs) havebecome a key part of the discussion about the fu-ture of our skies [1]. It is estimated that the num-ber of UAS will dramatically increase within thenext 20 years [2]–[4], and new approaches will beneeded to manage this influx of aircraft outside oftraditional air traffic management (ATM) systems.A number of proposals exist for modernizing thetraffic management process for UAS under a singleframework [5]–[7]. NASA refers to this framework asUAS Traffic Management (UTM) [5], and we adopttheir terminology in this paper for consistency. WhileUTM is a complex system of systems and has manytechnological challenges that need to be overcome,

safe and efficient path planning for flight trajectoriesis one of the most critical.

Path planning has been studied extensively ina number of applications from robotics [8] and au-tonomous cars [9] to drones [10] and commercialaircraft [11]. However, the path-planning work donein the context of UTM has been limited to lowvehicle encounter densities [12]–[14] or standalonealgorithms [15]. In both cases, it is not clear howwell the approaches will scale to an airspace withhigh density UAS operations in a real world setting.In addition to difficult scalability requirements, pathplanning in the context of UTM may need to beperformed in a distributed setting. In the NASAUTM architecture, unmanned flight operations maybe managed by different UAS Service Suppliers(USSs) [5]. This would require a distributed approachto flight planning, and would make it more difficult toachieve a globally optimal airspace utilization. In thatarchitecture, strategic deconfliction is defined by therequirement that a UTM operation should be free of4-D intersection with any other UTM operation priorto departure operation [16], and in this work we aimto address exactly this problem.

We focus on a class of motion-planning algo-rithms known as trajectory optimization [17]. At ahigh level, trajectory optimization methods attempt todesign a trajectory by minimizing a generalized costfunction and meeting a set of constraints. A number oftrajectory optimization methods have been developedin recent years that are able to compute collision-free trajectories from a naive straight line initializa-tion [18]–[20]. These methods translate well to pathplanning in UTM, because prior to optimization aflight-request for a UAS can be modeled as a pointto point 3D trajectory that may not be collision-free.

We approach the flight planning problem byfirst identifying the limitations of existing methodsin airspace with large numbers of operations. Wefocus on unstructured airspace with free-flight me-chanics where the only means of traffic manage-ment is through flight planning. By first focusing

Page 2: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

Figure 1. Encounter density map (left) and the corresponding encounter distribution (right) for themulti-modal traffic region.

on individual UAS encounters, we are able to con-struct a metric that captures macroscopic complexityproperties of the whole airspace. The formalism pre-sented here identifies precisely how the high densityairspace leads to degrading safety even when state-of-the-art path planning algorithms are in use. Whileconceptually straightforward, we show that the path-planning problem becomes more difficult to solve asthe number of vehicles in individual encounters in-creases throughout the airspace. By generalizing thisnotion into a single metric we are able to incorporateit into different planning algorithms and into UTMarchitectures both with centralized and distributedplanning.

The goal of this paper is develop a robust andefficient flight planning approach that can operate inan airspace with high operational volumes while ad-hering to the constraints of a UTM. The contributionsof this work are as follows:

1) To our knowledge, the first quantitative com-parison of planning approaches in high densityunmanned airspace for distributed and central-ized UTM architectures.

2) A set of encounter-based metrics that providean aggregate estimate of complexity in theunmanned airspace, and an estimated impact ofa single flight on airspace complexity.

3) A novel approach to flight planning that incor-porates these metrics and is able to significantlyoutperform the benchmark methods.

The remainder of the paper is organized as fol-lows. We first introduce airspace encounters metricson which the methodology proposed in this paperis based on, and propose a notion of airspace ca-pacity for unmanned and unstructured flight as wellas provide a definition for a dense airspace in thecontext of UTM. Next, we describe the path-planningproblem for UAS, and outline how a distributed or acentralized path planning architecture could work inUTM. We then describe our algorithmic contributionas a trajectory optimization approach combined withan encounter-aware scheduling heuristic. We providesimulation results that compare our algorithmic ap-proach to existing methods, and provide some avenuesfor future work in the conclusion.

Encounter Distributions and AirspaceImpact Metrics

This section defines two metrics for charac-terizing an airspace, the encounter distribution andthe encounter expectation. The encounter distribu-tion captures macroscopic encounter properties of anairspace, while the encounter expectation quantifiesthe expected encounters for a single flight trajectory.

Page 3: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

Figure 2. The encounter distribution and the corresponding fraction of loss of separation events (left),and the fractional rate of pairwise and multi-threat encounter (right).

A. Encounter Distributions and Airspace Ca-pacity

Before defining the encounter distribution, wefirst formalize the notion of an encounter. The mostgeneral description is defined by a Boolean functionthat takes the states of two vehicles in a sharedairspace as input, and outputs whether the vehiclesare in an encounter or not. Typically, the states in-clude position and velocity of the vehicles, and couldalso include more complex information such as theirexpected trajectories as well. In this work, we use asimplified definition where two vehicles within someconstant distance of each other are considered to be inan encounter. However, the more general definition isnot limited to a constant spherical geometry and canuse more complex geometries that could be dependenton time, as well as vehicle position and velocity.

The encounter distribution specifies the prob-abilities over the types of encounters that exist inan airspace. Specifically, given an encounter in anairspace, it depicts the probabilistic values for thenumber of vehicles in that encounter. An example ofan encounter distribution and a corresponding geo-graphic encounter density map is shown in Figure 1.The map and distribution were generated using resultsfrom a four-hour simulation over a multi-modal trafficregion at 1000 takeoffs per hour. The multi-modalregion is intended to model an urban area withdistributed demand clusters for UAV operations and isdescribed in more detail in the Results Section. Notethat the encounter distribution can be dynamic and

vary with time.

One way to quantify airspace capacity is toestimate the decision making limitations of the systemresponsible for managing that airspace. A number ofmetrics have been identified and analyzed to quantifydynamic density in the context of dynamic airspaceconfiguration for the Next Generation Air Trans-portation System (NextGen) [21], [22]. These metricsattempt to capture the limitation of the cognitive loadon air traffic controllers managing an airspace. It’s notclear how useful these metrics are in the context ofUTM, and we leave that evaluation for future work.Instead, we make a simple conjecture that for a givenencounter in the airspace, the path planning problembecomes more difficult as the number of vehiclesin that encounter increases. In short, an encounterwith more vehicles in it is a complex multi-agentproblem and is less likely to be resolved by a planningalgorithm. These problems are known to be difficultfrom a combinatorial standpoint [23], and it is usuallyimpossible to provide tractability or completenessguarantees unless a restrictive set of constraints ismet [24], [25]. These conditions are observed inour simulations as well. In simulation, we observethat encounters with more than two vehicles in themcontribute disproportionately more loss of separationevents than their pairwise counterparts (see Figure 2).

We use the notion of encounter distributions todefine an operationally dense airspace by observingthat an airspace dominated by encounters with morethan two vehicles will be difficult to manage from

Page 4: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

PrefPA PB

Es = 1.45Es = -0.75

Figure 3. A visualization of the encounter shift from a reference distribution PRe f (middle) to PA (left) andPB (right). Minimizing the encounter shift causes the encounter distribution to move towards encounterswith a lower number of vehicles.

a planning perspective. Formally, we can define adense airspace by determining if the expectation foran encounter with more than two UAS is above somethreshold value λ , E[NUAS > 2] ≥ λ , where NUAS isthe number of UAS in an encounter. A simple choiceis λ = 0.5, where over half of the encounters havemore than two UAS in them. We adopt this value forλ in the remainder of this work. We thus consideran airspace to be operating past its capacity whenE[NUAS > 2]≥ 0.5.

The advantage of using encounter distributionsto describe the complexity of an airspace lies intheir ability to track how different configurations ofthe airspace impact the encounter distribution andthus the complexity of the airspace. Here, we de-fine a single-valued metric based on total variationaldivergence that we call the encounter shift. Thismetric can be though of a signed distance betweenencounter distributions, and can be used to evaluatethe impact that different planning approaches have onthe complexity of the airspace. Given two encounterdistributions PA and PB, the encounter shift is givenby

ES(PA ‖ PB) =12 ∑

x∈Ω

wx(PA(x)−PB(x)), (1)

where Ω is the support of the encounter distributionand wx are importance weights associated with thenumber of vehicles in an encounter. In Equation 1PA is the reference encounter distribution, and PB isthe distribution of which we want to measure the

encounter shift. This expression differs from totalvariational divergence in that it is both a signed and aweighted sum. The fact that the expression is signedallows us to track the direction of the shift, and theweights allow us to place more importance on theencounters with greater number of vehicles in them.Figure 3 shows how the encounter shift is affectedby the shape of the encounter distribution. Whenthe encounter distribution moves towards encounterswith lower numbers of vehicles in them, the shift isnegative. A move the other way creates a positiveshift. In practice, minimizing the encounter shift alsominimizes the complexity of the encounters in theairspace, making it simpler for path-planning algo-rithms to manage.

B. Encounter Driven Airspace Impact Predic-tion

We now consider how the encounter shift canbe used during path planning to decrease the overallcomplexity of the airspace. Consider the contributionof total encounters from a single flight plan to theairspace as a whole. This contribution can be dividedinto two parts:

1) Immediate Impact: the encounters a particularflight creates with existing traffic

2) Future Impact: the encounters a flight willcreate with traffic that will be flying in thefuture

Given a flight plan that leads to NnI immediate en-

counters with n vehicles, it is possible to write the

Page 5: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

total expected encounters with n vehicles from theflight as

Nn = NIn +E[NUAS = n] (2)

Where E[NUAS = n] is the expected number of futureencounters with n vehicles from the flight in question.To compute E[NUAS = n], we use historical traffic datafor the airspace of interest.

The process of computing the expected numberof encounters with n vehicles, E[NUAS = n], canperformed by discretizing historical encounter infor-mation and performing statistical inference on it. Thisprocess allows us to predict the number of encountersthat are not immediately accounted for a given flight,i.e. the encounters that may occur from other vehiclesthat will be flying in the future. Formally, our goal isto compute the full joint probability of all encountersover a given trajectory

P(e11,e

21, . . . ,e

55 | trajectory) =

P(e11 | trajectory)×

P(e21 | trajectory,e1

1) . . .P(e55 | trajectory,e1

1, . . .e45)

(3)

where ein denotes the ith n vehicle encounter on the

trajectory. In the expression we chose to truncate thepermutations for i and n at five, although neither i orn need to be bound.

There are a number of methods to compute thejoint probability, such as Navie Bayes [26] by makingthe assumption that all encounters are independent.However, because our primary objective is to estimatethe encounter distribution for a single flight, we caninstead determine the probability of encounters with nvehicles over a trajectory for n independent values ofinterest. We can then use those probability values toconstruct the encounter distribution. If we continueto make the assumption that all encounters are in-dependent events, we can write the probability of aencounters with n vehicles over the whole trajectoryas a modified geometric distribution that has the form

P(NUAS = n) = pTn

T−1

∏t=1

(1− ptn) (4)

where T denotes the total number of timesteps in thetrajectory of the vehicle, and pt

n is the probability ofan encounter with n vehicles at time-step t. We can

obtain ptn using a normalized historical encounter data

from the airspace discretized into finite sized 3D binsor voxels (see Figure 4. In this work, we use timestepsthat are one second in length. A temporal componentcan be added to the encounter data if the historicaldata is expected to vary with time. While such datamay not be readily available, we assume it exists inthis work, and we obtain it through simulation.

0.0

1e-3

2e-3

3e-3

4e-3

5e-3

6e-3

Encounter P

robability / Second

Figure 4. An example trajectory over a geographicheat-map of encounter distribution density

By combining the expression for total expectedencounters in Equation 2 with the encounter shift,we can compute the encounter shift between theunderlying encounter distribution of the airspace andthe one generated for a single flight plan. This metricprovides a prediction of the impact a single flighthas on the airspace as a whole. While statistically,this approach is prone to effects of variance, weobserve that for an airspace simulation with a non-trivial number of flights, it is possible to use thismetric to drive the airspace either towards or awayfrom complex operations.

Problem FormulationThis section outlines the flight-planning problem

in UTM. We define the general requirements for aflight plan, and describe the mathematical formalismthat goes along side of it. We pose the problem in thecontext of two UTM architectures: one where trafficmanagement capabilities are completely distributedbetween multiple USSs, and one where centralizedflight planning is possible.

Page 6: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

C. Collision-Free Flight PlansIn this work, a flight-plan is defined to be a set of

4D waypoints parameterized by (x,y,z, t) that meetsthe time constraint ti+1 > ti between two waypoints piand pi+1. A flight plan is generated during the pre-flight planning phase of an operation, and we leavethe problem of in-flight re-routing and contingencyplanning for future work. Computing a conflict-freeflight plan before the flight requires accounting forany uncertainties associated with the trajectories ofother UAS in the airspace to ensure no safety viola-tions occur after takeoff. There are a number of otherways to represent a flight plan. A common approachis to use a set of time-bounded 3D polygons aroundthe flight volume, also known as intent [27]. However,this representation is more restrictive and constrainsthe approaches that can be used for flight planning.

Flight planning can be formulated as an opti-mization problem, where we attempt to minimize anobjective function subject to inequality and equalityconstraints:

min f (x) (5a)

subject to gi(x)≤ 0, i = 1,2, . . .nineq (5b)

hi(x) = 0, i = 1,2, . . .neq (5c)

where x is a set of waypoints representing theflight plan, and f , gi, hi are scalar functions. Theobjective may consider the risk associated with atrajectory [28], and numerical terms that encouragea minimal length path. Typically, the optimization isperformed over a T ×K dimensional vector with Tbeing the number of time-steps and K the number ofdegrees of freedom. In this work, we treat time asa degree of freedom, and instead have T flight planwaypoints we optimize over.

D. Centralized and Distributed PlanningThe choice between centralized and distributed

planning typically depends on the effectiveness ofcommunication networks, the available resources, andthe constraints imposed by the system architecture. Inthis work, we make the following distinction betweencentralized and distributed planning:

1) Centralized: a planning approach that canjointly optimize plans simultaneously. This ap-proach requires a single central entity to beresponsible for flight planning.

2) Distributed: a planning approach that is dis-tributed between multiple entities. Existing planinformation can be freely exchanged betweenentities to ensure deconfliction, but it is notpossible to jointly optimize plans.

Joint Planning

Idle/Flight Prep Flight

Request 1

Request 2

Request 3

Request 1

Request 2

Request 3

Distributed Planning

Centralized

Distributed

time

Figure 5. Distributed (top) and centralized (bot-tom) planning architectures. A flight plan is opti-mized jointly in the centralized architecture, andindividually in the distriubted architecture.

Note that the primary distinction between cen-tralized and distributed planning is the ability of thecentralized planner to optimize plans simultaneously.In the context of trajectory optimization, this impliesan optimization over a shared objective. While a lot ofwork has been done on solving optimization problemswith a shared objective in a distributed setting [29],[30], the assumptions made in these settings, such asa requirement that the cost function be convex, areusually too restrictive for path-planning algorithmslike trajectory optimization methods. Recent work hasalso shown that coordination between multiple asyn-chronous planners is feasible [31], but it is not clearhow well the approach can scale to relatively short,high-frequency operations like the ones envisioned inUTM. We assume that such methods are too restric-tive at this time, and that joint optimization of a singleplanning objective with a shared set of constraintsbetween distributed planners is not feasible. We thusleave any distributed architectures with capabilitiesfor joint multi-plan optimization as future work.

For a UTM, the ability to perform centralizedplanning depends on the architecture of the system.

Page 7: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

For example, centralized planning is not possible inthe NASA UTM architecture unless a single USS isdesignated as the sole planner for the airspace ina given region. Folding the planning function intoa single Air Navigation Service Provider (ANSP)would also enable centralized planning. The intentof the NASA UTM architecture is to be distributedin nature, and that leads to a number of trade-offs from a planning perspective. At a high level,the advantage of a distributed architecture is thatit enables multiple entities to independently managetheir UAS operations, while adhering to coordinationwhen needed to ensure safety. However, this leadsto sub-optimal airspace utilization in regions wheremultiple USSs are operating simultaneously, and canlead to cascading effects that cause severe airspacecongestion in highly used regions [32]. This problemis particularly evident in free-flight operations wheremultiple USSs may need to plan around each otherwithout any structural constraints in the airspace toorganize operations. While negotiation schemes havebeen discussed in the context of the distributed UTMarchitecture [16], the implementation and the impactof the negotiation on sub-optimal use of airspace isnot clear.

In the centralized architecture, all flight plans aregenerated by a single planner which allows them tobe globally optimal. However, the disadvantage of thecentralized approach is that it may not be scalableto high operational frequencies and would requireoperators to share their mission data with a centralentity. It may also be less adaptable to emerginguse cases and technologies, making it less desirablefrom an operators’ stand point. The planning cyclesfor each architecture are shown in Figure 5. In thedistributed architecture, plans are computed one at atime if they are owned by different USSs. While com-pleted plans can be shared between USSs, there is noinformation sharing during the planning process itself.In the centralized architecture, all plans are jointlyoptimized, because a single entity is responsible forcollecting flight requests and computing associatedplans. The advantage of the centralized architectureis that it can jointly optimize flight plans as requestscome in, for all flights that have not yet started, andit does not require additional negotiation schemes orprotocols.

Flight PlanningIn this section, we first outline the flight planning

algorithm used in this work. We then describe themethodology for incorporating encounter distributionsinto the flight-planning process. We conclude thesection with an overview of how this algorithm fitsinto the overall UTM architecture, and explain howthe distinction between centralized and distributedUTM architectures impacts flight-planning.

E. 4D Trajectory Optimization for Highly Uti-lized Airspace

We use gradient-based trajectory optimizationto compute flight trajectories in this work. One ofthe biggest challenges in creating collision-free flightplans is that the environment in consideration hasboth static and dynamic obstacles in it. The staticobstacles are used to model constructs like temporaryflight restrictions (TFRs) that remain unchanged forthe duration of a single flight. Dynamic obstaclesinclude other UAS, and large airspace constructsthat are in motion such as weather events, and aremore difficult to incorporate into the planning pro-cess. While the problem of motion planning withdynamic obstacles has been studied extensively, mostapproaches focus on online re-planning in static en-vironments [33], velocity obstacles [34], or discretegrid-based search [35]. While these approaches canbe applied to flight planning, they are either difficultto scale to continuous state spaces or are most suitablefor problems where online re-planning is appropriate.

To naturally handle dynamic obstacles this worktreats time as an optimization variable during plan-ning. However, we introduce a heuristic that is ableto efficiently approximate the safe time intervals be-tween each waypoint in dynamic environments duringoptimization. In this way, our approach is similar tosafe interval path planning [36], but is capable ofscaling to continuous state spaces while remainingcomputationally efficient. The heuristic uses a dis-tance measure to add or remove 4D waypoints fromthe flight trajectory as the plan is being generated.The bounds of the measure are based on geometricdistance and are set prior to the optimization process.If a segment between two waypoints is not collisionfree and falls outside of the bounds, the segmentis either expanded or contracted. A segment that isgeometrically longer than the upper bound, is split

Page 8: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

0.0

Enco

unte

r Sh

ift

Start Time (seconds)0.0 10.0 20.0 30.0 40.0 50.0 60.0 70.0 80.0 90.0

Figure 6. An example of encounter aware scheduling for a single flight-plan. The horizontal axis representsthe potential start-time for a flight, while the vertical axis represents the encounter shift from that flightat the given start time

evenly in half by introducing a new waypoint, whilea segment that is shorter is merged with neighboringsegments by removing a waypoint. The heuristic isimportant for two primary reasons:

1) It enforces a bound on the number of waypointsin the trajectory

2) By expanding and contracting the segmentsbetween waypoints, they can converge to thelength of the smallest collision free interval

Because this heuristic is used at each iteration of theoptimization process, the optimization is not guaran-teed to converge to a local minima. The heuristicmodifies the parameter space of the objective if iteither adds or removes a waypoint. To handle thisproblem, we split the optimization into two parts,with the first allowing the addition and removal ofwaypoints, and the second freezing the number ofwaypoints in the trajectory in place and proceedingwith standard gradient optimization. We found thisapproach to work particularly well, because the firsthalf of the optimization process allows the trajectoryto converge to a reasonable number of waypointsgiven the obstacles in the configuration, while thesecond fine-tunes that representation of the trajectorywith respect to the constraints and the objective. Weleave convergence proofs of this approach for futurework.

In our approach, we apply the penalty method asa way to enforce constraints [37]. The penalty methodtransforms a constrained optimization problem into an

unconstrained problem by including the constraints inthe objective. Using the l1 exact penalty method thetransformed objective takes on the following form:

f (x) = f (x)+µ

nineq

∑i=1|gi(x)|++µ

neq

∑i=1|hi(x)| (6)

where |gi(x)|+= max(0,gi(x)) is the penalty satisfy-ing the inequality constraint, and |hi(x)| is the penaltysatisfying the equality constraint. By formulating theconstraints in this way, and picking a sufficiently largepenalty coefficient µ , the optimization eventuallydrives all of the constraint violations to zero. Theiterative approach is outlined in Algorithm 1.

Input:Tterm: terminating conditionsiwaypt : iteration to freeze number waypointsα: initial step-sizef : optimization objectivex0: initial trajectory from a flight requestwhile not Tterm do

if i < iwaypt thenif not collisionFree(xi) then

xi = expandWaypoints(xi)xi = contractWaypoints(xi)

endendxi+1← xi−αi∇ f (xi)

endAlgorithm 1: Gradient based trajectory optimiza-tion with waypoint expansion

Page 9: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

We pick iwaypt such that it is equal to roughly halfof the iterations that will be performed during theoptimization.

As stated previously, by formulating the objec-tive in this way and allowing waypoint expansion,we are able to optimize the trajectory directly inthe 4D space while considering dynamic obstaclessuch as UAS and weather events. We are also ableto compute the gradients directly by keeping boththe constraints and the original objective as smoothlydifferentiable functions. This allows our planningalgorithm to scale well to complex environments withmany other co-existing UAS. In this work, we use areal-time constraint and an iteration constraint i= 500as the termination conditions, with iwaypt = 250. Thestep size α is incrementally reduced at each iterationafter iwaypt has been exceeded.

F. Encounter-Aware Flight PlanningIn the previous section, we introduced a trajec-

tory optimization approach that can efficiently per-form deconfliction and scale to airspace with a largenumber of UAS. However, the algorithm only worksto deconflict a trajectory against the existing trajecto-ries and obstacles in the airspace, without consideringcapacity constraints and the overall impact on theairspace as a whole. To address this problem, weintroduce a decomposition in our planning approachbetween the lower-level trajectory optimization andthe high-level traffic management decision makingsuch as schedule allocation, altitude assignment, andcorridor control. We adopt an approach similar tothe NASA SAFE50 architecture [38], and allow thescheduling of the flight to be independent of thetrajectory generation. While scheduling and trajectorygeneration could be coupled we introduce this de-composition to allow our approaches to scale and tomore easily integrate the encounter metrics introducedearlier into the flight-planning process. We deferthe coupling of the trajectory-optimization and thehigher-level traffic management for future work.

To introduce encounter metrics into the planningprocess, we focus on a single aspect of high-leveltraffic management - flight-scheduling. We considera simple approach to scheduling, where we attemptto optimize the future take-off time of the UAS withregards to a quantity of interest. For example, ifa flight request come in at time t0, it may take-

off anytime between t0 and tmax, where tmax is themaximum delay that flight can incur. If the take-off time is optimized in regard to the total numberof encounters with already planned flights, we cancompute the total number of those encounters forhypothetical flights that would start in the time range[t0, tmax] and determine the optimal take-off time. Wecall this approach First Come Scheduling. The namewas chosen, because the first vehicles to request plansin an airspace will not incur any delays, while plansat later times may be asked to delay in order tominimize the number of encounters with existingvehicles. For simplicity, we discretize the time rangeat fixed intervals ∆t, and evaluate the immediateencounters for a flight request starting at each of thediscrete start times.

We introduce the encounter shift metric intothis scheduling approach by considering how the en-counter shift changes as we change the take-off timeof the flight request. We evaluate the encounter shiftof a flight-request between the encounter distributionof the airspace at each point in the interval [t0, tmax],and pick a take-off time with lowest encounter shiftvalue. The evaluation process is outlined in Figure 6for a request on the time interval [0,90]. In theexample, the encounter shift is minimized at t = 10s,and we call this scheduling process the EncounterSchedule. In the remainder of this work we uset = 10s and tmax = 90s The trajectory optimizationapproach outlined earlier can be used following eitherof the scheduling approaches. Because the schedulingand the trajectory optimization are decoupled it isalso possible to evaluate the effectiveness of theapproaches individually.

While it is possible to minimize the encountershift by introducing structure into the airspace, weleave that investigation for future work. Instead, wefocus on using take-off scheduling that is encounteraware to minimize the encounter shift for each flight.In particular, one important aspect of minimizingthe encounter shift during scheduling is that it helpsaddress the problem of planning in many-vehicleencounters. By optimizing the take-off time for eachflight with regards to the encounter shift, we natu-rally drive the airspace to have fewer many vehicleencounters. We demonstrate this property in detail inthe Results Section.

Page 10: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

G. Jointly Optimized Flight Planning

Jointly optimizing flight plans can be done witha centralized planner, that can process all flight re-quests within an airspace and perform multi-trajectoryoptimization. During this optimization process, theplanner computes multiple optimized trajectories thatare collision free simultaneously. Note that this doesnot require that the take-off times for the trajectoriesbeing optimized are the same only that the planningprocess is mutually shared for all of the flights. Theformulation of the problem is nearly identical tothe single trajectory optimization in Equation 5 ex-cept the optimization vector x now includes multipletrajectories. The complexity of optimizing multipletrajectories simultaneously grows quadratically withthe number of encounters despite the optimizationvector growing linearly, so the problem becomes morecomputationally expensive to solve.

It is important that the planner work in a realisticairspace simulation where flight requests can come inwell before the flight or just a few moments prior totake-off. However, jointly optimizing all known flightrequests is not feasible, particularly if the number ofoperations is high. In this work, we enforce a limiton the number of trajectories the planner optimizessimultaneously by defining a time horizon at whichthe joint optimization ends topt . The approach is asfollows:

Input: toptwhile t < topt do

if new requests thenF ← flight requests in range [t, topt ]T ← JointOpt(F )

endtake off for all in T starting at tt← t +∆t

endAlgorithm 2: Rolling horizon joint trajectory op-timization

After the planner has gone through a single opti-mization cycle, the process can start with a new topt .In this work, we use ∆t = 1s. While it is possibleto efficiently perform coordinated planning even inthe presence of asynchronous schedules [31], we donot explore this route in this work. We assume acentralized planner that can process flight requests si-multaneously for when we perform joint optimizationof multiple trajectories.

2 km

0

2

4

6

8

10

12

14

Take-Offs/Hr

Figure 7. Take-off heat-map for the multi-modalregion used to evaluate the approaches in thiswork.

ResultsThe scalability and effectiveness of the encounter

aware planning approach is demonstrated throughhundreds of hours of airspace simulation. We comparethe approach to stand alone trajectory optimization,two schedule based approaches for deconfliction, anda joint optimization planning approach. We examinethe performance of each in a high-fidelity airspacesimulation.

H. Simulation ModelWe use a high-fidelity airspace simulator to eval-

uate our approach. In the simulation, flight-requestsare generated using a stochastic process and are basedon a demand model. The demand model used in thiswork is multi-modal from a geographic perspective.For a map of take-off heat-map of a 5 hour simulationrun, see Figure 7. The region is 18km× 18km insize. The requests are passed onto a planner whichcan be configured to follow any of the managementapproaches and their combination discussed in theprevious section. Planning is performed in a dis-tributed way except for joint optimization.

To model the vehicles in our simulation, we usea simple point-particle dynamic model with a hybridPID and logic control for guidance. The prescribedcruise speed and cruise altitudes of the vehicles are40ms−1 and 120m respectively. While the simulatedvehicles have on board sensing and conflict resolution

Page 11: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

2 3 4 5 6

Vehicles Per Encounter

0.0

0.2

0.4

0.6

0.8

1.0

Pro

babi

lity

Joint Opt

2 3 4 5 6

Vehicles Per Encounter

0.0

0.2

0.4

0.6

0.8

1.0

Pro

babi

lity

Trajectory Opt + Encounter

2 3 4 5 6

Vehicles Per Encounter

0.0

0.2

0.4

0.6

0.8

1.0

Pro

babi

lity

No Deconfliction

Figure 8. The encounter distributions with 1000 take-offs per hour for no deconfliction (left), jointoptimization (center), and encounter aware trajectory optimization (right). The horizontal line representsthe fraction of pairwise encounters in the the encounter aware trajectory optimization simulations.

capabilities we do not consider them in this work,and instead focus on the evaluation of the planningapproaches proposed.

I. Airspace SimulationsThe goal of the airspace simulations is to eval-

uate the viability of the approaches presented earlierin the context of strategic pre-flight deconfliction. Weconsider point to point operations with take-off ratesranging from 100 to 1000 per hour. The followingapproaches are evaluated in this section:• Trajectory Optimization: standalone trajectory

optimization approach. Referred to as Traj Optin the evaluations.

• First Come Scheduler: a scheduler that attemptsto minimize the number of encounters for a flightrequest.

• Encounter Scheduler: a scheduler that attemptsto minimize the encounter shift for a flight re-quest.

• Encounter Aware Trajectory Optimization:combined encounter scheduler and trajectory op-timization. Referred to as Traj Opt + Encounter.

• Joint Optimization: jointly optimized planningapproach using a centralized planner. Referred toas Joint Opt.

For each approach, we collected approximately 28hours of simulated operational time, resulting in 95%confidence intervals for the results at the lowest take-off rate of 100 per hour, and 99% confidence intervalat 1000 take-offs per hour.

Qualitatively, the differences in encounter distri-butions between encounter aware flight planning andthe joint optimization approaches are shown in Fig-ure 8 for 1000 take-off/hr simulations. The encounter

distribution for an airspace managed by the encounteraware planner has a significantly larger fraction ofpairwise encounters compared to encounter with morethan two vehicles. This is in contrast to the encounterdistribution from simulations with no deconflictionand the encounter distribution with joint optimization,where the encounters are more evenly distributed.A key property of the encounter aware planner isthat it drives the airspace into a less complex regimeby shifting the encounter distribution to simpler en-counter sets. This has a significant impact on theoverall safety of the airspace (see Figure 9). Wenote that the encounter aware trajectory optimizationplanner outperforms all the planning approaches in-cluding the one using joint optimization at 1000 take-offs/hr. This is a particularly surprising result, as weexpect joint optimization to be the superior approachbecause it is centralized. However, we suspect thatat the higher take-off/hr rates, we are reaching thelimit of how well a centralized method can performand thus see a worsening performance compared tothe encounter aware method. Route efficiencies areshown in Figure 10 as ratios of actual over nominalroute lengths. Deconfliction approaches that use onlyscheduling have an efficiency of 1.0, and are notshown. Overall, we see that joint optimization isthe most efficient approach, with the encouter awareplanning performing nearly as well.

We also examine the resulting encounter charac-teristics for each method of the airspace in questionin Table I. The table shows the encounter shift foreach method at different take-off/hr rate as well asthe percentage of the encounter which have morethan two vehicles in them. Both of these metrics are

Page 12: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

Figure 9. Loss of separation rates for the multi-modal region with linear (left) and log (right) scaledaxis. The horizontal axis represents the vehicle take-off rate per hour for the whole region.

200 400 600 800 1000Take-Off/Hr

1.00

1.02

1.04

1.06

1.08

1.10

1.12

1.14

1.16

Actu

al /

Nom

nal R

oute

Len

gth

Route Efficiencytypetraj-opttraj-opt+encounterjoint-opt

Figure 10. Route efficiencies for the multi-modalregion at varying take-off rates. Efficiencies arerepresented by the ratio of actual / nominal routelengths.

important in assessing airspace complexity. Here, weare able to observe the primary difference between thejoint optimization and the encounter aware methods.Because the joint optimization method is not attempt-ing to manage the encounters in the airspace, we seethat it actually has a positive encounter shift at 1000take-offs/hr. This implies that the airspace managedby the joint optimization planner has more complexencounters than the one with no deconfliction at all. Itshould also be noted that the encounter aware trajec-tory optimization planner has the lowest encounter

shift, signifying it is able to drive the encounterdistribution towards simple encounter scenarios. Thiswould explain the gap in safety performance betweenthe encounter aware and the joint optimization ap-proaches.

ConclusionA robust and efficient distributed planning

method is presented in this paper. The approachcombines 4D trajectory optimization and an encounteraware scheduling heuristic, and is shown to outper-form existing methods for distributed flight-planning.As part of this work, we also provide a number ofnumerical benchmarks that compare our approach toa other distributed planning algorithms and a cen-tralized joint optimization approach in a high-fidelityairspace simulation environment. We show that ourapproach is able to consistently perform more safelyand efficiently than other distributed approaches at allthe operational densities considered in this work. Weshow that by reducing the fraction of many-vehicleencounters in the airspace, our approach is not onlyable to achieve better safety performance but is alsomore efficient than traditional planning approaches.

While this work provides a starting point, a num-ber of questions still remain about traffic managementin the unmanned sky. In particular, one big challengelies in understanding the requirements of UTM. It isnot clear how demand for UAS will evolve in the next20 years, making it difficult to create requirements

Page 13: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

Metric CAS Take-off Rates (1 / hr)100 250 500 1000

Encounter Shift

No Deconfliction (ref) - - - -Traj Opt -0.02 ± 0.01 -0.04 ± 0.03 -0.08 ± 0.03 -0.14 ± 0.05Encounter Scheduler -0.10 ± 0.02 -0.22 ± 0.08 -0.47 ± 0.16 -0.84 ± 0.11Encounter Traj Opt -0.11 ± 0.01 -0.29 ± 0.09 -0.63 ± 0.21 -1.02 ± 0.14Joint Opt 0.01 ± 0.02 -0.12 ± 0.04 -0.02 ± 0.05 0.13 ± 0.04

Multi-threatEncounter Percent

No Deconfliction 5.6 ± 1.3 19.5 ± 2.1 31.8 ± 2.5 51.4 ± 3.3Traj Opt 4.8 ± 1.5 17.1 ± 3.7 29.3 ± 3.2 54.5 ± 3.9Encounter Scheduler 0.1 ± 0.1 4.3 ± 1.7 21.9 ± 5.4 36.8 ± 3.2Encounter Traj Opt 0.2 ± 0.1 4.9 ± 1.2 23.6 ± 2.9 41.4 ± 2.8Joint Opt 5.3 ± 0.9 20.8 ± 2.7 34.6 ± 3.2 58.9 ± 3.8

Table I. Encounter metrics for varying take-off rates and different planning algorithms

and a functional system that can manage unmannedtraffic, and future work will examine how flexible ourapproach is to a wide range of requirements. We alsoplan to examine other methods beyond the penaltymethod trajectory optimization [37], as it is known tohave difficulties in convergence which could impactthe overall quality of the flight-plans it produces. An-other important aspect will be in evaluating how wellthe flight-planning approaches outlined in this workcan integrate into the current airspace. Of particularimportance is the ability to interface with humandecision makers in ATC [39]. Lastly, we plan toexamine other approaches to inferring the encountershift. Such as the ones that have been applied topredict delays in air traffic networks [40]. One thingis certain. To enable safe and efficient operation ofUAS, a traffic management system is needed that isrobust, reliable, and scalable. The work presented inthis paper is a small step towards that goal.

AcknowledgementsThe authors would like to thank Richard Gold-

ing and Karthik Balakrishnan for their insights andguidance throughout this work. A special thanks alsogoes out to everyone at Airbus UTM, who in one wayor another helped contribute to this paper.

References[1] K. Balakrishnan, J. Polastre, J. Mooberry, R.Golding, and P. Sachs, “Blueprint for the sky: Theroadmap for the safe integration of autonomous air-craft,” Airbus UTM, San Francisco, CA, 2018.

[2] D. Jenkins, B. Vasigh, C. Oster, and T. Larsen,Forecast of the Commercial UAS Package DeliveryMarket. Embry-Riddle Aeronautical University, 2017.[3] J. Holden and N. Goel, “Uber elevate: Fast-forwarding to a future of on-demand urban air trans-portation,” Uber Technologies, Inc., San Francisco,CA, 2016.[4] B. A. Hamilton. (2018). Urban air mobility marketstudy, [Online]. Available: https : / / go . nasa . gov /2MVSbth.[5] P. Kopardekar, J. Rios, T. Prevot, M. Johnson,J. Jung, and J Robinson, “Unmanned aircraft systemtraffic management (utm) concept of operations,” inAIAA Aviation Forum, 2016.[6] H. Ushijima. (2017). Utm project in japan, [On-line]. Available: https://bit.ly/2UMzDyw.[7] SESAR. (2017). U-space blueprint, [Online].Available: https://bit.ly/2UKf8SX.[8] L. Janson, E. Schmerling, A. Clark, and M.Pavone, “Fast marching tree: A fast marchingsampling-based method for optimal motion planningin many dimensions,” The International journal ofrobotics research, vol. 34, no. 7, pp. 883–921, 2015.[9] B. Paden, M. Cáp, S. Z. Yong, D. Yershov, andE. Frazzoli, “A survey of motion planning and con-trol techniques for self-driving urban vehicles,” IEEETransactions on intelligent vehicles, vol. 1, no. 1,pp. 33–55, 2016.[10] Y.-b. Chen, G.-c. Luo, Y.-s. Mei, J.-q. Yu, andX.-l. Su, “Uav path planning using artificial potentialfield method updated by optimal control theory,”International Journal of Systems Science, vol. 47,no. 6, pp. 1407–1420, 2016.

Page 14: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

[11] C. Tomlin, G. J. Pappas, and S. Sastry, “Conflictresolution for air traffic management: A study inmultiagent hybrid systems,” IEEE Transactions onautomatic control, vol. 43, no. 4, pp. 509–521, 1998.[12] A. Chakrabarty, V. Stepanyan, K. S. Krishnaku-mar, and C. A. Ippolito, “Real-time path planningfor multi-copters flying in utm-tcl4,” in AIAA Scitech2019 Forum, 2019, p. 0958.[13] S. Balachandran, A. Narkawicz, C. Muñoz, andM. Consiglio, “A path planning algorithm to enablewell-clear low altitude uas operation beyond visualline of sight,” in Twelfth USA/Europe Air TrafficManagement Research and Development Seminar(ATM2017), 2017.[14] J. Lee, H. Shin, and D. H. Shim, “Path-planning with collision avoidance for operating mul-tiple unmanned aerial vehicles in same airspace,”in 2018 AIAA Information Systems-AIAA Infotech@Aerospace, 2018, p. 1460.[15] Z. Liu and R. Sengupta, “An energy-based flightplanning system for unmanned traffic management,”in Systems Conference (SysCon), 2017 Annual IEEEInternational, IEEE, 2017, pp. 1–7.[16] J. Rios. (2018). Strategic deconfliction: Systemrequirements, [Online]. Available: https : / / utm . arc .nasa.gov/docs/2018- UTM- Strategic- Deconfliction-Final-Report.pdf.[17] J. T. Betts, “Survey of numerical methods fortrajectory optimization,” Journal of guidance, control,and dynamics, vol. 21, no. 2, pp. 193–207, 1998.[18] N. Ratliff, M. Zucker, J. A. Bagnell, and S. Srini-vasa, “Chomp: Gradient optimization techniques forefficient motion planning,” in Robotics and Automa-tion, 2009. ICRA’09. IEEE International Conferenceon, IEEE, 2009, pp. 489–494.[19] M. Kalakrishnan, S. Chitta, E. Theodorou, P.Pastor, and S. Schaal, “Stomp: Stochastic trajectoryoptimization for motion planning,” in Robotics andAutomation (ICRA), 2011 IEEE International Con-ference on, IEEE, 2011, pp. 4569–4574.[20] J. Schulman, J. Ho, A. X. Lee, I. Awwal, H.Bradlow, and P. Abbeel, “Finding locally optimal,collision-free trajectories with sequential convex opti-mization.,” in Robotics: science and systems, Citeseer,vol. 9, 2013, pp. 1–10.[21] A. Klein, M. D. Rodgers, and K. Leiden,“Simplified dynamic density: A metric for dynamicairspace configuration and nextgen analysis,” in Dig-

ital Avionics Systems Conference, 2009. DASC’09.IEEE/AIAA 28th, IEEE, 2009, pp. 2–D.[22] P. Kopardekar, A. Schwartz, S. Magyarits,and J. Rhodes, “Airspace complexity measurement:An air traffic control simulation analysis,” in 7thUSA/Europe Air Traffic Management R&D Seminar,Barcelona, Spain, 2007.[23] G. Sharon, R. Stern, M. Goldenberg, and A.Felner, “The increasing cost tree search for opti-mal multi-agent pathfinding,” Artificial Intelligence,vol. 195, pp. 470–495, 2013.[24] K.-H. C. Wang and A. Botea, “Mapp: A scalablemulti-agent path planning algorithm with tractabilityand completeness guarantees,” Journal of ArtificialIntelligence Research, vol. 42, pp. 55–90, 2011.[25] R. Luna and K. E. Bekris, “Push and swap: Fastcooperative path-finding with completeness guaran-tees,” in IJCAI, 2011, pp. 294–300.[26] I. Rish et al., “An empirical study of the naivebayes classifier,” in IJCAI 2001 workshop on empir-ical methods in artificial intelligence, vol. 3, 2001,pp. 41–46.[27] L. Ren, M. Castillo-Effen, H. Yu, Y. Yoon,T. Nakamura, E. N. Johnson, and C. A. Ippolito,“Small unmanned aircraft system (suas) trajectorymodeling in support of uas traffic management (utm),”in 17th AIAA Aviation Technology, Integration, andOperations Conference, 2017, p. 4268.[28] P. Sachs. (2018). A quantitative framework foruav risk assessment, [Online]. Available: http://bit.ly/altiscopetr008.[29] L. Xiao and S. Boyd, “Optimal scaling ofa gradient method for distributed resource alloca-tion,” Journal of optimization theory and applications,vol. 129, no. 3, pp. 469–488, 2006.[30] C. A. Uribe, S. Lee, A. Gasnikov, and A. Nedic,“Optimal algorithms for distributed optimization,”arXiv preprint arXiv:1712.00232, 2017.[31] E. Robinson, H. Balakrishnan, M. Abramson,and S. Kolitz, “Optimized stochastic coordinatedplanning of asynchronous air and space assets,” Jour-nal of Aerospace Information Systems, pp. 10–25,2017.[32] R. Golding. (2018). Metrics to characterizedense airspace traffic, [Online]. Available: http://bit.ly/altiscopetr004 (visited on 02/03/2019).[33] M. Rufli, D. Ferguson, and R. Siegwart, “Smoothpath planning in constrained environments,” in IEEE

Page 15: ENCOUNTER AWARE FLIGHT PLANNING IN THE ...4-D intersection with any other UTM operation prior to departure operation [16], and in this work we aim to address exactly this problem.

International Conference on Robotics and Automa-tion, 2009. ICRA’09, Eidgenössische TechnischeHochschule Zürich, 2009, pp. 3780–3785.[34] J. Van den Berg, M. Lin, and D. Manocha,“Reciprocal velocity obstacles for real-time multi-agent navigation,” in Robotics and Automation, 2008.ICRA 2008. IEEE International Conference on, IEEE,2008, pp. 1928–1935.[35] D. Silver, “Cooperative pathfinding.,” AIIDE,vol. 1, pp. 117–122, 2005.[36] M. Phillips and M. Likhachev, “Sipp: Safe in-terval path planning for dynamic environments,” inRobotics and Automation (ICRA), 2011 IEEE Inter-national Conference on, IEEE, 2011, pp. 5628–5635.[37] E. Polak, Optimization: algorithms and consis-tent approximations. Springer Science & BusinessMedia, 2012, vol. 124.

[38] C. Ippolito, K Krishnakumar, V Stepanyan, AChakrabarty, and J Baculi, “An autonomy architecturefor high-density operations of small uas in low-altitude urban environments,” in 2019 AIAA Modelingand Simulation Technologies Conference. San Diego,CA. Jan, vol. 2109, 2019.[39] P. D. Vascik, H. Balakrishnan, and R. J. Hans-man, “Assessment of air traffic control for urban airmobility and unmanned systems,” 2018.[40] K. Gopalakrishnan and H. Balakrishnan, “Acomparative analysis of models for predicting delaysin air traffic networks,” ATM Seminar, 2017.

2019 Integrated Communications Navigationand Surveillance (ICNS) Conference


Recommended