Small unmanned aerial vehicles (UAVs) have the potential to revolutionize various applications in civilian domain such as disaster management, search and rescue operations, law enforcement, precision agriculture, and package delivery. As the number of such UAVs rise, a robust and reliable traffic management is needed for their integration in national airspace system (NAS) to enable real-time, reliable, and safe operation. Management of UAVs traffic in NAS becomes quite challenging due to issues such as real-time path planning of large number of UAVs, communication delays, operational uncertainties, failures, and noncooperating agents. In this work, we present a novel UAV traffic management (UTM) architecture that enables the integration of such UAVs in NAS. A combined A*–mixed integer linear programming (MILP)-based solution is presented for initial path planning of multiple UAVs with individual mission requirements and dynamic constraints. We also present a distributed detect-and-avoid (DAA) algorithm based on the concept of resource allocation using a market-based approach. The results demonstrate the scalability, optimality, and ability of the proposed approach to provide feasible solutions that are versatile in dynamic environments.

Introduction

While unmanned air vehicles (UAVs) have been used in military operations for many years, they have recently generated a lot of interest due to their potential application in civilian domains. Applications include emergency management, law enforcement, precision agriculture, package delivery, infrastructure inspection, and imaging/surveillance [16]. As the use of UAVs rapidly becomes a reality in civilian domains, it becomes increasingly critical to solve the challenges emanating from integration of UAVs in the national airspace system (NAS). It is important for a UAV to plan its mission path, replan or adjust its trajectory to maintain separation with other aircraft. Traffic management adds a third goal: a UAV must act in a way that does not interfere with traffic. Furthermore, the dramatic increase in the number of aircraft, manned and unmanned, over the last 50 years will pose severe challenges to the current air traffic control. Hence, the radio technical commission for aviation and Federal Aviation Administration have been charged with a responsibility to implement a seamless change from air traffic control to air traffic management by 2020 [79]. To this end, the Federal Aviation Administration has begun to deploy the low altitude authorization and notification capability, which enables drone pilots access to controlled airspace near airports through a UAV service supplier [10]. This fits with the UAV traffic management (UTM) architecture developed by the National Aeronautics and Space Administration and industry.

National Aeronautics and Space Administration's TCL3 tests, held in spring of 2018, focused on testing technologies that maintain safe spacing between cooperative and noncooperative UAV over moderately populated areas. Their current UTM architecture includes an air navigation service provider, which interfaces with NAS data sources and provides constraints and directives to multiple industry UAV service suppliers, which coordinate with UAV operators, each other, and supplemental service providers to maintain a clear airspace [11].

For managing airspace traffic, there are various studies on lane-based systems [12], using rapidly exploring random trees and conflict bands [13], implicit coordinated detect-and-avoid using airspace tessellation, A*, and keep-out geofences [14]. Furthermore, there are market-inspired approaches for urban automotive intersection management [15], which could be expanded to work with lane-based or tessellation-based systems. While UTM may prevent some conflicts from occurring, there still needs to be detect-and-avoid (DAA) methods for UAVs. There are various methods for calculating escape trajectories that have been proposed for collision avoidance including classical control [16], fuzzy logic [17], E-field maneuver planning [18,19], game theory [20], evolutionary methods [21] and their application in numerical control machines path planning [22,23], automotive trajectory planning [24], and mixed-integer linear programming (MILP) [25,26].

The UTM problem essentially refers to planning paths of UAVs so that minimum separation is maintained between UAVs, static obstacles, and each UAV completes its mission. The UTM problem essentially involves two steps: (i) global path planning, which refers to obtaining collision-free paths for all UAVs in a global manner and (ii) DAA, which avoids collisions in a local manner. DAA becomes necessary because UAV traffic condition is subject to change due to any number of factors, including but not limited to: wind, new aircraft entering airspace, and changes in mission objectives. DAA's objective is to avoid collisions arising due to these dynamic effects and is usually implemented on a local basis. Criterion for assessing the performance of a DAA system includes how well safety was maintained, how close each UAV's trajectory is to optimal for its mission, and how quickly the system can resolve conflicts. In this paper, we utilize A*/MILP approach for global path planning. Use of A*/MILP ensures global optimality of the paths obtained. A* is first used to obtain initial trajectories of all the UAVs considering only static obstacles on a coarser grid scale. Paths obtained by A* are then refined by the MILP algorithm on a finer grid scale ensuring collision avoidance with other UAVs (dynamic obstacles). The DAA capability is implemented using a market-based approach. The DAA algorithm works by a market-based bidding process to resolve conflicts as they occur. This approach offers computationally efficient solutions, which are near-optimal, and can be implemented in a distributed fashion. Safety is quantified by the difference between the closest point between UAVs at a given time and any loss of separation. The problem is formulated such that several UAVs fly through a three-dimensional representation of a city, following a set of waypoints. The approaches proposed in this paper have been validated using very realistic numerical simulations that include three-dimensional (3D) model of downtown part of City of Cincinnati, OH.

The paper is outlined as follows: We propose a novel UTM architecture that is composed of flight protocol, communication aspects, and the navigation scenario in Sec. 2. Section 3 talks about the global path planning problem formulation and its solution and Sec. 4 explains our market-based DAA approach. We present the simulation results in Sec. 5 and the discussions in Sec. 6.

Proposed Unmanned Aerial Vehicles Traffic Management Architecture

We present a novel UTM architecture in this section that comprises the flight, communication, and navigation protocol. The nomenclature of various terms is defined as follows:

UAS: Unmanned aerial system, also referred to as UAV, is an autonomous flying vehicle. It is capable of talking to the UAS operator via wireless telemetry, using LTE, Wi-Fi, or any other methods. It is also equipped with an autopilot and an automated dependence surveillance-broadcast.

UAS operator: A person, or an organization, that is in charge of flying vehicles and is responsible for ensuring airworthiness by proper maintenance.

NAS: National airspace system is the airspace, its facilities, and airports of the United States along with their rules, regulations, policies, personnel, etc.

VLOS: Visual line of sight, basically means that the system can be observed visually. The contrary term is BVLOS (Beyond VLOS), which means the system is not visible to an observer.

UTM: UAS traffic management service is the main service that monitors and ensures that all the airborne UAS are operating in a safe manner. It also plans the flight path for these UAS as requested by the user through a ground control station. The UTM talks to ground control station through the internet to receive mission plan requests and responds with an approval or denial. The UTM also talks to the airspace management database that is shared with the air traffic controllers for manned aircrafts.

No-fly zone: A geo-fenced area that is restricted for general UAS to enter. This could be permanent, such as 400 ft. above ground level or airports, or it could be temporary, such as construction or accident sites.

Waypoints: Geo-coordinates of a location that will be visited by a UAS during its flight. They could be mandatory or optional.

Flight mission: A layout of the flight plan with starting and ending geolocations, optionally but generally, with intermediate waypoints. It is basically trajectory information with timestamped waypoints to be visited. Additionally, it might include the tolerance around the area and/or the time where/when the UAS could be located.

Centralized approach: This kind of approach means that all the operations are handled by a central service.

Decentralized approach: Opposed to centralized approach, the operations are handled by the services that are responsible for their respective coverage areas. Essentially, this is a combination of several centralized approaches talking to each other.

UAS state: The state of the UAS, which includes the position and velocity information and additionally, may include the health of the UAS, such as battery status, sensor health, etc.

Obstacles: The locations in the environment that cannot be taken by the UAS. These could be buildings, trees, and any other flying objects, including other UAS.

Noncooperative/rogue UAS: The UAS, which have deviated from the prescribed flight plan by the UTM and behaving in a suspicious manner. This could be caused by system malfunction or malicious intent of the user.

Pop-up threats: Threat to the UAS navigation that was not anticipated. This could include rogue UAV, or even unplanned construction/accident sites.

C2: Command and control, the method to send control commands to the UAS to ensure it follows the prescribed flight plan.

SAA: Sense and avoid is the capability to sense the obstacles (static or dynamic) and use obstacle avoidance algorithms to avoid collisions with those obstacles by flying around them at a safe operating distance.

Flight Protocol.

A schematic of the flight protocol is shown in Fig. 1. Sequentially, this can be realized as follows:

Fig. 1
  • (1)

    The UAS operator comes up with a desired mission. This demand would include a starting point, a destination (which could be same as the starting point), optionally, the waypoints to visit, the time of flight, and additionally, some identification of their UAS, such as build type, type of sensors, and capabilities.

  • (2)

    The UAS operator sends this demand to the UTM service.

  • (3)

    The UTM responds with an approval or denial. If approved, a detailed flight mission plan is returned. If denied, the user may retry with a new request.

  • (4)

    If the UAS operator received an approved flight plan, they can communicate this to their UAS through wireless link.

  • (5)

    The UAS starts the mission according to the given flight plan.

  • (6)

    If the actual navigation performance of the UAS deviates from the required navigation performance by a prescribed limit, the UAS is considered as noncooperative and goes into a rogue state. An occasional small deviation could be a result of noise in sensors or positioning and may be ignored.

  • (7)

    In case of rogue UAS, the UTM sends the mission abort commands to the UAS directly, thus forcing the UAS to end mission and land at the nearest safe location.

  • (8)

    In case the UAS operator comes up with a need to modify the original flight plan while the UAS is still flying, they may request this to the UTM and an updated flight mission may be received. This change can be uploaded to the UAS directly or sent through the UAS operator.

  • (9)

    If the UAS completes the mission successfully, the UAS operator sends a mission report log and the UTM retains it.

  • (10)

    Once the mission report is received, the UTM stops monitoring that UAS and the UAS operator is unsubscribed from the UTM service until next mission.

Navigation Protocol.

A schematic of the navigation protocol is shown in Fig. 2. The airspace below 400 ft. above ground level will be divided into N number of layers of an appropriate height depending on minimum safe operating radius. As the UAS operators request a flight path, a cuboid strip of airspace from the starting location to destination will be allocated to the user for the requested time. These airstrips will be divided into separate sections that will be reserved for the operator for a given time. This would mean that at any time instant, the UAS can be located within a given location only (with tolerances on location and time). This would make the airspace utilization more efficient by freeing up sections through which the UAS has already passed.

Fig. 2
Navigation protocol
Fig. 2
Navigation protocol
Close modal

Communication Protocol.

A schematic of the communication protocol is shown in Fig. 3. We define the various communication links as follows:

Fig. 3
Communication protocol
Fig. 3
Communication protocol
Close modal

The primary command and control (C2) link will be set up between the UTM server and the UTM client onboard the UAS. This will be the primary mode of communication between the UTM service and the UAS. The UTM will get the state of the UAS through this link that will include position, velocity, and the health of the UAS (such as battery status, and sensor status).

There will be a secondary C2 link between the UAS operator and the UAS, which may be used if needed. For instance, the onboard autopilot will be aware of the environment and strategies for a successful mission through the primary C2. However, there might be cases when sudden changes in environment arise, such as accident sites and medevac instances, which would require the UAS to change its mission course. The UAS will then ask the operator to supply with proper strategies to continue its mission. Another example could be if the operator decides to abort the mission prematurely, they can send the abort commands directly to the UAS.

The UTM to UAS Operator communication will be the one instantiating/subscribing to the UTM service. This would include mostly environmental updates, such as weather info, terrain updates, and emergency announcements.

The UAS will be able to subscribe to other agents' positions through an onboard position information broadcast system. This will include the position and velocity information of the agents that will be vital in making SAA decisions.

Global Path Planning—Problem Formulation and Solution Methodology

This paper focuses on the development of a method to manage UAV traffic in an urban environment. The UAVs must navigate through an environment full of static and dynamic obstacles (in the form of each other). The path-planning problem is solved using a combination of A*, to find a general optimal path, and MILP to find optimized trajectories with respect to the static and dynamic obstacles. Particularly, A* provides the shortest path for all the UAVs at macro level (at a coarser grid scale) while the MILP part of the algorithm gives the optimal path in terms of minimum energy consumption of all the UAVs at a finer grid scale. In what follows, we describe our A*/MILP approach in more detail.

Obstacles drawn from laser imaging, detection and ranging data of a city's height are represented by 8 m × 8 n rectangles, where m and n are nonzero integers. Each obstacle has minimum and maximum x and y coordinates. Each vehicle has a minimum and maximum speed, a mass, and a maximum acceleration. Each vehicle submits a flight plan at a specified time with a start point, end point, and K destinations, where K is a non-negative integer. There are two major parts to the algorithm: an A* portion that conducts macro path-planning considering only obstacles, and a MILP portion that finds an optimal path considering the waypoints from A*, time, vehicle dynamics, obstacle positions, and the other vehicles in the airspace. The overall algorithm for the UTM problem is shown in Algorithm 1.

Table

Algorithm 1: Path planning of multiple UAVs

 foreach flight plan (from earliest takeoff to latest)do
   foreach pair of waypoints in the flight plando
    Path = A*(pair of waypoints)
   end
   Construct the waypoints in path into segments short enough for the s-UAS to traverse in the time given for a MILP call.
   Trajectory = empty set of x, y, t points
  for each segment do
   Find the segment trajectory using MILP given the waypoints in the segment and the intruders in the segment for the time provided
   Append the segment trajectory to the current trajectory
  end
  Add the new trajectory to the list of trajectories
 end
 foreach flight plan (from earliest takeoff to latest)do
   foreach pair of waypoints in the flight plando
    Path = A*(pair of waypoints)
   end
   Construct the waypoints in path into segments short enough for the s-UAS to traverse in the time given for a MILP call.
   Trajectory = empty set of x, y, t points
  for each segment do
   Find the segment trajectory using MILP given the waypoints in the segment and the intruders in the segment for the time provided
   Append the segment trajectory to the current trajectory
  end
  Add the new trajectory to the list of trajectories
 end
Table

Algorithm 2: A* path planning approach

Initialize the start node with starting coordinates, no parent, and g and f scores of 0
Initialize all other Nodes with no parent and g and f scores of infinity
Declare the open set as an empty priority Queue
Declare the closed set as an empty set
Add the start node to the open set
Add all invalid nodes from the grid to the closed set
 whilethe open set is not emptydo
  Pop the best node from the open set
  Add the best node to the closed set
  ifthe best node is the goalthen
   Declare the Path as an empty set
   Current node = Best node
    whileCurrent node has a parentdo
    Prepend the current node to the Path
    Current node = parent(Current node)
    end
     Return Path
    end
    foreach neighbor of the best nodedo
    ifneighbor is not in closed setthen
    tentativeGScore = best node's g score + distance(Best node, neighbor)
    iftentativeGScore < neighbor's g Score
      then
     neighbor's g score = tentativeGScore
     neighbor's f score = neighbor's g score + distance(neighbor, goal)
     parent(neighbor) = best node
     Update the neighbor in the open set
     end
        end
      end
 end
Return path unavailable message
Initialize the start node with starting coordinates, no parent, and g and f scores of 0
Initialize all other Nodes with no parent and g and f scores of infinity
Declare the open set as an empty priority Queue
Declare the closed set as an empty set
Add the start node to the open set
Add all invalid nodes from the grid to the closed set
 whilethe open set is not emptydo
  Pop the best node from the open set
  Add the best node to the closed set
  ifthe best node is the goalthen
   Declare the Path as an empty set
   Current node = Best node
    whileCurrent node has a parentdo
    Prepend the current node to the Path
    Current node = parent(Current node)
    end
     Return Path
    end
    foreach neighbor of the best nodedo
    ifneighbor is not in closed setthen
    tentativeGScore = best node's g score + distance(Best node, neighbor)
    iftentativeGScore < neighbor's g Score
      then
     neighbor's g score = tentativeGScore
     neighbor's f score = neighbor's g score + distance(neighbor, goal)
     parent(neighbor) = best node
     Update the neighbor in the open set
     end
        end
      end
 end
Return path unavailable message
The pseudocode for the A* portion of the algorithm follows a typical A* approach as shown in Algorithm 2. Nodes are snapped to a grid with 8 m spacing and then added to the closed set if they are too close to an obstacle. This grid is kept consistent between calls so there is no need to recalculate whether a node is valid each time. Furthermore, the grid can be precomputed given a visibility criteria to determine which nodes are valid neighbors. A node is not a valid neighbor to a given node if they are farther apart than the visibility criteria or if they are separated by an obstacle. The initial and goal positions are snapped to the closest points in the grid that are not in an obstacle. The MILP portion of the algorithm functions by solving a set of mixed-integer linear programming equations with the Gurobi optimizer [27]. When called, it is given a time during which the s-UAS is expected to traverse a waypoint or set of waypoints from its initial state and a finite horizon it is expected to stay within during this time frame, in addition to vehicle, intruder trajectory, and obstacle information. The first constraint is the initial constraint, shown in the following equation:
x1=xinitialy1=yinitialvx1=vx,initialvy1=vy,initial
(1)
where, xinitial, yinitial, vx,initial, and vy,initial are all provided by the flight plan or a previous iteration of MILP. x1, y1, vx1, and vy1 are all of the form xn, yn, vxn, and vyn, where n is the nth timestep, here equal to 1. The finite horizon constraint is given by the following equation:
xinitialLhorizonxnxinitial+LhorizonnNstepsyinitialLhorizonynyinitial+LhorizonnNstepsNsteps={nZ+|nceil(TTd)}
(2)
where Lhorizon is the length of the finite horizon and T is the length of time in which the segment is to be completed. The constraints for the dynamic model are given by the following equation:
Sn+1=AdSn+BdFn:{nN|n<ceil(TTd)}Sn=[xnynvxnvyn]Ad=[10Td0010Td00100001]Bd=[Td2m00Td2mTdm00Tdm]Fn=[fxnfyn]
(3)
where m is the mass of the vehicle, fxn and fyn are the force of the vehicle in the x and y directions, respectively. Acceleration and velocity constraints are given by the following equation:
fxnsin(2hπH)+fyncos(2hπH)fmaxnNsteps,hZ+,hHvxnsin(2hπH)+vyncos(2hπH)vmin(vmaxvmin)(1bspeed,h,n)nNsteps,hZ+,hHvxnsin(2hπH)+vyncos(2hπH)vminη+(vminvmaxη)bspeed,h,nnNsteps,hZ+,hHh=1Hbspeed,h,nH1nNsteps
(4)
where fmax is the maximum force the vehicle can generate, H is an integer chosen to discretize the circle, vmin and vmax are the minimum and maximum velocity of the vehicle, respectively, bspeed,h,n is the binary variable for velocity at time-step n in direction h, and η is a very small number. If the minimum velocity is zero, as in multicopter vehicles, the binary variables bspeed,h,n can be excluded, and the constraint on velocity is given by the following equation:
vxnsin(2hπH)+vyncos(2hπH)vmaxnNsteps,hZ+,hH
(5)
The constraints for arriving at the waypoints and dwelling for a specified amount of time are given by the following equation:
xnxwrmin+Mbig(1bw,n)nNsteps,wZ+,wWynywrmin+Mbig(1bw,n)nNsteps,wZ+,wWxnxwrminMbig(1bw,n)nNsteps,wZ+,wWynywrminMbig(1bw,n)nNsteps,wZ+,wWbw,1=bTOA,w,1wZ+,wWbw,n=(t=1nbTOA,w,t)t=1n1bTOD,w,tnNsteps,wZ+,wWt=1NMAXbTOA,w,t=1wZ+,wWt=1NMAXbTOD,w,t=1wZ+,wWNMAX=ceil(TTd)rmin=m×vmin2fmaxt=1nbTOA,w+1,tt=1nbTOD,w,tnNsteps,wZ+,wW
(6)
where xw and yw are the coordinates of waypoint w. Mbig is a number that is large with respect to the finite horizon. bw,n is the binary variable for being at waypoint w at time-step n. W is the number of waypoints. bTOA,w,n and bTOD,w,n are binary variables for arriving at and departing from waypoint w at time-step n, respectively. Wdwell,w is the amount of time the vehicle is instructed to dwell at waypoint w. To prevent the vehicle's path from intersecting with obstacles or intruders between time steps, a safety factor is used. The constraints on this safety factor are in the following equation:
Sf,x,nvxnTd+fxnTd2+fxnTd22m+σSf,x,nnNstepsSf,y,nvynTd+fynTd2+fynTd22m+σSf,y,nnNsteps
(7)
where σ is the minimum safe distance allowed between the vehicle and an obstacle or intruder. Sf,x,n and Sf,y,n are the safety factors in the x direction and y direction, respectively. The equations to prevent obstacle collisions are in the following equation:
xnxmin,oSf,x,n+Mbigbobs,o,n,1nNsteps,oZ+,oOxnxmax,oSf,x,n+Mbigbobs,o,n,2nNsteps,oZ+,oOynymin,oSf,y,n+Mbigbobs,o,n,3nNsteps,oZ+,oOynymax,oSf,y,n+Mbigbobs,o,n,4nNsteps,oZ+,oOk=14bobs,o,n,k3nNsteps,oZ+,oO
(8)
where xmin,o, xmax,o, ymin,o, and ymax,o are the minimum x, maximum x, minimum y, and maximum y of obstacle o, respectively. bobs,o,n,k with k =1, 2, 3, and 4 are the binary variables for being outside of the minimum x, maximum x, minimum y, and maximum y, respectively, of obstacle o at time-step n. O is the total number of obstacles in the finite horizon. A similar set of constraints is used to construct the intruder avoidance in the following equation:
xnxmin,i,n2Sf,x,n+Mbigbi,1,nnNsteps,iZ+,iIxnxmax,i,n2Sf,x,n+Mbigbi,2,nnNsteps,iZ+,iIynymin,i,n2Sf,x,n+Mbigbi,3,nnNsteps,iZ+,iIynymax,i,n2Sf,x,n+Mbigbi,4,nnNsteps,iZ+,iIk=14bi,k,n3nNsteps,iZ+,iI
(9)
Here, xmin,i,n, xmax,i,n, ymin,i,n, and ymax,i,n are the minimum x, maximum x, minimum y, and maximum y, respectively, of intruder i at time-step n. bi,k,n, with k =1, 2, 3, and 4, are binary variables for excluding the vehicle from the area covered by intruder i at time-step n. I is the maximum number of intruders in the timeframe and finite horizon. The cost function for this two-dimensional maneuver has acceleration (i.e., force) and time components. The time component is given by the following equation:
Jtime=w=1Wn=1N(n1)bTOD,w,n
(10)
The acceleration component is given by the following equation:
Jforce=k=12n=1NMAXWslack,k,n
(11)
where Wslack,k,n is a slack variable constrained by the following equations:
fxnWslack,1,nnNstepsfxnWslack,1,nnNstepsfynWslack,2,nnNstepsfynWslack,2,nnNsteps
(12)

It may be noted that we include acceleration in our cost function in order to minimize force required for the motion, which translates into energy consumption.

Detect-and-Avoid—Market-Based Approach

As discussed in Sec. 3, the path planning of the UAVs is done based on a globally optimized solution by the UTM when they request a mission. This means there will not be any conflicts or chances of UAVs breaching safe zones of other UAVs. However, due to unavoidable circumstances and practical considerations, sometimes a UAV may deviate from its path. This may lead to conflicts with other UAVs.

The DAA process is triggered as soon as the UAVs enter a conflict zone. This conflict zone is determined based on safe operating distance of UAVs, which, in turn, may be based on the individual capabilities of the UAVs, such as maximum velocity and agility. Thus, the conflict zone is tessellated into grids and each grid cell may be envisioned as a resource that an agent (UAV) is trying to access at a given time. We borrow the concepts from economic markets such as demand supply for price updates and agent-level calculations [28]. This ensures scalability, optimality, and ability to provide feasible solutions that are fast enough to be responsive for dynamic changes.

Implementation.

Consider the conflict zone, encircled in red ellipse, as shown in Fig. 4 for a case of multiple UAVs under conflict. The conflicting cell is as marked and the UAVs are shown communicating with a ground UTM station, denoted as edge-UTM. The multi-UAV resource allocation problem can be mathematically formulated as
mint=tstri=1nrj=1naaij,txij,t
(13)
such that
i=1nrxij,t=1j=1,2,,na
(14)
j=1naxij,tNi,ti=1,2,,nr
(15)
Fig. 4
Conflict zone with multiple UAVs
Fig. 4
Conflict zone with multiple UAVs
Close modal

In the above equations, i and j are the resources (cells) and the agents (UAVs), respectively. Hence, Eq. (13) represents the total profit accumulated by all the UAVs. na is the number of UAVs and nr is the number of resources (grid cells). aij,t represents the known profit of agent j in utilizing resource i at time t. xij,t is the decision binary variable, which is 1 when the resource i is being utilized by the agent j, and 0, otherwise. ts and tr represent the start time of the conflict and the time instant when all conflicts have been resolved, respectively. In this paper, we consider a constant value of ai,j,t, which essentially means that the cost function is a measure of total distance traveled by all the UAVs. Equation (14) ensures that all UAVs utilize a resource at a given time (i.e., continuity) and Eq. (15) prevents a resource from being utilized by more than Ni agents. For collision avoidance, Ni would be equal to unity.

The solution to above problem is attempted in an iterative manner by each agent as follows:
minimizei=1nraij,txij,ti=1nr(pij)k,txij,t
(16)
where (pij)k represents the price of resource xij. The mechanism for price update is based on the concept of demand supply that uses information about the total number of requests made on a resource and its constraints to update the price. This essentially means increasing the price of resource that is under demand by more than Ni agents
(pi)k,t=(pi)k1,t+α(j=1naxij,tNi,t)
(17)

Simulation Results

Simulation Environment.

We consider an environment of 1.25 mi × 1.25 mi with a maximum height of 500 ft (2 km × 2 km × 152 m) in the downtown area of the city of Cincinnati. The laser imaging, detection and ranging data available from the USGA [29] were used to generate 3D model of the downtown area of Cincinnati. The UAVs are allowed to fly between 50 ft and 500 ft only. The grid size is chosen as 8 m × 8 m × 8 m. Multiple UAVs with random start and destination locations start their mission at different times. The initial path planning has been described in Sec. 3. Figure 5 shows the simulation area with height map of obstacles. To introduce operational delays in the system, we have assumed that 10% of the UAVs get delayed randomly by a uniformly distributed delay period of a maximum of ten time steps. This essentially means that some of the UAVs will start later than their proposed time of start. The market-based DAA algorithm can be constructed as in Algorithm 3.

Fig. 5
Height map of obstacles in the simulated environment
Fig. 5
Height map of obstacles in the simulated environment
Close modal
Table

Algorithm 3: DAA using market-based strategy

 Generate grids and set all grid prices to zero
 Set tglobal = 0
whilemissions remaindo
   Set tglobal = tglobal + 1
   Detect conflicts in next tdetect time steps
  whileconflicts remaindo
     Update grid prices (Eq. (17))
     Replan UAV paths between current position and local goal* based on Eq. (16)
  end
end
 *local goal is the grid cell where UAV would have been after tdetect time steps
 Generate grids and set all grid prices to zero
 Set tglobal = 0
whilemissions remaindo
   Set tglobal = tglobal + 1
   Detect conflicts in next tdetect time steps
  whileconflicts remaindo
     Update grid prices (Eq. (17))
     Replan UAV paths between current position and local goal* based on Eq. (16)
  end
end
 *local goal is the grid cell where UAV would have been after tdetect time steps

Results.

We simulated a number of scenarios for a different number of UAVs with different start and destination positions. Here, we present three such scenarios for 10, 25, and 100 UAVs. For 10 UAVs, we have considered a smaller area, to ensure there are conflicts observed and to demonstrate the potential of our DAA algorithm. This is shown in Fig. 6. The different UAV paths are shown in different colors. The destination of each UAV is shown by a ×. It should be noted that the axes represent the grids in the figures. The conflicting cell is identified by the Δ. To demonstrate the applicability of the proposed method to larger number of UAVs, Figs. 7 and 8 show the path planning over the whole simulation environment for 25 and 100 UAVs, respectively.

Fig. 6
Path planning of ten UAVs in a section of the simulation environment using market-based DAA strategy
Fig. 6
Path planning of ten UAVs in a section of the simulation environment using market-based DAA strategy
Close modal
Fig. 7
Path planning of 25 UAVs in the simulation environment using market-based DAA strategy
Fig. 7
Path planning of 25 UAVs in the simulation environment using market-based DAA strategy
Close modal
Fig. 8
Path planning of 100 UAVs in the simulation environment using market-based DAA strategy
Fig. 8
Path planning of 100 UAVs in the simulation environment using market-based DAA strategy
Close modal

Optimality Validation.

In order to demonstrate the optimality of proposed market-based DAA approach, we have compared the results obtained from market-based approach with those obtained from MILP solution, proposed in Refs. [25] and [30], as shown in Table 1. For a given tdetect in the conflict zone, we formulated the conflict zone and the UAVs in MILP framework and found that the result provides compatibility with the MILP solutions. Table 1 represents the comparison of three incidents of the scenarios provided in Sec. 5.2 and the MILP solver.

Table 1

Optimality analysis of market-based DAA approach with respect to MILP approach

Distance traveled by all the UAVs (number of grid cells)Market-based approachMILP approach
Incident 12626
Incident 22828
Incident 32828
Distance traveled by all the UAVs (number of grid cells)Market-based approachMILP approach
Incident 12626
Incident 22828
Incident 32828

In Table 1, for each of the incidents, we have reported the total distance traveled by all the UAVs, engaged in the conflict. The results represent compatibility with the MILP solver, which verifies the optimality of the proposed DAA solution.

Discussions

In this work, we have developed a centralized UTM architecture for safe path planning and navigation of multiple UAVs in national airspace. We have identified essential flight, navigation, and communication protocols for managing multiple UAV mission planning by the UTM server.

Further, we present a MILP-based solution for the initial path planning of the UAVs and a distributed DAA algorithm inspired from the concept of resource allocation to various tasks in an optimized way from market-based approach. We demonstrated that this concept can be extended to enable a safe navigation for multiple UAVs in a given environment, while generating a situational awareness in the region using on-board and ground-based sensors.

We also simulated a general scenario of multiple UAVs requesting mission plans with different start and destination locations. The simulation environment is taken as a subset of the downtown area of the city of Cincinnati, OH. To simulate the operational delays, we have introduced delays in the starting time of some of the UAVs. The simulation results corroborate the validity and scalability of our approach, and it can be observed that this approach can be easily extended to a large number of UAVs in a given environment while optimally carrying out the path planning and DAA in a safe and reliable manner. The developed algorithm is also robust to delays, uncertainties, and deviations in the UAV paths. A striking feature of this DAA approach is the ability to globally optimize the cost function of all the UAVs present in the environment as validated in Sec. 5.2.1. This makes it suitable for real-time path planning and DAA in uncertain environments where UAVs enter and leave at will.

References

1.
Schaufele
,
R.
,
Ding
,
L.
,
Miller
,
N.
,
Barlett
,
H.
,
Lukacs
,
M.
, and
Bhadra
,
D.
,
2017
, “
FAA Aerospace Forecast: Fiscal Years 2017-2037
,” United States Department of Transportation, Washington, DC.
2.
Radmanesh
,
M.
,
Nematollahi
,
O.
,
Nili-Ahmadabadi
,
M.
, and
Hassanalian
,
M.
,
2014
, “
A Novel Strategy for Designing and Manufacturing a Fixed Wing Mav for the Purpose of Increasing Maneuverability and Stability in Longitudinal Axis
,”
J. Appl. Fluid Mech.
,
7
(
3
), pp. 435–446.
3.
Nex
,
F.
, and
Remondino
,
F.
,
2014
, “
UAV for 3D Mapping Applications: A Review
,”
Appl. Geomatics
,
6
(
1
), pp.
1
15
.
4.
Nemati
,
A.
, and
Kumar
,
M.
,
2016
, “
Control of Microcoaxial Helicopter Based on a Reduced-Order Observer
,”
J. Aerosp. Eng.
,
29
(
3
), p.
04015074
.
5.
Nemati
,
A.
,
Haddad Zarif
,
M.
, and
Fateh
,
M. M.
,
2007
, “
Helicopter Adaptive Control With Parameter Estimation Based on Feedback Linearization
,” Vol.
29
, World Academy of Science, Engineering and Technology, Turkey.
6.
Sarim
,
M.
,
Nemati
,
A.
,
Kumar
,
M.
, and
Cohen
,
K.
,
2015
, “
Extended Kalman Filter Based Quadrotor State Estimation Based on Asynchronous Multisensor Data
,”
ASME
Paper No. DSCC2015-9929.
7.
Ray
,
I.
,
1991
, “
ADS Integration Into the Flight Management Computer
,”
FAA, First Annual International Satellite Surveillance and Communication Symposium, Atlantic City, NJ, Sept. 24–26
, pp.
277
280
.
8.
Perry
,
T. S.
,
1997
, “
In Search of the Future of Air Traffic Control
,”
IEEE Spectrum
,
34
(
8
), pp.
18
35
.
9.
Nordwall
,
B. D.
,
1995
, “
Road Map Leads FAA to Free-Flight
,”
Aviat. Week Space Technol.
,
143
(
19
), pp.
34
34
.https://aviationweek.com/awin/road-map-leads-faa-free-flight
10.
Federal Aviation Administration
,
2018
, “
FAA UAS Data Exchange
,” United States Department of Transportation, Washington, DC, accessed Apr. 5, 2018, https://www.faa.gov/uas/programs_partnerships/uas_data_exchange/
11.
Aweiss
,
A. S.
,
Owens
,
B. D.
,
Rios
,
J.
,
Homola
,
J. R.
, and
Mohlenbrink
,
C. P.
,
2018
, “
Unmanned Aircraft Systems (UAS) Traffic Management (UTM) National Campaign II
,”
AIAA
Paper No. 2018-1727
.https://utm.arc.nasa.gov/docs/2018-Aweiss_SciTech_1727.pdf
12.
Jang
,
D.-S.
,
Ippolito
,
C. A.
,
Sankararaman
,
S.
, and
Stepanyan
,
V.
,
2017
, “
Concepts of Airspace Structures and System Analysis for UAS as Traffic Flows for Urban Areas
,”
AIAA
Paper No. 2017-0449.
13.
Balachandran
,
S.
,
Narkawicz
,
A.
,
Muñoz
,
C.
, and
Consiglio
,
M.
, “
A Path Planning Algorithm to Enable Well-Clear Low Altitude UAS Operation Beyond Visual Line of Sight
,”
Twelfth USA/Europe Air Traffic Management Research and Development Seminar
(
ATM2017
), Seattle, WA, June 26–30.http://www.atmseminarus.org/seminarContent/seminar12/papers/12th_ATM_RD_Seminar_paper_16.pdf
14.
Balachandran
,
S.
,
Munoz
,
C.
, and
Consiglio
,
M. C.
,
2017
, “
Implicitly Coordinated Detect and Avoid Capability for Safe Autonomous Operation of Small UAS
,”
AIAA
Paper No. 2017-4484.
15.
Vasirani
,
M.
, and
Ossowski
,
S.
,
2012
, “
A Market-Inspired Approach for Intersection Management in Urban Road Traffic Networks
,”
J. Artif. Intell. Res.
,
43
, pp.
621
659
.
16.
Asep
,
R.
,
Achaibou
,
A.
, and
Mora-Camino
,
F.
,
1996
, “
Automatic Collision Avoidance Based on Supervised Predictive Controllers
,”
Control Eng. Pract.
,
4
(
8
), pp.
1169
1175
.
17.
Mostov
,
K.
, and
Soloviev
,
A.
,
1996
, “
Fuzzy Adaptive Stabilization of Higher Order Kalman Filters in Application to Precision Kinematic GPS
,” Ninth International Technical Meeting of the Satellite Division of The Institute of Navigation (
ION GPS
'96), Kansas City, MO, Sept. 17–20, pp.
1451
1456
.https://www.ion.org/publications/abstract.cfm?articleID=2677
18.
Miura
,
A.
,
Morikawa
,
H.
, and
Mizumachi
,
M.
,
1995
, “
Aircraft Collision Avoidance With Potential Gradient-Ground-Based Avoidance for Horizontal Maneuvers
,”
Electron. Commun. Jpn.
,
78
(
10
), pp.
104
114
.
19.
Reichardt
,
D.
, and
Shick
,
J.
,
1994
, “
Collision Avoidance in Dynamic Environments Applied to Autonomous Vehicle Guidance on the Motorway
,”
Intelligent Vehicles'94 Symposium
(
IVS
), Paris, France, Oct. 24–26, pp.
74
78
.
20.
Tomlin
,
C. J.
,
Lygeros
,
J.
, and
Sastry
,
S. S.
,
2000
, “
A Game Theoretic Approach to Controller Design for Hybrid Systems
,”
Proc. IEEE
,
88
(
7
), pp.
949
970
.
21.
Radmanesh
,
M.
,
Kumar
,
M.
, and
Sarim
,
M.
,
2018
, “
Grey Wolf Optimization Based Sense and Avoid Algorithm in a Bayesian Framework for Multiple UAV Path Planning in an Uncertain Environment
,”
Aerosp. Sci. Technol.
,
77
, pp.
168
179
.
22.
Velastin
,
S. A.
, and
Xu
,
C.
,
1994
, “
Line and Circle Finding by the Weighted Mahalanobis Distance Transform and Extended Kalman Filtering
,”
IEEE International Symposium on Industrial Electronics
(
ISIE' 94
), Santiago, Chile, May 25–27, pp.
258
263
.
23.
Chiang
,
L. E.
,
1994
, “
3-D CNC Trajectory Interpolation Using Bresenham's Algorithm
,”
IEEE International Symposium on Industrial Electronics
(
ISIE'94
), Santiago, Chile, May 25–27, pp.
264
268
.
24.
An
,
P.
,
Harris
,
C.
,
Tribe
,
R.
, and
Clarke
,
N.
,
1993
, “
Aspects of Neural Networks in Intelligent Collision Avoidance Systems for Prometheus
,” Joint Framework for Information Technology, University of Keele, Keele, UK.
25.
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
.
26.
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.
27.
Gurobi Optimization, Inc.
,
2016
, “
Gurobi Optimizer Reference Manual
,” Gurobi Optimization, Beaverton, OR.
28.
Kivelevitch
,
E.
,
Cohen
,
K.
, and
Kumar
,
M.
,
2011
, “
Market-Based Solution to the Allocation of Tasks to Agents
,”
Procedia Comput. Sci.
,
6
, pp.
28
33
.
29.
U.S. Geological Survey, Department of the Interior
,
2018
, “
USGS U.S. Topo 7.5-Minute Map for Cincinnati
,” U.S. General Services Administration, Technology Transformation Service, Cincinnati, OH, accessed May 5, 2018, https://catalog.data.gov/dataset/usgs-us-topo-7-5-minute-map-for-cincinnati-east-oh-2010
30.
Radmanesh
,
M.
,
Kumar
,
M.
,
Nemati
,
A.
, and
Sarim
,
M.
,
2016
, “
Dynamic Optimal UAV Trajectory Planning in the National Airspace System Via Mixed Integer Linear Programming
,”
Proc. Inst. Mech. Eng., Part G
,
230
(
9
), pp.
1668
1682
.