Next Article in Journal
Selection and Optimization of Motor KV Values for Multi-Blade and High-Load Ratio UAVs
Previous Article in Journal
Comparative Assessment of Remote and Proximal NDVI Sensing for Predicting Wheat Agronomic Traits
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Gradient-Guided Search for Autonomous Contingency Landing Planning †

by
Huseyin Emre Tekaslan
and
Ella M. Atkins
*,‡
Kevin T. Crofton Aerospace and Ocean Engineering Department, Virginia Tech, Blacksburg, VA 24061, USA
*
Author to whom correspondence should be addressed.
This paper is an extended version of our paper published in Tekaslan, H.E.; Atkins, E.M. Gradient Guided Search for Aircraft Contingency Landing Planning. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Atlanta, GA, USA, 19–23 May 2025.
These authors contributed equally to this work.
Drones 2025, 9(9), 642; https://doi.org/10.3390/drones9090642
Submission received: 28 July 2025 / Revised: 8 September 2025 / Accepted: 11 September 2025 / Published: 13 September 2025

Abstract

The growing reliance on autonomy in uncrewed aircraft systems (UASs) necessitates a real-time solution for assured contingency landing management during in-flight emergencies. This paper presents a novel gradient-guided search algorithm for risk-aware emergency landing trajectory generation with a wing-lift UAS loss-of-thrust use case. This framework integrates a compact four-dimensional discrete search space with aircraft kinematic and ground-risk cost. A multi-objective cost function is employed, combining flight envelope feasibility, optimal descent, and overflown population risk terms. To ensure discrete search convergence, a constrained hypervolume definition is introduced around the destination. A holding pattern identification algorithm is defined to minimize risk during the necessary flight path angle-constrained descent to final approach. Planner effectiveness is validated through randomly generated case studies over a region of Long Island, NY, under steady wind conditions. Benchmark comparisons with a 3D Dubins solver demonstrate the approach’s improved risk mitigation and acceptable real-time computation overhead. Future development will focus on integrating collision avoidance into the discrete search-based landing planner.

1. Introduction

Uncrewed aircraft systems (UASs) are increasingly being developed with electric vertical takeoff and landing (eVTOL) featuring a lift–cruise configuration that dramatically reduces energy consumption compared to rotorcraft and multicopter designs [1,2]. Cargo transport UASs are expected to have a weight and volume similar to today’s general aviation aircraft, and full integration into the airspace will enable them to utilize existing vertiports and runways. A variety of conditions, ranging from propulsion module failure to unexpectedly low battery energy or fuel, can render any UAS unable to remain aloft long-term. A lift–cruise eVTOL with low battery energy can safely fly longer, with more of a margin, if it remains in a wing-lift (cruise, fixed-wing) configuration, rather than converting to vertical flight. Whether operating in wing-lift mode, in the case of low energy or an eVTOL propulsion unit failure condition, a contingency landing plan can be the safest for the drone and people on the ground below when the UAS relies on wing-lift throughout a stable planned descent to land on a nearby runway. Because UASs can glide without consuming fuel in wing-lift mode, it is the most energy-efficient configuration. Gliding is also feasible, regardless of which propulsion unit fails. Therefore, this paper models the UAS in wing-lift mode during contingency descent to landing. The algorithm’s reliance on aerodynamic gliding and discrete ground-risk data enables autonomous onboard planning for drones conducting logistics, surveillance, or emergency response missions—applications that are becoming increasingly common in densely populated areas [3,4,5].
During urgent or emergency landings, the distressed UAS must deal with whatever winds and weather are present. This work, therefore, focuses on a consideration of a steady wind and flight envelope margin and appropriately assumes that other UASs will avoid collision with the distressed drone as it lands. Path planning for urgent or emergency landing requires a four-dimensional solution that meets strict spatiotemporal constraints and minimizes safety risks. Along with the implementation of degraded wing-lift aircraft performance constraints for flight safety, ground risk is quantified by employing discrete population census data in this paper.
Wing-lift aircraft involve non-holonomic motion constraints that require maintaining forward motion at a minimum (stall) speed and limiting the turn radius. Urgent landing descent paths must avoid obstacles, minimize risk, and align with suitable runways while accounting for steady winds in planning and adjusting to actual variable winds during plan execution. There are several methods for aircraft path planning. However, not all of them are suitable for constrained minimum-risk path planning in complex environments. For instance, although they are fast to compute, geometric solutions such as Dubins paths [6,7,8] solely incorporate path length and curvature metrics. Despite the success of optimal control (OC) and model predictive control (MPC), these methods suffer from initial guess dependency, non-convergence, and low computational efficiency in complex environments [9,10,11,12,13]. The reduced dimensionality that can be achieved through constraints in a search space cannot be applied with OC and MPC. In addition, it is difficult to adapt inherently discrete ground-risk metrics to these methods, as solutions may become stuck at local minima that may not meet feasibility constraints. Similarly, Hamilton–Jacobi–Bellman (HJB) reachability does not scale efficiently due to the curse of dimensionality [14]. Moreover, the HJB value function requires spatial continuous differentiability [15], a requirement that the discrete ground-risk cost violates. Even though such metrics can be approximated by projecting data onto smooth hyperplanes (e.g., Fourier series expansion) this task increases complexity while reducing the data resolution. Note that dynamic cost metric updates, such as ground-risk values derived from mobile phone activity [16] and real-time ground-traffic data [17], render data projection computationally unaffordable for real-time risk quantification as part of contingency planning.
Tree-search-based path planners are well suited for diverse, discrete cost metrics such as ground risk. As an example of related work, Ref. [18] applies a modified A* algorithm to find a shortest feasible path. In [19,20], Monte Carlo tree search was exploited to plan UAS flight paths. A rapidly exploring random tree (RRT) was used in [21,22,23] to safely navigate a space with obstacles. Ref. [24] used pre-calculated maneuvers for emergency landing planning for a gliding aircraft. The Markov decision process (MDP) formulations in Refs. [25,26] focused on uncertainty in aircraft performance and prognostics-based margins, respectively, in emergency landing planning. A three-dimensional A* variant in [27] balanced flight-path and landing-site risk but faced significant complexity challenges when the path length was substantial. This work advances previous search-based and MDP approaches by integrating risk, kinematic, and flight envelope constraints within a solver that efficiently generates feasible long-distance four-dimensional (4D) landing paths. This paper’s approach accounts for operational altitude ranges with a minimum-risk loitering approach and wind effects while maintaining a compact heading-constrained search space.
The discrete search contingency landing planner in this paper adopts a priority queue and operators inspired by the Theta* search algorithm [28] to accommodate flight envelope constraints as a function of steady wind. By fusing feasible path and population risk cost metrics, the presented method simultaneously considers the safety of the landing (e.g., path margin) and risk due to a distressed UAS passing over an urban population. The multi-objective cost function forms a gradient field that significantly reduces state-space exploration thus to minimize computational overhead to support real-time implementation. A constrained 4D position and heading volume around the approach fix is introduced to guarantee search convergence. Since ground risk is negligible at a high altitude, the planner incorporates a three-dimensional (3D) Dubins path solver with a holding point identification scheme to efficiently generate a path to a minimum-risk holding pattern that dissipates altitude. The algorithm’s effectiveness is demonstrated through use cases under steady wind at different initial states. Search-based planning results are benchmarked against 3D Dubins path solvers, evaluating overflown population risk, deviations from optimal gliding trajectories, and computational overhead. The key contributions of this work include the following:
  • Efficient and feasible contingency landing planning with a compact 4D discrete search framework guided by a cost function with a constraint margin gradient field.
  • A constrained hypervolume definition around an approach fix to ensure discrete search convergence.
  • A real-time minimum-risk holding pattern placement algorithm and its integration into contingency landing planning.
  • Assured contingency landing plan generation within a prescribed time limit.
This paper is organized as follows. Section 2 introduces fundamental concepts that this work builds upon, including the gliding flight envelope determination of an aircraft in wing-lift mode, reachability, and geometric path planning. Section 4 and Section 5 present the key components of the contingency landing planner, such as the building blocks of the gradient-guided search incorporating flight feasibility and landing risk assessment with a convergence guarantee. Section 6 details studies over a Long Island, NY, region with a Cessna 182 (C182) model serving as a surrogate for a large eVTOL cargo drone, as in [29].

2. Preliminaries

This section summarizes the principles of wing-lift aircraft flight, reachability, and geometric path planning. These concepts are essential for understanding and developing emergency landing planning procedures.

2.1. Wing-Lift Aircraft Performance

An aircraft in wing-lift configuration is exposed to three fundamental forces [30]: aerodynamic, gravitational, and propulsive, as shown in Figure 1.
A high wing-lift, L, to-drag, D, ratio is the key to efficient fixed wing or “cruise” mode eVTOL flight [32]. Lift is mainly produced by the pressure difference between upper and lower wing surfaces and requires forward flight above a minimum stall speed. In cruise flight, forward thrust, T, generated by propulsion units must counter drag, D, while lift, L, balances the total weight, W. The four primary forces ( L , D , T , W ) define the flight path angle γ , the angle between the ground velocity, v g , and the horizontal plane, with γ = 0 in level flight. The aircraft course angle, denoted as χ , is the angle between north and the horizontal projection of v g .
The best-glide flight path angle in forward flight, γ b g R + , Equation (1), defines the most shallow descent possible without thrust. It is defined by the wing-lift aircraft nonlinear equations of motion, f ( x , u ) , where x and u denote state and control input vectors, respectively.
γ b g = arg max L [ 0 , L m a x ] L D s . t . x ˙ = f ( x , u ) , T = 0
The best-glide for a two-minute standard constant radius turn, γ b g , t R + , under steady wind conditions is as formulated in Equation (2), where the bank angle is μ 0 . An additional inequality constraint [16] on the maximum bank angle μ m a x limits the maximum load factor, L / W , to meet structural integrity constraints.
γ b g , t = arg max C L [ 0 , C L , m a x ] L D s . t . x ˙ = f ( x , u ) , T = 0 , | μ | | μ max | 0
The best-glide angle is important for any emergency situation where an aircraft needs to descend rapidly, even if the engines are still operational but delivering a reduced maximum output.
A good landing begins with a good approach, so it is important to define a stabilized approach speed. Wing flaps are extendable only below the maximum flap extended speed, v F E . The steepest flight path angle, γ m a x R + , for straight gliding, Equation (3), and turning flight, Equation (4), are identified to ensure that the airspeed, v a , is upper-bounded by v F E .
γ m a x = min γ s . t . x ˙ = f ( x , u ) , T = 0 , v a v F E = 0
The steepest gliding angle for turning, γ m a x , t R + , is per Equation (3), where μ 0 .
γ m a x , t = min γ s . t . x ˙ = f ( x , u ) , T = 0 , v a v F E = 0 , | μ | | μ max | 0
The best-glide and steepest-descent flight path angle pair of a C182 [33] are defined as functions of wind speed, v w , and direction, χ w , and obtained as in [17]. Given no forward thrust ( T = 0 ), the best-glide angle, γ b g , represents the shallowest gliding angle an aircraft can fly at without stalling. While aerodynamically efficient, this angle is susceptible to stall due to disturbances such as wind gusts. Conversely, flying at the steepest glide angle, γ m a x , requires a higher approach speed, leading to a longer deceleration path. To balance safety and efficiency during emergency approaches, the flight path angle, γ o p t , is defined per Equation (5), which lies halfway between γ b g and γ m a x . γ o p t offers an optimal safety margin. This value can be adjusted to provide flexibility in the safe landing path descent profile.
γ o p t ( v w , χ w ) = 1 2 γ b g ( v w , χ w ) + γ m a x ( v w , χ w ) γ o p t , t ( v w , χ w ) = 1 2 γ b g , t ( v w , χ w ) + γ m a x , t ( v w , χ w )
For clarity, the flight path angle notation is simplified by omitting its input arguments, i.e., γ · = γ · ( v w , χ w ) . Note that all flight path angles are functions of steady wind conditions, as used to define the aircraft turn radius, R, per Equation (6) [32] for path planning.
R = v a 2 cos γ g cos μ
Here, g and μ are gravitational acceleration and the wing bank angle, respectively.

2.2. Reachable Footprint

For emergency landing, potential landing sites must be identified within a reachable area. This area, known as the reachable footprint [16], is determined by the drone’s capabilities and the specific emergency. For example, a complete loss of thrust limits the reachable footprint to the gliding range, while a medical emergency prioritizes nearby landing sites that are also close to healthcare facilities to minimize the total transit time. Various methods have been proposed to determine the reachable area for distressed aircraft landing. Aircraft dynamics analysis [34,35], optimal control theory [36], and Hamilton–Jacobi methods [37,38] have been employed with different cost/benefit trade-offs. In this paper, the reachability of the target destination is assumed to be confirmed to focus this research effort on path planning to a designated site.

2.3. Geometric Aircraft Path Planning

The Dubins path [6] provides a geometric solution for transitioning between two states while respecting a minimum turning radius constraint. Originally formulated for two-dimensional paths, assuming constant altitude, this solution has been extended to three-dimensional aircraft path-planning applications [8,39,40]. The literature offers several contingency landing management frameworks with Dubins paths. Ref. [7] modified the kinematic model of Dubins paths to include transient effects such as translational and rotational acceleration in emergency path planning. Ref. [41] extends Dubins paths by incorporating real-time updates for dynamically feasible landing plans under degraded aircraft performance. Dubins path and RRT* are fused in [42] to create emergency landing procedures. Ref. [17] incorporated datalink and the Dubins path to coordinate distressed aircraft and ground traffic for road-based emergency landings.
Conventional Dubins path solutions are formed by an initial minimum radius turn segment, a final minimum radius turn segment, and a straight segment connecting tangents of the initial and final turns. There are four options for the turn–straight–turn type of paths: right–straight–right (RSR), right–straight–left (RSL), left–straight–right (LSR), and left–straight–left (LSL). Dubins  [6] also defined solutions with intermediate turns (RLR and LRL), but these are not practical for long-distance traversals between arbitrary configurations. Most Dubins solvers typically evaluate all four path types and select the shortest, assuming constant velocity. Path geometry and length derivations can be found in [30].
To enhance discrete search-based path planning, the proposed algorithm incorporates 3D Dubins path solutions. For instance, Dubins paths can be employed to establish a connection between an initial emergency state and a designated holding point, as well as to link a discrete search-generated trajectory to final approach to the landing runway. Also, S-turn Dubins paths [41] are employed for benchmarking.
UAS state is defined as a tuple , s = ( φ , λ , h , χ ) , where φ Φ , λ Λ , h R 0 , and χ [ 0 , 2 π ) , respectively, correspond to latitude, longitude, the altitude above the mean sea level (MSL), and the course angle. The symbols Φ and Λ denote valid sets of latitude and longitude. The set of all possible states, S , is defined per Equation (7).
S = ( φ , λ , h , χ ) φ Φ , λ Λ ,   h [ 0 , ) , χ [ 0 , 2 π )
Let the initial and final states, respectively, be s 0 S and s N S . A contingency landing path, P S , consists of a sequence of states from s 0 to s N , where P = { s 0 , s 1 , , s N } . A set of Dubins path solutions between arbitrary states, s i and s j , is denoted as D ( s i , s j ) , per Equation (8).
D ( s i , s j ) = { P type type { RSR , RSL , LSR , LSL } }
The shortest Dubins solution, P D , is defined in Equation (9), where L ( P ) is the length of path P .
P D = arg min P D ( s i , s j ) L ( P ) , D ( s i , s j ) , , D ( s i , s j ) =
Note that D ( s i , s j ) ; thus, P D can be an empty set if s j is unreachable, given s i .

3. Problem Statement

Ensuring a safe and feasible contingency landing for UASs in emergency scenarios is a critical problem that demands both efficiency and reliability. The objective of this paper is to present and analyze a contingency landing planner that minimizes risk to the overflown population while ensuring the timely definition of a feasible path. This problem presents several key challenges. First, the feasibility of the landing path is constrained due to the distressed drone’s flight envelope, necessitating a careful assessment of its aerodynamic limitations, given degraded performance. Second, minimizing risk along the trajectory requires an accurate evaluation and incorporation of risk data. Another fundamental challenge lies in the computational complexity of search-based path planning. The need to explore a continuous search space with theoretically infinite extent complicates real-time decision-making and solution convergence guarantees. This trade-off between runtime efficiency, search completeness, and trajectory risk must be carefully managed to ensure a practical implementation. For this study, the following assumptions are made. First, designated landing sites are assumed to be within the aircraft-reachable footprint. Second, this paper assumes a known steady wind throughout the descent to landing.

4. Methodology

This section introduces the contingency landing planner and its building blocks, including a search-based path-planning algorithm, a solution identification criterion, and a method for defining a minimum-risk holding pattern.

4.1. Contingency Landing Path Planning

Because a Dubins solution is purely geometric, risk metrics cannot be considered. A low-flying large UAS in distress poses a risk to an overflown population. However, an aircraft at high altitude poses a negligible risk to people on the ground below because it will fly well past its current position before reaching the ground, even in a steep descent. Discrete search with a population risk metric is, therefore, only useful when the UAS descends below a crossover altitude, h c R > 0 . The handling of high and low altitude cases is illustrated in Figure 2.
In a low-altitude emergency, a discrete search planner generates a low-risk, energy-managed path P s ( s 0 , s N ) from the initial emergency state s 0 to the final search state s N . Final search state s N is constrained to lie in a predefined hypervolume around s N . Then, a final turn to join a final approach path to touchdown state s t is computed with a 3D Dubins path, P D ( s N , s t ) , considering s N as a fly-by waypoint. Note that the exact initial and final states of the Dubins path for the final turn are, respectively, computed via the Dubins path solver between s N and s N , as well as s N and s t , to ensure feasibility with respect to wing-lift aircraft dynamics and kinematic continuity. Formally, a low-altitude solution is defined as follows:
P = P s ( s 0 , s N ) P D ( s N , s t )
In a high-altitude emergency, the distressed aircraft must descend at a flight path angle near γ o p t before initiating an approach to landing. Altitude dissipation is achieved by defining a circular holding pattern with inbound state s h and outbound state s h . The planner identifies the optimal holding pattern location using a utility function specified below. It connects s 0 to s h with the shortest Dubins path, P D ( s 0 , s h ) . The holding pattern is traversed until reaching s h , where a discrete search is initiated to find a low-risk low-altitude landing path to s N . A high-altitude solution can be expressed as follows:
P = P D ( s 0 , s h ) P s ( s h , s N ) P D ( s N , s t )
A transition case arises if h 0 > h c , yet s h is unreachable above h c . Similar to high-altitude cases, a Dubins path is generated from s 0 to s h . The crossover state, s c P D ( s 0 , s h ) , at the crossover altitude on the path to s h is identified. The search-based planner then generates a low-risk path from s c to s N . Then, the solution is finalized with a 3D Dubins path, P D ( s N , s t ) . The solution of a transition case is given as follows:
P = P D ( s 0 , s c ) P s ( s c , s N ) P D ( s N , s t )

4.2. Search-Based Path Planning

A UAS flight envelope defines its safe operating limits. These limits include but are not limited to stalling for controllability, the load factor, and the maximum airspeed for structural integrity. Let the degraded wing-lift aircraft flight envelope A be defined as follows:
A = { ( v a , R , γ , γ t ) all within safe limits }
For a given flight envelope, A , s 0 , and s N , the search space per Equation (7) can be identified using a reachability method. In this study, S is an infinite, continuous, and non-Euclidean space where the distance between arbitrary states is a geodesic distance. Feasible actions for transition from a parent state to successor states are given by a ( s )   =   { a j ( s )     j     Z > 0 } , where j is the branching factor. Each action, a j , is composed of a course angle change, Δ χ , a path segment length, which is the great-circle distance between the parent and successor state, , and optimal straight gliding and turning flight path angles along segment γ and γ t , given a known steady wind.
a j ( s ) = ( Δ χ , , γ , γ t Δ χ X , R + , γ R + , γ t R + )
where X [ 0 , 2 π ] is a set of feasible course angle changes. The set of all feasible actions, A , is per Equation (15), where | A | < .
A = { a ( s ) s S }
For a given aircraft flight envelope, A , set of actions, A , initial and goal states s 0 and s N , state cost function g ( s ) , and steady wind with magnitude v w and direction χ w , the 4D search-based path planning problem T is formulated as in Equation (16), where P s is a non-ascending emergency landing path solution.
P s = { s s = T ( A , A , g ( s ) , s 0 , s N , v w , χ w ) }

4.3. Feasible Actions

The action set must consist only of feasible actions, considering potentially degraded flight envelope constraints. For example, while symmetrical lateral maneuverability can be used for left and right turns, considering airspeed and load factor for a single-engine UAS experiencing loss of thrust, asymmetrical course angle rate limits will be present for aircraft with deteriorated lateral controllability caused by conditions such as a control surface jam [16], structural damage [43], and uneven icing [44]. The minimum segment length for a given arbitrary set of course angle changes is further defined below.
A sketch of sequential turns in the horizontal plane is shown in Figure 3. The minimum segment length, m i n , that can accommodate sequential turns between state s i and s i + 1 is expressed in Equation (17). When expanding state s i , the next state and action are unknown; hence, Δ χ i + 1 can be substituted with the highest possible course change value to ensure feasibility.
m i n = R tan Δ χ i 2 + tan Δ χ i + 1 2
The search algorithm uses an adaptive segment length, Equation (18), that reduces search resolution at higher altitudes where ground risk is minimal to improve real-time performance. This function uses h i , the altitude at s i , h ̲ R + , the floor altitude for the adaptive segment length , and m R + , the rate of segment length change per unit altitude.
i = m i n + m ( h i h ̲ ) , h i > h ̲ m i n , h i h ̲
Per Equation (5), γ o p t and γ o p t , t are determined within A for given steady wind conditions. Therefore, a feasible action, a j , at state s is a function of wind speed v w and wind direction χ w .

4.4. State Expansions

Successor states are generated by expanding parent states. A successor of parent s resulted from the j-th feasible action a j of s is denoted as s j = ( φ j , λ j , h j , χ j ) . The course angle of a successor state, χ j , is
χ j = | χ + Δ χ j | 2 π
where χ s and Δ χ j a j . The operator   .   α wraps an angle at α . The coordinates of a successor state are computed by using the World Geodetic System 1984 (WGS84) [45] model W : R > 0 × R × S Φ × Λ , per Equation (20). Let c ( s ) : S Φ × Λ be an operator, such that c ( s ) = [ φ   λ ] . Simply, W is a function that returns the destination coordinates, given a reference state and action variables.
c ( s j ) = W ( j , χ j s )
The altitude of the successor state h j Equation (21) is computed with a consideraton of turning and straight-gliding traversals where γ . j a j .
h j = h t u r n tan γ o p t , t j ( t u r n ) tan γ o p t j
The turning traversal is denoted as t u r n and calculated as in Equation (17). For convenience, the transition model E : S × A S is specified to apply an action to a state, which composes relations Equations (19)–(21). The set of successors for parent state s is
C ( s ) = { s j s j = E ( s a j ) , a j A } .
Reciprocally, the parent of a successor state is s = π ( s j ) .

4.5. Cost Functions with a Constraint Margin Gradient Field

The path-planning cost function is constructed by four distinct terms: (1) a gradient function to prioritize state expansion with an optimal descent path angle, (2) a gradient function to guide search toward the target location, (3) a gradient function that guides search toward the desired course angle as the target location is approached, and (4) a term that discourages flight over densely populated urban areas. The total cost of a state, g ( s ) , is given in Equation (23).
g ( s ) = w 1 [ ρ ( s ) g d , 1 ( s ) ] + w 2 [ ( 1 ρ ( s ) ) g d , 2 ( s ) ] + w 3 g χ ( s ) + w 4 g p ( s ) , i = 1 4 w i = 1
Here, g d , 1 , g d , 2 , g χ , and g p are, respectively, optimal descent, direct distance, course angle, and population cost functions. Terms w i R 0 are weight coefficients, while ρ ( s ) : S [ 0 ,   1 ] is an adaptive weighting factor. First, common terms used in cost functions are introduced. An approximate shortest path length to the goal is calculated based on a combination of turn and straight sections.
d m i n ( s ) = d g c ( s ) + R | θ ( s , s N ) χ | π
The function d g c ( s ) : S R 0 represents the great-circle distance from state s to s N , where θ : S × S [ 0 ,   2 π ) returns the bearing angle between two states. The remaining best-glide range, d b g ( s ) R 0 , given the altitude loss from s to s N , is defined as follows:
d b g ( s ) = h h N tan γ b g
States with d b g ( s ) < d m i n ( s ) indicate unreachability and are pruned from further expansion. d o p t is defined as an approximate optimal distance to be flown to descend to goal altitude h N from initial altitude h 0 at optimal glide slope γ o p t , initially estimated based on the relative wind between s 0 and s N .
d o p t = h 0 h N tan γ o p t

4.5.1. Optimal Gliding Cost

Two cost functions are employed to encourage progress toward the goal state region. The first function, g d , 1 ( s ) : S [ 0 ,   1 ] , Equation (27), prioritizes the necessary altitude loss to reach the goal state. It serves as a measure of how efficiently the estimated total path length (the first two terms in the numerator) compares to the optimal descent path length. Consequently, it penalizes deviations from the optimal path length caused by deviation from the optimal flight path angle using the heuristics.
g d , 1 ( s ) = | ( s ) + d m i n ( s ) d o p t | d o p t
Here, : S R 0 R 0 is the total path length leading s 0 to s as a function of either state s or time t to reach s, per Equation (28).
( x ) = s ( s ) , x R 4 , t ( t ) , x R 0 .
The cost g d , 1 ( s ) is proven bounded, per Lemma 1.
Lemma 1.
For a non-ascending landing path with γ b g γ , and a UAS whose optimal glide angle satisfies tan γ o p t 2 tan γ b g , the cost function g d , 1 ( s ) is bounded within the closed interval [ 0 ,   1 ] , s S .
Proof of Lemma 1.
The boundedness of g d , 1 ( s ) can be established by analyzing the limits of ( s ) + d m i n ( s ) , given that d o p t is a constant. Given the path slope γ , γ b g γ , a feasible landing path cannot exceed the best-glide range d b g ; hence, the upper bound is as follows:
( s ) + d m i n ( s ) h 0 h N tan γ b g = d b g .
Defining Δ h = h 0 h N and substituting d b g into the expression for g d , 1 ( s ) , one obtains the following:
g d , 1 ( s ) = | ( s ) + d m i n ( s ) d o p t | d o p t | d b g d o p t | d o p t = Δ h / tan γ b g Δ h / tan γ o p t Δ h / tan γ o p t = tan γ o p t tan γ b g 1 .
Given an aircraft flight envelope with tan γ o p t 2 tan γ b g , it follows that
tan γ o p t tan γ b g 1 1
Thus, g d , 1 ( s ) 1 is found. Next, the lower bound is examined. The quantity ( s )   +   d m i n ( s ) attains its minimum if and only if the initial and goal states coincide in latitude and longitude, i.e., c ( s 0 ) = c ( s N ) . Given these conditions, ( s ) = 0 and d m i n ( s ) = 0 , leading to the following:
g d , 1 ( s ) = | d o p t | d o p t = 1
Per Equations (31) and (32), g d , 1 ( s ) is found to be upper-bounded by 1. With a note that g d , 1 ( s ) is non-negative due to the absolute value term in its definition, the following is concluded:
g d , 1 ( s ) [ 0 , 1 ] , s S .
Thus, g d , 1 ( s ) is bounded within the closed interval [ 0 ,   1 ] , completing the proof.    □

4.5.2. Direct Distance Cost

Using only g d , 1 ( s ) ensures that the path follows the optimal length using heuristics, but it can lead to wasted potential energy by expanding nodes away from the goal, particularly in high-altitude emergency cases. To address this, a second function, g d , 2 ( s ) : S [ 0 ,   1 ] , a heuristic estimate for the shortest path to the goal normalized by d o p t , is introduced, per Equation (34). This function prioritizes states that are closer to the goal, regardless of their descent profile.
g d , 2 ( s ) = d m i n ( s ) d o p t
Due to reachability limitations, the optimal flight path angle γ o p t cannot be determined per Equation (5) if d m i n ( s 0 ) > d o p t . In such cases, a shallower flight path angle—optimal for the specific emergency scenario—must be used to ensure reachability, such that d b g ( s 0 )     d m i n ( s 0 )     d o p t . Therefore, the condition 0 d m i n ( s ) d o p t < , s S inherently guarantees the boundedness of g d , 2 ( s ) on a closed interval [ 0 ,   1 ] , eliminating the need for a separate proof.
By weighting g d , 1 ( s ) and g d , 2 ( s ) , the prioritization of expanding states towards the goal and the establishment of the optimal descent profile are balanced. To achieve this balance, upper- and lower-bound radii around s N ; respectively, r ¯ and r ̲ , are specified to calculate ρ ( s ) to limit outward branching. Equation (35) defines r ¯ , while r ̲ is a predetermined constant.
r ¯ = 1 2 ( d o p t + d m i n ( s 0 ) )
The weighting factor is
ρ ( s ) = 0 , d m i n ( s ) r ¯ r ¯ d m i n ( s ) r ¯ r ̲ , r ̲ < d m i n ( s ) < r ¯ 1 , d m i n ( s ) r ̲
Equation (36) guides state expansion toward s N by adjusting the influence of g d , 1 ( s ) and g d , 2 ( s ) , based on the state’s location in the search space. Specifically, according to Equation (23), when s is farther than r ¯ from s N , g d , 1 ( s ) is set to zero, preventing outward branching and conserving excess altitude. This allows the aircraft to later use its potential energy to navigate around densely populated areas. Conversely, when s is closer than r ̲ to s N , g d , 2 ( s ) is eliminated, prioritizing the optimal descent path by managing altitude loss.
To facilitate further analysis, let g d ( s ) be as follows:
g d ( s ) = ρ ( s ) g d , 1 ( s ) + ( 1 ρ ( s ) ) g d , 2 ( s )
Now, the boundedness of g d ( s ) is established in Theorem 1.
Theorem 1.
The weighted sum of g d , 1 ( s ) and g d , 2 ( s ) is bounded within the closed interval [ 0 ,   1 ] , s S .
Proof of Theorem 1.
Per Lemma 1, g d , 1 ( s ) is bounded within [ 0 ,   1 ] . Additionally, by definition, both g d , 2 ( s ) and ρ ( s ) are constrained within [ 0 ,   1 ] . Since g d ( s ) is a convex combination of these bounded functions, it follows that g d ( s ) remains within [ 0 ,   1 ] , s S . The constant weights w 1 and w 2 do not alter the boundedness of the linear combination.    □
Figure 4 demonstrates the evolution of g d ( s ) during path planning. The vector field visualizes the gradient of g d ( s ) , g d ( s ) = [ g d ( s ) / λ   g d ( s ) / φ ] , indicating the preferred direction of state expansion.
Initially, in the upper left figure, where ( s ) = 0 NM, the vector field around state s points away from the goal state. This outward direction of state expansion occurs as g d ( s ) forms a repellent, high-cost region around goal state s N due to d o p t > d m i n ( s 0 ) . As the path planning progresses, the search captures and follows the optimal descent path, as in the upper right and lower left corners. Finally, it converges toward s N by following the minimum cost isoline, as depicted in the lower right figure. If the initial altitude were set lower, the minimum cost region would lie between s 0 and s N due to d o p t d b g , leading state expansion immediately toward s N .

4.5.3. Course Angle Cost

The costs g d 1 ( s ) and g d 2 ( s ) enable a search to reach the goal region, yet they do not reward the desired course angle. It is challenging to match the exact target course with a discrete search. Explicitly incorporating the course angle difference in a cost function would eventually enforce states to only expand parallel to the goal course, which impedes necessary turns to match the goal location. Thus, a course angle cost that represents the preferred direction for approaching the goal state in lieu of exactly matching the landing runway course angle is proposed.
A unit normal vector, n χ N , represented in a north–east–down (NED) coordinate system and aligned with the target course χ N , is used to partition the cost map into regions of higher and lower cost, per Equation (38), where R ( φ , λ ) N E D : Φ × Λ R × R is the transformation operator from a geodetic system to the NED coordinate system.
g ˜ χ ( s ) = n χ N · R ( φ , λ ) N E D ( c ( s ) ) R ( φ , λ ) N E D ( c ( s N ) )
It should be noted that the vector operations in Equation (38) must be in a local coordinate system to eliminate the asymmetrical gradient field with respect to χ N due to the Earth’s curvature. The scalar product in Equation (38) evaluates the projection of the vector from an arbitrary state, s to s N , onto n χ N . A g ˜ χ ( s ) value of zero indicates that s lies on the line perpendicular to n χ N that passes through c ( s N ) , bisecting the search map with a vertical plane. Such states require a 90 ° turn to align with the final course, similar to the common practice in an airport traffic pattern. States with g ˜ χ ( s ) < 0 are located in the region behind the bisecting line and require a course change of less than 90 ° to reach the goal. Conversely, states with g ˜ χ ( s ) > 0 are penalized, as they necessitate a course angle change greater than 90 ° to align with the landing site. Equation (38) is exploited to further define the course angle cost g χ ( s ) , per Equation (39), where κ χ > 0 is a normalization constant to ensure the cost is bounded on the closed interval [ 0 ,   1 ] . The scalar product term is multiplied by distance terms to ensure that distant states can be explored in any direction, while nearby states are restricted to the region behind the bisecting line. The max ( . , . ) operator is introduced to zero out the course angle cost of states with g ˜ χ ( s ) < 0 .
g χ ( s ) = 1 κ χ max 0 , g ˜ χ ( s ) d o p t d g c ( s )
The normalizer κ χ can easily be determined based on the maximum course cost value in the search space S , per Equation (40).
κ χ = sup s S g ˜ χ ( s ) d o p t d g c ( s )
Overall, the max ( . ) operator ensures a lower bound of zero, while κ χ normalizes the upper bound to one, simplifying the need for a boundedness proof for g χ ( s ) on the closed interval [ 0 ,   1 ] .
An illustration of Equation (39) for χ N = 132 ° is shown in Figure 5. The arrows point in the course angle directions, and the vector field of g χ = [ g χ / λ   g χ / φ ] encourages the search algorithm to expand states toward regions where g χ ( s ) = 0 , enabling a feasible final approach.
The function g χ ( s ) alone is insufficient to guide the search to the solution, as it only provides guidance for one half of the horizontal cost map. However, stacking g χ ( s ) on top of g d , 1 ( s ) and g d , 2 ( s ) alters the gradient field direction in the vicinity of the goal state, allowing state expansion in the right direction.
The combined g d , 1 ( s ) , g d , 2 ( s ) , and g χ ( s ) are depicted in Figure 6. In contrast to the solution shown in Figure 4, the state expansion crosses the bisecting line from g ˜ χ ( s ) > 0 to g ˜ χ ( s ) < 0 while simultaneously capturing the optimal descent path.

4.5.4. Population Cost

The population cost is computed by integrating the overflown population density over time. Let the population density function be η ˜ : Φ × Λ R 0 . The function η ˜ is reformulated as a function of time for a known state, per Equation (41), where ∘ is the composition operator. In this paper, the population and land area dataset shared by the U.S. Census Bureau [46] is utilized to obtain population density as a function of time η ( t s , v ) , which will be denoted as η ( t ) for convenience. For population risk estimation, the wind effect is ignored; thus, v = v a .
η ( t s , v ) = η ˜ W v t , χ s   persons / m 2
To reflect the true population risk, a weighting function, w p , 1 ( s ) , Equation (42), is introduced to penalize η under a lower altitude path.
w p , 1 ( t ) = 1 h ( t ) min ( h 0 , h c ) , h ( t ) h c 0 , h ( t ) > h c
Here, the crossover altitude h c is used for the ceiling altitude for population risk consideration. Therefore, population risk is not taken into account for path planning above  h c .
In the case of an emergency, the population residing under a given destination is not a factor, as the aircraft is supposed to be approaching and landing at an airport runway in this work. Thus, the impact of population risk is reduced proportionally to the remaining traversal using a quadratic cost, w p , 2 ( t ) , Equation (43).
w p , 2 ( t ) = 1 ( t ) d o p t 2
Time t is the input argument to Equation (28) for integration purposes.
Let the cumulative overflown population risk to reach s j from s in flight time t be the integration of weighted Equation (41) with respect to time, per Equation (44).
g p ( s j ) = 1 κ p 0 t w p , 1 ( t ) w p , 2 ( t ) η ( t ) d t
Here, the flight time t is estimated using j / v . The boundedness of g p ( s ) depends on the proper scaling by κ p R 0 (45).
κ p = κ w κ η t
Per Equation (45), the population risk is time-averaged and normalized by the upper bound of the weight product κ w = sup w p , 1 ( t ) w p , 1 ( t ) and the maximum population density κ η within the search space S (46).
κ η = sup s S η ˜ ( c ( s ) )
The magnitudes of each cost term must be normalized and/or appropriately weighted in path planning for an unbiased solution. To prove the boundedness of g p ( s ) in numerical implementations, two lemmas are provided.
Lemma 2.
The population density function η ( t ) is Riemann-integrable on [ 0 , T ] .
Proof of Lemma 2.
A function is Riemann-integrable on a closed interval, [ 0 , T ] , if and only if it is bounded and the lower and upper integrals are equal to each other [47].
First, the boundedness of η ( t ) is established. Since η ( t ) represents population density, a physical quantity, it is inherently bounded over the finite time interval [ 0 , T ] . Next, the discontinuities of η ( t ) are taken into account. By its nature, η ( t ) is piecewise continuous. Consider a partition, P = { t 0 , t 1 , t n } on [ 0 , T ] , such that 0 = t 0 < t 1 < < t n = T . The norm of the partition P is
| | P | | = max 0 < i < n { ( t i t i 1 ) }
Let the lower sum S ̲ ( P , η ( t ) ) and upper sum S ¯ ( P , η ( t ) ) of η ( t ) , given the partition P, be
S ̲ ( P , η ( t ) ) = i = 1 n inf { η ( t ) t i 1 < t < t i } ( t i t i 1 ) S ¯ ( P , η ( t ) ) = i = 1 n sup { η ( t ) t i 1 < t < t i } ( t i t i 1 )
The function η ( t ) has a finite number of discontinuities corresponding to discrete transitions (e.g., entering or leaving census blocks). Each discontinuity has zero width. Therefore, it is deduced that
lim P 0 S ̲ ( P , η ( t ) ) = lim P 0 S ¯ ( P , η ( t ) ) = 0 T η ( t )
η ( t ) is Riemann-integrable on [ 0 , T ] .    □
Lemma 3.
There exists a point, * ( t ) ( 0 , d o p t ) , at which the product w p , 1 ( t ) w p , 2 ( t ) attains its maximum value, denoted as κ w R 0 , for h 0 h c .
Proof of Lemma 3.
Substituting h ( t ) = h 0 ( t ) tan γ into w p , 1 ( t ) w p , 2 ( t ) , the product is expressed in terms of ( t ) . To find its maximum, one can take the derivative and equate it to zero:
0 = ( t ) w p , 1 ( t ) w p , 2 ( t ) = 1 ( t ) d o p t tan γ h 0 d o p t 3 ( t ) d o p t
Solving for * ( t ) ,
* ( t ) = d o p t 3
Substituting * ( t ) into w p , 1 ( t ) w p , 2 ( t ) , the upper bound κ w is obtained:
κ w = 4 27 d o p t tan γ h 0
Thus, w p , 1 ( t ) w p , 2 ( t ) is bounded by κ w , completing the proof.    □
Theorem 2.
The population cost g p ( s ) is bounded on the closed interval [ 0 ,   1 ] , s S .
Proof of Theorem 2.
Since w p , 1 ( t ) , w p , 2 ( t ) , and η ( t ) are nonnegative, it is concluded that g p ( s ) 0 . To find the upper bound, consider the magnitude of (44).
| g p ( s ) | = 1 κ p 0 t w p , 1 ( t ) w p , 2 ( t ) η ( t ) d t
The function g p ( s ) is Riemann-integrable, per Lemma 2; thus, the triangular inequality for integrals can be applied to Equation (53) [48]:
| g p ( s ) | 1 κ p 0 t w p , 1 ( t ) w p , 2 ( t ) η ( t ) d t
Using the Cauchy–Schwarz inequality,
| g p ( s ) | 1 κ p 0 t w p , 1 ( t ) w p , 2 ( t ) η ( t ) d t
Per Lemma 3 and Equation (46),
| g p ( s ) | 1 κ p 0 t κ w κ η d t = 1 κ p κ w κ η t = 1
 □
This study implements the R*-Tree [49], a spatial indexing algorithm, to efficiently query population density in real time. The process begins by assigning a unique identification number (ID) to each polygon (i.e., census block) in the dataset. These polygons are then organized hierarchically in an R*-tree. The intermediate nodes store bounding boxes that enclose multiple polygons, allowing for efficient spatial pruning, while the leaf nodes contain the smallest bounding boxes, along with the corresponding polygon IDs.
To perform a query, the R*-Tree first retrieves the smallest bounding box that contains the query coordinate, quickly eliminating large portions of the dataset. Then, a ray-casting algorithm is used to precisely determine which polygon contains the query point among the remaining candidates. Finally, once the correct polygon is identified, its population and land area values are retrieved from a lookup table using the polygon’s ID. The normalized density values are then used in trapezoidal integration. This approach significantly reduces the computational cost of population density queries, making real-time overflown population risk estimation feasible.

4.6. Feasible Solution Identification for Discrete Search

In a 4D discrete search space, reaching an exact goal state, s N , cannot be guaranteed. Therefore, there are two parts of the proposed search algorithm: (1) discrete search to a feasible region around a goal state to identify s N , and (2) a Dubins solver that can always find a geometric solution from the end of the search path to finalize the landing path. Let Z S be the solution identification set, defining the set of feasible final search states. A state, s, is considered final, s N , if and only if the following conditions are met:
  • First, d g c ( s ) must fall within a defined annulus, per Equation (57).
    R i d g c ( s ) R o s . t . 2 R o
    This annulus, centered on s N , is independent of altitude. Ensuring that the outer diameter 2 R o is at least the length of one discrete search segment, , guarantees state expansion within the outer circle. The inner radius R i ensures the feasibility of a Dubins path connecting the search solution to the final approach.
  • Second, the flight path angle of the remaining traversal γ r e m from s N to s N should adhere to the constraints specified in Equation (58).
    γ b g tan 1 h N h N d g c ( s ) γ m a x
    This constraint introduces altitude bounds to Z .
  • Third, s must lie behind s N , such that g χ ( s ) = 0 . This effectively excludes states requiring a significant course angle change to join the final approach.
  • Four, a Dubins path must be feasible from s N to s t .
Formally, the solution identification volume Z is per Equation (59).
Z = { s s S , R i d g c ( s ) R o , γ b g γ r e m γ m a x , g χ ( s ) = 0 , D ( s , s t ) }
The first and third conditions are treated as hard constraints, while modifications to the flight paths are permitted if the second and fourth conditions are not met. If the flight path angle constraints are satisfied, the optimal flight path angle remains unchanged. Otherwise, the gliding angles of both the discrete search and Dubins solutions must be adjusted. However, any such adjustments must ensure that the resulting flight path angle remains within the aircraft’s flight envelope for all segments of the flight. An example of a solution identification set is demonstrated in Figure 7. The volume between steepest-glide and best-glide surfaces defines the states of Z , which holds the potential final search state s N .

4.7. Minimum-Risk Holding Pattern Identification

Optimal holding point identification for UAS emergencies is based on leveraging census population data and geospatial analysis. This process also ensures compliance with safety constraints, such as the avoidance of no-fly zones within search space N S and a sufficient distance from the goal to enable maneuvering. The developed approach involves offline and online parts. The offline part begins by defining the circular area around the goal state, H , Equation (60), to identify candidate holding patterns, considering optimal glide performance.
H = { Δ p Δ p = i = 1 n e i , e i = { ( φ i , λ i ) , ( φ j , λ j ) } , A Δ p > π R 2 , Δ p N = }
Here, H is a set of polygons, Δ p , where e is an edge of a polygon with n edges. Each edge is defined by two vertices in latitude and longitude. The algorithm merges small, scattered polygons into larger polygons with area A Δ p , ensuring that the merged areas meet a minimum threshold defined by the turn radius so that the holding pattern is completely situated inside the polygon. It is worth mentioning that simply filtering out polygons with the minimum area constraint does not necessarily ensure that the remaining polygons can accommodate a holding pattern with a minimum radius of R due to their arbitrary shapes. However, this heuristic step prunes polygons that are unlikely to fit the required holding pattern, thereby reducing online computational overhead. A significant aspect of H is that it can be processed offline and retrieved in real-time from the flight computer.
The online steps of holding point identification include a real-time optimization to find holding pattern center coordinates and utility calculation over candidate holding points. Let a circular left-turn holding pattern be identified with centering state s h Δ p and Δ p H . A holding pattern is evaluated with a utility function, per Equation (61). The maximum values of these metrics are found over the set H .
U ( s h ) = η m a x η ˜ ( c ( s h ) ) η m a x + d m a x d g c ( s h ) d m a x + r h ( s h ) r m a x + g p , m a x g p ( s h ) g p , m a x
The coordinates of s h , c ( s h ) , are determined per Equation (62), which is a real-time optimization solved using [50] in this work.
c ( s h ) = arg max i = 0 n c ( s h ) e i
The radius r h refers to the largest inscribed circle in Δ p Equation (63).
r h ( s h ) = min e i Δ p c ( s h ) e i
The estimated overflown population risk from s h to s N on a straight path is specified by g p ( s h ) , per Equation (44). The best holding pattern, s h * , is identified per Equation (64).
s h * = arg max s h Δ p , Δ p H U
This approach ensures an efficient and robust selection of low-risk holding points for emergency scenarios over urban areas. The holding inbound state is specified in Equation (65).
χ h = θ ( s 0 , s h * ) , c ( s h ) = W ( R , | χ h + 0.5 π | 2 π s h * ) h h = h 0 δ h ( P D ( s 0 , s h ) )
The function δ h : P R > 0 yields the altitude loss along P P . Figure 8 visualizes the hold inbound state determination.
First, the holding outbound state s h is built by determining its altitude, which is set while accounting for the maximum obstacle height h ¯ o within S , the optimal glide distance from s h * to s N , the holding pattern floor altitude h ̲ h , and a buffer, h b u f f e r . The obstacle height data can be found from aeronautical charts.
h h = max h ¯ o , d g c ( s h * ) tan γ o p t , h ̲ h + h b u f f e r
The number of turns n 360 and the net course change Δ χ n e t during holding are given in Equation (67), with Δ h 360 = 2 π R tan γ o p t , t being the altitude loss in a 360 ° turn.
n 360 = h h h h Δ h 360 , Δ χ n e t = 2 π ( n 360 n 360 )
The holding outbound coordinate for a left-hand hold is
c ( s h ) = W ( R , | θ ( s h * , s h ) Δ χ n e t | 2 π   |   s h * )
The outbound course angle, the last element of s h , is found from | χ h + Δ χ n e t | 2 π .

5. Real-Time Contingency Landing Planning Algorithms

This section presents search space discretization and contingency landing planning algorithms.

5.1. Search Space Discretization

Search space S is a continuous infinite set, rendering the search problem T computationally incomplete. A search over a continuous infinite set is not guaranteed to return a solution, P s . To address this issue, S can be discretized into S d using uniform cells and reduced to a discrete finite set of states. Approaches for state-based discretization for search can be found in [51,52].
In this work, discretization is performed in the horizontal plane, altitude, and course angle dimensions. Hexagonal prism cells are used to represent the 3D position discrete state-space s d S d , as illustrated in Figure 9. This choice ensures the efficient tiling of the space, guaranteeing the full coverage of S while providing an upper bound on the size of the discrete search space. However, it is important to note that each hexagonal prism does not correspond to a single state; rather, a single prism represents multiple states, with each associated with a different discretized course angle. Each continuous state, s, within a discrete cell is mapped to a single unique discrete state, s d , which is defined as the centroid of the cell.
An upper bound to the total number of states can be estimated by considering an optimal packing of hexagons into a circle, an approximate footprint. The number of layers of hexagonal cells required to cover the footprint with a radius of r F , per Equation (69), where the circumradius of cells is / 2 .
l = r F 3 / 4 3 / 2
The total number of latitude–longitude pairs needed to completely cover the footprint is as follows:
n ( φ , λ ) = 1 + 3 l ( l + 1 )
The number of discrete course angles and altitude ranges is
n ψ = 2 π Δ ψ , n h = h 0 h N Δ h 360
Therefore, an upper bound to the total number of states is given per Equation (72).
n s = n ( φ , λ ) × n ψ × n h
As a finite search space is obtained, a formal proof for guaranteed convergence can be given.
Theorem 3.
Given a finite discrete search space, S d , a defined solution identification set, Z S d , and assured reachability between arbitrary states s i S d and s j S d , the discrete gradient-guided search from s i to s j is guaranteed to converge to a final state, s N Z .
Proof of Theorem 3.
The state-space S is discretized into a finite set of states with | S d |   =   n s < , ensuring that the search process operates over a well-defined and bounded space. A solution from s i to s j exists, given the reachability assurance.
P ( s i , s j ) S d
Given that the search space is finite and a feasible solution exists, the algorithm is guaranteed to terminate in a discrete feasible state within Z .
lim k n s s k = s N , s N Z
Thus, the discrete gradient-guided search is complete, given the conditions.    □
Figure 9 illustrates an example of S d for underestimated best-glide ranges with n h = 3 and n ψ = 1 . These values are intentionally chosen for visualization purposes and do not reflect the actual space discretization used in the algorithm. The red, green, and blue cells represent increasing altitudes, with n ( φ , λ ) values being 3, 4, and 5, respectively.
Table 1 presents upper bounds on the search space size for an engine-out Cessna 182, considering various altitude differences and segment lengths. As shown, increasing the altitude difference expands the search space, while the longer segment lengths reduce the number of discrete cells.
It should be noted that this structured grid is not directly used for search expansions. The search algorithm expands states based on actions defined in the previous section, and the resulting child states do not necessarily align with the hexagonal cell centers. Instead, each expanded state is assigned as the centroid of a newly generated hexagonal cell at an arbitrary position. Once a cell is explored, its corresponding centroid is stored in a closed list to track visited states and prevent redundant expansions using a point-in-polygon algorithm.

5.2. Contingency Landing Planner

This section describes a contingency landing planning framework consisting of three sequential stages. The first stage constructs an initial set of feasible landing paths using a 3D Dubins path planner formulated with Equation (9) to provide a geometric solution and holding pattern identification governed by Equations (60)–(68) to ensure safe altitude management. This first stage also performs a gradient-guided search based on standard tree search  [53,54] but with a key distinction: it detects repeated discrete states using a geometrical point-in-polygon algorithm, rather than state hashing.
In the second stage, Algorithm 1 implements the handling of different altitude cases by conditionally utilizing the first-stage algorithms. Contingent on the initial emergency altitude, a direct search-based path, P s , is computed, followed by a Dubins connection to the landing site. If the UAS has sufficient altitude, a holding pattern is first executed to dissipate the altitude before transitioning to the final approach descent via successive search- and Dubins-based trajectories.
Algorithm 1 Altitude-dependentpath planning.
Require: A , A , g ( s ) , s 0 , s N , s t , v w , χ w
Ensure: P
   if h 0 h c then
        P s ( s 0 , s N ) T ( A , A , g ( s ) , s 0 , s N , v w , χ w )
        P D ( s N , s t ) arg min P D ( s N , s t ) L ( P )
        P = P s P D
   else
        s h * arg max s h H U
        s h Equation (65)
        P D ( s 0 , s h ) arg min P D ( s 0 , s h ) L ( P )
       if  h h > h c  then
            s h Equations (66)–(68)
            P D ( s N , s t ) arg min P D ( s N , s t ) L ( P )
            P s ( s h , s N ) T ( A , A , g ( s ) , s h , s N , v w , χ w )
            P D ( s N , s t ) arg min P D ( s N , s t ) L ( P )
            P P D ( s 0 , s h ) P s ( s h , s N ) P D ( s N , s t )
       else
            s c arg min s c P D ( s 0 , s h ) | h h c |
            P s ( s c , s N ) T ( A , A , g ( s ) , s c , s N , v w , χ w )
            P D ( s N , s t ) arg min P D ( s N , s t ) L ( P )
            P P D ( s 0 , s c ) P s ( s c , s N ) P D ( s N , s t )
       end if
end if
return P
The final stage executes the contingency landing planner in Algorithm 2, which runs two planners in parallel: (1) the altitude-dependent search-based path planner to define the risk-aware path and (2) a Dubins-based shortest path solver, P D . Since Dubins is a geometrical solution, it enables a real-time response with onboard computing resources for execution as a fallback solution in the case where the search-based path cannot be computed within time limit T m a x R > 0 .
Algorithm 2 Contingency landing path planner.
Require: A , A , g ( s ) , s 0 , s N , s t , v w , χ w , T max
Ensure: P or fallback path P D
1:Initialize runtime t 0
2:Initialize path set P
3:Initialize status flag flag False
4:while  t T max  and  ¬ flag  do
5:    Parallel Execution:
6:       Run Algorithm 1 on Processor-1
7:       Solve Equations (8) and (9) for P D ( s 0 , s N ) on Processor-2
8:    if  P  then
9:        flag ← True
10:    end if
11:     t t + Δ t
12:end while
13:if flag then
14:    return  P ▹Return the minimum-risk path
15:else
16:    return  P D ( s 0 , s N ) ▹Fallback to default path
17:end if
As a result, this framework guarantees that an emergency landing solution can be computed within a prescribed time limit. As described below, the search-based planner typically identifies a solution in time that improves safety using our cost metrics relative to Dubins.

6. Use Cases and Algorithm Benchmarking

This section presents use cases demonstrating the capabilities of the contingency landing planner under varying altitude conditions and steady wind. Descriptive statistics are also provided on the performance of the proposed method in different initial emergency states over a uniform grid. A populated residential area, Farmingdale, Long Island, NY, is chosen to simulate emergency landing scenarios for a large cargo drone operating in urban delivery missions. Therefore, all use cases and tests share the same goal state: a 1 NM final approach fix at 514 ft mean sea level (MSL) altitude to Runway 14 at Republic Airport (KFRG) in Long Island, New York. Table 2 lists user-defined parameters for path planning.
Weight coefficients are used to compute g ( s ) Equation (23) as a function of g χ ( s ) . A state with a high g χ requires a final approach turn greater than 90 ° . To mitigate this, state expansion toward regions where the final course change remains below 90 ° is prioritized. As g χ decreases, w 3 is gradually reduced, thereby shifting the cost emphasis toward the overflown population and distance to the goal. These coefficients are manually fine-tuned through simulations, while a machine learning algorithm can be leveraged for a more streamlined approach.

6.1. Altitude-Dependent Path Planning

The impact of initial emergency altitude on contingency landing solutions is illustrated in Figure 10, where an emergency scenario is simulated at a randomly selected location within the footprint, heading to the east, at altitudes of 4000 ft, 6000 ft, and 10,000 ft MSL.
At a low emergency onset altitude of 4000 ft MSL, Algorithm 1 directly computes the search-based path P s ( s 0 , s N ) and a 3D Dubins path for the final approach to Runway 14 at KFRG, as the initial altitude h 0 is below the crossover altitude h c . The trajectory effectively avoids residential areas by following roads, leveraging the available altitude for risk mitigation. This path is computed with as few as 3709 explored states, dramatically below the upper bound of the search space size of 8.44 × 10 5 for this case.
At a high emergency altitude of 10,000 ft MSL, altitude dissipation is necessary before the approach. A holding pattern is established over a sparsely populated region while maintaining a 0.5 NM no-fly zone around Runway 14 to prevent conflicts with the airport traffic pattern. A 3D Dubins path is then generated from s 0 to s h without considering population risk, as exposure risk at high altitude is minimal due to h 0 > h c . The distressed UAS descends from h h = 7923 ft to h h = 3000 ft over 3.28 full left-hand holding turns. Despite this descent, excess altitude remains as the aircraft approaches s N . The gradient-guided search subsequently determines a descent path to s N that avoids densely populated areas, exploring a total of 320 states. Once the search-based path is generated, a 3D Dubins path is planned from s N to s t .
At an initial emergency altitude of 6000 ft, a holding pattern is also identified. However, unlike the 10,000 ft case, the landing trajectory deviates from the initial Dubins path upon reaching the crossover altitude h c at s c , as the hold inbound cannot be reached above this altitude. From the crossover state s c , gradient-guided search is initialized. Similar to the example in Figure 4, g d , 1 ( s ) leads the minimum cost states away from s N due to the aircraft’s higher altitude relative to the remaining horizontal traversal, causing state expansion away from s N . As altitude decreases, g d , 1 ( s ) shifts the minimum-cost states closer to s N , gradually directing state expansion toward s N . Compared to the low- and high-altitude cases, the landing path found via the gradient-guided search is significantly longer due to the higher crossover altitude; however, P s ( s c , s N ) is computed with a total of 177 explored states, whereas n s = 1.2 × 10 6 . As with the previous cases, the final segment is completed with a 3D Dubins path to s t . The complete 3D contingency landing solution, along with the explored states for the transition case, is shown in Figure 11. The low number of state expansions demonstrates the efficiency of the presented search-based landing planner.
The dynamic feasibility of the low-altitude emergency landing plan is validated using a six-degree-of-freedom engine-out Cessna 182 model [17]. The simulation environment employs a conventional proportional–integral–derivative control system, a fly-by waypoint following for executing the search-based path, and a Dubins guidance manager to achieve final runway alignment. As shown in Figure 12, the lateral tracking error between the planned and simulated trajectories remains minimal, ensuring close alignment between the planned overflown population risk versus simulated overflown population risk. Figure 13 presents the time histories of the flight path angle and airspeed, highlighting constraints in red. Both quantities remain well within the prescribed operational limits. In addition, the maximum and minimum load factors are recorded below 1.1 G and above 0.85 G, respectively, confirming safe flight conditions. Since the simulated landing trajectory encompasses all five action types used in the planning framework, the feasibility of all search-generated sequences is confirmed.

6.2. Contingency Landing Planning Under Steady Wind

With the recollection of Equations (5) and (14), a feasible action depends on wind conditions. A nonzero wind vector alters both the direction and magnitude of the ground speed vector, which in turn affects the required flight path angle to maintain a given airspeed. For path planning, the flight path angle for each segment is selected from a dataset derived from Equations (1)–(4), taking into account wind speed and relative direction.
To illustrate the effect of wind on contingency landing planning, two trajectories are compared in Figure 14.
In this emergency scenario, the aircraft begins at 4000 ft MSL with a 10 knots south wind ( v w = 10 knots, χ w = 180 ° ). In windless conditions, the planned trajectory spans 7.33 NM at a constant optimal flight path angle of 4.4 ° . However, with a partial tailwind, the feasible flight path angle range becomes shallower with an average optimal flight path angle of 4.18 ° , leading to an extended trajectory of 7.73 NM.

6.3. Algorithm Benchmarking on a Uniform Grid

A benchmark study is conducted to evaluate the developed algorithm’s performance in terms of overflown population risk, optimal flight path angle, and computational overhead. The flight time comparison is refrained, as it conflicts with the optimal descent. For contingency landing solutions, the implemented framework is compared against 3D and S-turn Dubins paths. To determine the best Dubins-based solution for low-altitude cases, all possible Dubins path types are evaluated, and the one that minimizes the overflown population risk is selected. Specifically, for lower altitudes, four types of 3D Dubins paths are generated. If additional altitude dissipation is required, S-turn Dubins paths, extending in both directions, are computed, and the one with minimum risk is chosen for comparison.
Test scenarios are distributed across a uniform grid with nine coordinates, three altitude levels, and four cardinal directions, totaling 108 unique cases. All initial states are ensured to be reachable from the goal. Algorithm 1 is compared against the minimum-risk Dubins solutions, with results summarized in Table 3, including descriptive statistics on overflown population risk.
The search-based method consistently outperforms the Dubins-based approach in minimizing overflown population risk across altitude levels. This is expected as the construction of Dubins paths does not offer explicit risk mitigation. Additionally, at sufficiently high initial altitudes, both methods strictly follow the optimal flight path angle. In contrast, at lower altitudes, search solutions maintain this angle without deviation, whereas flight path angles for the four Dubins solutions are flattened (closer to level flight) by an average of 0.21 ° . However, these shallower paths are considered, as they offer minimum-risk solutions.
The framework, along with the benchmarking Dubins path solvers, is programmed in C, with the exception of R*-tree, whose source codes are written in C++ [55]. Table 4 provides a detailed runtime analysis benchmarking search-based path planning against the minimum-risk Dubins solutions. For higher-altitude scenarios, the total elapsed time for optimal holding point identification and the subsequent Dubins path solution to the hold pattern, labeled as hold planning, are also tabulated. Despite being slower than Dubins solutions, as would be anticipated, the developed contingency landing planner exhibits strong potential for real-time implementation. In addition, the separate computation times, g p ( s ) , Equation (44), are provided to highlight its significant contribution to the total computational overhead. As is evident, a high percentage of the total runtime is attributed to the overflown population risk estimation despite an efficient R*-tree implementation. This overhead could be reduced, albeit with a trade-off in accuracy due to interpolation, by reducing the integration time step or employing data projection methods onto uniform grids.
Table 5 presents the solution availability of Algorithm 2 across 108 test cases for different solver time limits. The planner provides search-based minimum-risk landing solutions in 75 out of 108 scenarios within the solver time limit of T m a x = 1 s. When the solver time limit is increased to T m a x = 2 s, search-based landing solutions are found in 102 out of 108 cases. Only four scenarios require fallback Dubins solution when the maximum time limit, T max = 3 s is applied.

7. Discussion

This paper has presented a contingency landing planning framework for a large cargo UAS with wing-lift capability. The proposed approach is adaptable to other emergency scenarios, including but not limited to control surface failures and structural damage by defining the set of feasible actions based on the aircraft’s degraded performance envelope. In addition, the turn radius and flight path angle constraints are applicable to any aircraft capable of wing-lift flight, including hybrid wing-lift configurations. Even multicopters operating with reduced but non-zero thrust could benefit from the proposed approach for risk avoidance. Therefore, the presented method is transferable and can be applied to a wide variety of UAS and crewed aircraft configurations with distinct aerodynamic characteristics.
To estimate the overflown population risk, publicly available population census data was utilized. To improve risk quantification, an interquartile rule for outlier detection was applied. These values were then adjusted to the third-quartile population density, ensuring a more representative risk assessment. Alternative population models might be created and updated with real-time data, e.g., from cellular network call data. Moreover, incorporating obstacle avoidance, real-time weather updates, and air traffic separation is crucial for holistic risk estimation and avoidance.
In general, the number of explored states in the presented use cases remains low. However, it is observed that, when the initial emergency state is located in a densely populated area with a high initial course angle cost, state expansion increases as the algorithm searches for a low-cost trajectory, leading to longer solution times. Additionally, a greater altitude difference between the initial and goal states requires a longer landing path, further increasing state expansion. The gradient-guided search utilizes course angle changes to navigate through narrow, low-risk passages. This is not a concern for UASs with attitude control authority and modern autopilot systems. However, these solutions can only reasonably be shared with unmanned aircraft traffic management systems, air traffic control, and other nearby air traffic via datalink to assure coordinated separation.

8. Conclusions

This paper has presented a real-time emergency landing planner that combines a novel gradient-guided discrete search with 3D Dubins paths to generate safe and risk-aware landing trajectories for wing-lift drone. To further minimize high-altitude risk, a minimum-risk holding pattern identification algorithm was also introduced. A series of 108 Long Island, New York, case studies demonstrated that the presented method significantly reduces risk compared to standard minimum-risk Dubins path solvers. While computationally more demanding, the search-based planner achieved real-time performance, generating minimum-risk landing trajectories within three seconds in 104 out of 108 cases. Future work must consider other air traffic in contingency flight planning solutions to minimize the risk associated with disrupting or losing separation within the low-altitude urban airspace. Such solutions will require awareness of commercial and Advanced Air Mobility airspace corridors and reserved geofence volumes for UAS traffic. To address this, airspace and air traffic avoidance risks will be captured in contingency landing planning by introducing new cost terms within the gradient-guided search framework.

Author Contributions

Conceptualization, H.E.T. and E.M.A.; methodology, H.E.T. and E.M.A.; software, H.E.T.; validation, E.M.A.; formal analysis, H.E.T. and E.M.A.; investigation, H.E.T. and E.M.A.; resources, E.M.A.; data curation, H.E.T. and E.M.A.; writing—original draft preparation, H.E.T. and E.M.A.; writing—review and editing, E.M.A.; visualization, H.E.T. and E.M.A.; supervision, E.M.A.; project administration, E.M.A.; funding acquisition, E.M.A. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by Langley Research Center grant number 80LARC23DA003.

Data Availability Statement

The original contributions presented in the study are included in the article; further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

Nomenclature

A Aircraft flight envelope
A Feasible action set
D Dubins path solution set
DDrag force
L, L m a x Lift force and maximum lift force
P Landing path
P D , P s Shortest Dubins and search-based paths
RAircraft turn radius
R i , R o Annulus radii of the solution identification set
S Aircraft state set
S ̲ , S ¯ Lower and upper sums in the context of integration
TThrust
WTotal weight
Z Solution identification set
aFeasible action
d b g , d o p t Best-glide and optimal gliding traversals
gGravitational acceleration
hAltitude in mean sea level
h 0 , h N , h c Initial, goal, and risk crossover altitudes
h ¯ o , h b u f f e r Maximum vertical obstacle height and a buffer altitude
h ̲ Floor altitude for adaptive segment length
h ̲ h Holding pattern floor altitude
Segment length
m i n , t u r n Minimum feasible segment length and effective arc length
mSegment length change rate per altitude
n 360 Number of full turns in a holding pattern
n s Upper bound to the total number of states
n χ N Unit normal vector of the goal state
r ̲ , r ¯ Lower and upper bound radii around the goal state
sAircraft state
s 0 , s N , s t Initial, goal, and touchdown states
s N Final search state of a converged path
s h * , s h , s h Optimal hold, hold inbound and outbound states
tTime
u Aircraft control input vector
v a , v g Airspeed and ground speed
v F E Maximum flap extended speed
v w Wind speed
w i Cost function weighting coefficients
x , x ˙ Aircraft dynamic state vector and its derivative
χ Course angle
χ w Wind direction
Δ χ Course angle change
γ b g , γ b g , t Best-glide flight path angle for forward and turning flight
γ m a x , γ m a x , t Steepest flight path angle for forward and turning flight
γ o p t , γ o p t , t Optimal flight path angle for forward and turning flight
κ χ , κ w , κ η Cost normalizers
λ Longitude
Λ Valid longitude set
μ Bank angle
Φ Valid latitude set
φ Latitude

References

  1. Bacchini, A.; Cestino, E.; Van Magill, B.; Verstraete, D. Impact of lift propeller drag on the performance of eVTOL lift+ cruise aircraft. Aerosp. Sci. Technol. 2021, 109, 106429. [Google Scholar] [CrossRef]
  2. Mathur, A.; Atkins, E. Multi-Mode Flight Simulation and Energy-Aware Coverage Path Planning for a Lift+Cruise QuadPlane. Drones 2025, 9, 287. [Google Scholar] [CrossRef]
  3. Kim, J.; Atkins, E. Airspace Geofencing and Flight Planning for Low-Altitude, Urban, Small Unmanned Aircraft Systems. Appl. Sci. 2022, 12, 576. [Google Scholar] [CrossRef]
  4. Russell, L.; Goubran, R.; Kwamena, F. Emerging Urban Challenge: RPAS/UAVs in Cities. In Proceedings of the 2019 15th International Conference on Distributed Computing in Sensor Systems (DCOSS), Santorini Island, Greece, 29–31 May 2019; pp. 546–553. [Google Scholar] [CrossRef]
  5. Wu, Y.; Low, K.H. An Adaptive Path Replanning Method for Coordinated Operations of Drone in Dynamic Urban Environments. IEEE Syst. J. 2021, 15, 4600–4611. [Google Scholar] [CrossRef]
  6. Dubins, L.E. On Curves of Minimal Length with a Constraint on Average Curvature, and with Prescribed Initial and Terminal Positions and Tangents. Am. J. Math. 1957, 79, 497–516. [Google Scholar] [CrossRef]
  7. Yomchinda, T.; Horn, J.F.; Langelaan, J.W. Modified Dubins parameterization for aircraft emergency trajectory planning. Proc. Inst. Mech. Eng. Part G J. Aerosp. Eng. 2017, 231, 374–393. [Google Scholar] [CrossRef]
  8. Chitsaz, H.; LaValle, S.M. Time-optimal paths for a Dubins airplane. In Proceedings of the IEEE CDC, New Orleans, LA, USA, 12–14 December 2007; pp. 2379–2384. [Google Scholar] [CrossRef]
  9. Ma, D.; Hao, S.; Ma, W.; Zheng, H.; Xu, X. An optimal control-based path planning method for unmanned surface vehicles in complex environments. Ocean. Eng. 2022, 245, 110532. [Google Scholar] [CrossRef]
  10. Bergman, K.; Ljungqvist, O.; Axehill, D. Improved Path Planning by Tightly Combining Lattice-Based Path Planning and Optimal Control. IEEE Trans. Intell. Veh. 2021, 6, 57–66. [Google Scholar] [CrossRef]
  11. Liu, J.; Han, W.; Liu, C.; Peng, H. A New Method for the Optimal Control Problem of Path Planning for Unmanned Ground Systems. IEEE Access 2018, 6, 33251–33260. [Google Scholar] [CrossRef]
  12. Zhang, K.; Sprinkle, J.; Sanfelice, R.G. A hybrid model predictive controller for path planning and path following. In Proceedings of the ACM/IEEE Sixth International Conference on Cyber-Physical Systems, Seattle, WA, USA, 13–16 April 2015; pp. 139–148. [Google Scholar] [CrossRef]
  13. Shen, C.; Shi, Y.; Buckham, B. Model predictive control for an AUV with dynamic path planning. In Proceedings of the 2015 54th Annual Conference of the Society of Instrument and Control Engineers of Japan (SICE), Hangzhou, China, 28–30 July 2015; pp. 475–480. [Google Scholar] [CrossRef]
  14. Akametalu, A.K.; Tomlin, C.J.; Chen, M. Reachability-Based Forced Landing System. J. Guid. Control. Dyn. 2018, 41, 2529–2542. [Google Scholar] [CrossRef]
  15. Berksetas, D.P. Dynamic Programming and Optimal Control, 3rd ed.; Athena Scientific: Belmont, MA, USA, 2005; Volume 1. [Google Scholar]
  16. Donato, P. Toward Autonomous Aircraft Emergency Landing Planning. Ph.D. Thesis, University of Michigan, Ann Arbor, MI, USA, 2017. [Google Scholar]
  17. Tekaslan, H.E.; Atkins, E.M. Vehicle-to-Vehicle Approach to Assured Aircraft Emergency Road Landings. J. Guid. Control. Dyn. 2025, 48, 1800–1817. [Google Scholar] [CrossRef]
  18. Howlett, J.K.; McLain, T.W.; Goodrich, M.A. Learning Real-Time A* Path Planner for Unmanned Air Vehicle Target Sensing. J. Aerosp. Comput. Inf. Commun. 2006, 3, 108–122. [Google Scholar] [CrossRef]
  19. Qian, Y.; Sheng, K.; Ma, C.; Li, J.; Ding, M.; Hassan, M. Path Planning for the Dynamic UAV-Aided Wireless Systems Using Monte Carlo Tree Search. IEEE Trans. Veh. Technol. 2022, 71, 6716–6721. [Google Scholar] [CrossRef]
  20. Chour, K.; Pradeep, P.; Munishkin, A.A.; Kalyanam, K.M. Aerial Vehicle Routing and Scheduling for UAS Traffic Management: A Hybrid Monte Carlo Tree Search Approach. In Proceedings of the 2023 IEEE/AIAA Conference on Digital Avionics Systems, Barcelona, Spain, 1–5 October 2023; pp. 1–9. [Google Scholar] [CrossRef]
  21. Guo, Y.; Liu, X.; Jia, Q.; Liu, X.; Zhang, W. HPO-RRT*: A sampling-based algorithm for UAV real-time path planning in a dynamic environment. Complex Intell. Syst. 2023, 9, 7133–7153. [Google Scholar] [CrossRef]
  22. Xu, D.; Qian, H.; Zhang, S. An Improved RRT*-Based Real-Time Path Planning Algorithm for UAV. In Proceedings of the IEEE International Conference on High Performance Computing & Communications, Haikou, China, 20–22 December 2021; pp. 883–888. [Google Scholar] [CrossRef]
  23. Kothari, M.; Postlethwaite, I.; Gu, D.W. Multi-UAV path planning in obstacle rich environments using Rapidly-exploring Random Trees. In Proceedings of the IEEE Conference on Decision and Control, Shanghai, China, 15–18 December 2009; pp. 3069–3074. [Google Scholar] [CrossRef]
  24. Sláma, J.; Herynek, J.; Faigl, J. Risk-Aware Emergency Landing Planning for Gliding Aircraft Model in Urban Environments. In Proceedings of the 2023 IEEE/RSJ International Conference on Intelligent Robots and Systems, Detroit, MI, USA, 1–5 October 2023; pp. 4820–4826. [Google Scholar] [CrossRef]
  25. Meuleau, N.; Plaunt, C.; Smith, D.; Smith, T. A POMDP for Optimal Motion Planning with Uncertain Dynamics. In Proceedings of the ICAPS-10: POMDP Practitioners Workshop, Toronto, ON, Canada, 12 May 2010; ICAPS: CA, USA, 2010. Available online: https://www.icaps-conference.org/icaps-executive-council/ (accessed on 24 April 2025).
  26. Sharma, P.; Kraske, B.; Kim, J.; Laouar, Z.; Sunberg, Z.; Atkins, E. Risk-Aware Markov Decision Process Contingency Management Autonomy for Uncrewed Aircraft Systems. AIAA J. Aerosp. Inf. Syst. 2024, 21, 234–248. [Google Scholar] [CrossRef]
  27. Castagno, J.; Atkins, E. Map-based planning for small unmanned aircraft rooftop landing. In Handbook of Reinforcement Learning and Control; Springer: Berlin/Heidelberg, Germany, 2021; pp. 613–646. [Google Scholar]
  28. Daniel, K.; Nash, A.; Koenig, S.; Felner, A. Theta*: Any-Angle Path Planning on Grids. J. Artifical Intell. Res. 2010, 39, 533–579. [Google Scholar] [CrossRef]
  29. Akinola, A.A.; Atkins, E.M. Markov Decision Process Contingency Landing Management Autonomy for Advanced Air Mobility. In Proceedings of the AIAA Aviation Forum and Ascend, Las Vegas, NV, USA, 22–24 July 2025; p. 3399. [Google Scholar]
  30. Beard, R.W.; McLain, T.W. Small Unmanned Aircraft: Theory and Practice; Princeton University Press: Princeton, NJ, USA, 2012. [Google Scholar]
  31. Tekaslan, H.E.; Atkins, E.M. Gradient Guided Search for Aircraft Contingency Landing Planning. In Proceedings of the 2025 IEEE International Conference on Robotics and Automation (ICRA), Atlanta, GA, USA, 19–23 May 2025; pp. 526–532. [Google Scholar] [CrossRef]
  32. Raymer, D. Aircraft Design: A Conceptual Approach, 5th ed.; American Institute of Aeronautics and Astronautics, Inc.: Reston, VA, USA, 2012. [Google Scholar]
  33. Napolitano, M.R. Aircraft Dynamics: From Modeling to Simulation; John Wiley: Hoboken, NJ, USA, 2011. [Google Scholar]
  34. Coombes, M.; Chen, W.H.; Render, P. Reachability Analysis of Landing Sites for Forced Landing of a UAS. J. Intell. Robot. Syst. 2013, 73, 635–653. [Google Scholar] [CrossRef]
  35. Matthew Coombes, W.H.C.; Render, P. Landing Site Reachability in a Forced Landing of Unmanned Aircraft in Wind. AIAA J. Aircr. 2017, 54, 1415–1427. [Google Scholar] [CrossRef]
  36. Arslantaş, Y.E.; Oehlschlägel, T.; Sagliano, M. Safe landing area determination for a Moon lander by reachability analysis. Acta Astronaut. 2016, 128, 607–615. [Google Scholar] [CrossRef]
  37. Kirchner, M.R.; Ball, E.; Hoffler, J.; Gaublomme, D. Reachability as a Unifying Framework for Computing Helicopter Safe Operating Conditions and Autonomous Emergency Landing. IFAC-PapersOnLine 2020, 53, 9282–9287. [Google Scholar] [CrossRef]
  38. Chen, M.; Tomlin, C.J. Hamilton–Jacobi Reachability: Some Recent Theoretical Advances and Applications in Unmanned Airspace Management. Annu. Rev. Control. Robot. Auton. Syst. 2018, 1, 333–358. [Google Scholar] [CrossRef]
  39. Shanmugavel, M.; Tsourdos, A.; White, B.; Zbikowski, R. 3D Dubins Sets Based Coordinated Path Planning for Swarm of UAVs. In Proceedings of the AIAA Guidance, Navigation, and Control Conference, Keystone, CO, USA, 21–24 August 2006. [Google Scholar]
  40. Shanmugavel, M.; Tsourdos, A.; White, B.; Żbikowski, R. Cooperative path planning of multiple UAVs using Dubins paths with clothoid arcs. Control Eng. Pract. 2010, 18, 1084–1092. [Google Scholar] [CrossRef]
  41. Atkins, E.M.; Portillo, I.A.; Strube, M.J. Emergency Flight Planning Applied to Total Loss of Thrust. AIAA J. Aircr. 2006, 43, 1205–1216. [Google Scholar] [CrossRef]
  42. Fallast, A.; Messnarz, B. Automated trajectory generation and airport selection for an emergency landing procedure of a CS23 aircraft. CEAS Aeronaut. J. 2017, 8, 481–492. [Google Scholar] [CrossRef]
  43. Bacon, B.; Gregory, I. General Equations of Motion for a Damaged Asymmetric Aircraft. In Proceedings of the AIAA Atmospheric Flight Mechanics Conference and Exhibit, Hilton Head, SC, USA, 20–23 August 2007. [Google Scholar] [CrossRef]
  44. Lampton, A.; Valasek, J. Prediction of Icing Effects on the Lateral/Directional Stability and Control of Light Airplanes. In Proceedings of the AIAA Atmospheric Flight Mechanics Conference and Exhibit, Keystone, CO, USA, 21–24 August 2006. [Google Scholar] [CrossRef]
  45. National Imagery and Mapping Agency. Department of Defense World Geodetic System 1984, Its Definition and Relationships with Local Geodetic Systems; Technical Report TR8350.2; National Imagery and Mapping Agency: Bethesda, MD, USA, 2000. [Google Scholar]
  46. U.S. Census Bureau. RACE; U.S. Census Bureau: Suitland, MD, USA, 2020. [Google Scholar]
  47. Rana, I.K. An Introduction to Measure and Integration, 2nd ed.; American Mathematical Society: Providence, RI, USA, 2002. [Google Scholar]
  48. Chae, S.B. Lebesgue Integration, 2nd ed.; Springer: New York, NY, USA, 1995. [Google Scholar]
  49. Beckmann, N.; Kriegel, H.P.; Schneider, R.; Seeger, B. The R*-tree: An efficient and robust access method for points and rectangles. SIGMOD Rec. 1990, 19, 322–331. [Google Scholar] [CrossRef]
  50. Johnson, S.G. The NLopt Nonlinear-Optimization Package. 2007. Available online: https://github.com/stevengj/nlopt (accessed on 24 April 2025.).
  51. Bandi, S.; Thalmann, D. Space discretization for efficient human navigation. Comput. Graph. Forum 1998, 17, 195–206. [Google Scholar] [CrossRef]
  52. Henrich, D.; Wurll, C.; Worn, H. Online path planning with optimal C-space discretization. In Proceedings of the IEEE International Conference on Intelligent Robots and Systems, Victoria, BC, Canada, 17 October 1998; Volume 3, pp. 1479–1484. [Google Scholar] [CrossRef]
  53. Russell, S.; Norvig, P. Artificial Intelligence: A Modern Approach, 3rd ed.; Prentice Hall Series; Pearson: Upper Saddle River, NJ, USA, 2010. [Google Scholar]
  54. Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  55. Libspatialindex Contributors. Libspatialindex: A General Framework for Spatial Indexing. 2025. Available online: https://libspatialindex.org/en/latest/ (accessed on 15 February 2025).
Figure 1. Fundamental forces acting in the aircraft longitudinal plane [31].
Figure 1. Fundamental forces acting in the aircraft longitudinal plane [31].
Drones 09 00642 g001
Figure 2. Contingency landing paths for low-altitude, high-altitude, and transition cases. A circular holding pattern is used for high-altitude cases.
Figure 2. Contingency landing paths for low-altitude, high-altitude, and transition cases. A circular holding pattern is used for high-altitude cases.
Drones 09 00642 g002
Figure 3. Planar geometry of sequential turns, the dotted lines indicate constant radius turn geometry [31].
Figure 3. Planar geometry of sequential turns, the dotted lines indicate constant radius turn geometry [31].
Drones 09 00642 g003
Figure 4. An evolution of g d ( s ) with a vector field around the goal state. Red and magenta arrows show the course angles. Black arrows indicate the gradient vector field.
Figure 4. An evolution of g d ( s ) with a vector field around the goal state. Red and magenta arrows show the course angles. Black arrows indicate the gradient vector field.
Drones 09 00642 g004
Figure 5. A map of the course angle cost. The black dashed line illustrates the state-bisecting plane. Red arrows show the course angles. Black arrows indicate the gradient vector field.
Figure 5. A map of the course angle cost. The black dashed line illustrates the state-bisecting plane. Red arrows show the course angles. Black arrows indicate the gradient vector field.
Drones 09 00642 g005
Figure 6. Evolution of the total distance and course angle costs with a vector field around a goal state. Red and magenta arrows show the course angles. Black arrows indicate the gradient vector field.
Figure 6. Evolution of the total distance and course angle costs with a vector field around a goal state. Red and magenta arrows show the course angles. Black arrows indicate the gradient vector field.
Drones 09 00642 g006
Figure 7. A representative solution identification set. Red arrow shows the course angle of the goal state.
Figure 7. A representative solution identification set. Red arrow shows the course angle of the goal state.
Drones 09 00642 g007
Figure 8. Holding inbound state determination.
Figure 8. Holding inbound state determination.
Drones 09 00642 g008
Figure 9. An illustration of a discrete search space in 3D.
Figure 9. An illustration of a discrete search space in 3D.
Drones 09 00642 g009
Figure 10. Contingency landing solutions for varying initial altitudes. Arrows show the course angles.
Figure 10. Contingency landing solutions for varying initial altitudes. Arrows show the course angles.
Drones 09 00642 g010
Figure 11. The 3D contingency landing trajectory and explored state coordinates for the transition case, initially at 6000 ft MSL. Arrows indicate the course angles.
Figure 11. The 3D contingency landing trajectory and explored state coordinates for the transition case, initially at 6000 ft MSL. Arrows indicate the course angles.
Drones 09 00642 g011
Figure 12. Dynamic simulation: a magnified view comparing the plan and simulation trajectory of the low-altitude case.
Figure 12. Dynamic simulation: a magnified view comparing the plan and simulation trajectory of the low-altitude case.
Drones 09 00642 g012
Figure 13. Dynamic simulation: flight path angle and airspeed of an engine-out Cessna 182 in time for the low-altitude case. Shaded areas indicate regions outside the degraded flight envelope.
Figure 13. Dynamic simulation: flight path angle and airspeed of an engine-out Cessna 182 in time for the low-altitude case. Shaded areas indicate regions outside the degraded flight envelope.
Drones 09 00642 g013
Figure 14. The impact of tailwind in the contingency landing solution. Arrows show the course angles.
Figure 14. The impact of tailwind in the contingency landing solution. Arrows show the course angles.
Drones 09 00642 g014
Table 1. Upper bounds of the discrete search space size for the Cessna 182 experiencing loss of thrust.
Table 1. Upper bounds of the discrete search space size for the Cessna 182 experiencing loss of thrust.
h 0 h N [ft] n s for Different Circumradii in ft
50010001500
500 2.88 × 10 4 7.39 × 10 4 2.85 × 10 3
2500 3.30 × 10 6 8.56 × 10 5 3.60 × 10 5
5000 26.2 × 10 6 8.40 × 10 6 4.11 × 10 6
Table 2. Parameters for altitude-dependent path planning.
Table 2. Parameters for altitude-dependent path planning.
ParameterValueUnit
R3000ft
h c 5000ft
X { 30 , 15 , 0 , 15 , 30 }
h ̲ , m 2000, 0.1ft, -
r ̲ 0.5NM
R i , R o 3000, 6000ft, ft
h ̲ h 1000ft
h b u f f e r 2000ft
Δ ψ 5
Weight coefficients as a function of g χ
Condition on g χ Cost Weights
g χ 0.5 ( w 1 , w 2 , w 3 , w 4 ) = ( 0.2 , 0.3 , 0.2 , 0.3 )
10 4 < g χ < 0.5 ( w 1 , w 2 , w 3 , w 4 ) = ( 0.2 , 0.3 , 0.1 , 0.4 )
g χ 10 4 ( w 1 , w 2 , w 3 , w 4 ) = ( 0.2 , 0.4 , 0.0 , 0.4 )
Table 3. Risk and gliding constraint comparison of the gradient-guided search and the minimum-risk 3D Dubins solutions.
Table 3. Risk and gliding constraint comparison of the gradient-guided search and the minimum-risk 3D Dubins solutions.
h 0 [ft]MethodPopulation Risks
Min.Max.Median μ σ
4000Search0.00430.16580.02230.04120.0393
Dubins0.00740.16240.04460.05930.0454
6000Search0.00580.03900.01530.01620.0077
Dubins0.00580.13600.04330.04910.0283
10,000Search0.00850.05940.02390.02540.0124
Dubins0.00500.08350.02440.02780.0164
Table 4. Runtime comparison of the gradient-guided search and the minimum-risk 3D Dubins solutions with a C language code implementation.
Table 4. Runtime comparison of the gradient-guided search and the minimum-risk 3D Dubins solutions with a C language code implementation.
h 0 [ft]MethodTotal Runtime [ms]Risk ( g p ) Computation Runtime [ms]
Min. Max. Median μ σ Min. Max. Median μ σ
4000Search78.44037.7466.3718.9839.977.03239.8428.8631.1680.7
Dubins33.3100.453.357.917.44.949.432.933.110.5
6000Hold Planning83.692.787.487.31.81.36.25.14.41.3
Search99.33891.3598.3852.3869.994.03173.2547.9741.6719.2
Dubins46.292.966.065.310.56.864.353.348.712.8
10,000Hold Planning83.698.988.588.52.61.36.15.24.51.3
Search49.41933.1567.6747.2541.544.21727.5498.5662.7473.4
Dubins16.696.750.748.521.53.421.010.39.84.2
All experiments were conducted on a single performance core of anApple M2 processor (Apple Inc., Cupertino, CA, USA) (ARM64, 3.49 GHz) using Apple Clang 17.0.0 (clang-1700.0.13.5) as the backend compiler.
Table 5. Algorithm 2 solution availability for different time limits.
Table 5. Algorithm 2 solution availability for different time limits.
T max [s] h 0 [ft]Number of Solutions
4000 6000 10,000 Search-Based ( P ) Fallback Dubins ( P D )
12822257533
23433351026
33434361044
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Tekaslan, H.E.; Atkins, E.M. Gradient-Guided Search for Autonomous Contingency Landing Planning. Drones 2025, 9, 642. https://doi.org/10.3390/drones9090642

AMA Style

Tekaslan HE, Atkins EM. Gradient-Guided Search for Autonomous Contingency Landing Planning. Drones. 2025; 9(9):642. https://doi.org/10.3390/drones9090642

Chicago/Turabian Style

Tekaslan, Huseyin Emre, and Ella M. Atkins. 2025. "Gradient-Guided Search for Autonomous Contingency Landing Planning" Drones 9, no. 9: 642. https://doi.org/10.3390/drones9090642

APA Style

Tekaslan, H. E., & Atkins, E. M. (2025). Gradient-Guided Search for Autonomous Contingency Landing Planning. Drones, 9(9), 642. https://doi.org/10.3390/drones9090642

Article Metrics

Back to TopTop