Next Article in Journal
Robust UAV-Oriented Wireless Communications via Multi-Agent Deep Reinforcement Learning to Optimize User Coverage
Previous Article in Journal
Attention-Enhanced Contrastive BiLSTM for UAV Intention Recognition Under Information Uncertainty
Previous Article in Special Issue
Fixed/Mobile Collaborative Traffic Flow Detection Study Based on Wireless Charging of UAVs
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Digital Low-Altitude Airspace Unmanned Aerial Vehicle Path Planning and Operational Capacity Assessment in Urban Risk Environments

College of Civil Aviation, Nanjing University of Aeronautics and Astronautics, Nanjing 211106, China
*
Author to whom correspondence should be addressed.
Drones 2025, 9(5), 320; https://doi.org/10.3390/drones9050320
Submission received: 4 March 2025 / Revised: 3 April 2025 / Accepted: 21 April 2025 / Published: 22 April 2025
(This article belongs to the Special Issue Urban Traffic Monitoring and Analysis Using UAVs)

Abstract

:
This paper proposes a digital low-altitude airspace unmanned aerial vehicle (UAV) path planning method tailored for urban risk environments and conducts an operational capacity assessment of the airspace. The study employs a vertical–horizontal grid partitioning technique to achieve airspace grid-based modeling, classifying and configuring “management-operation” grids. By integrating multi-source heterogeneous data, including building structures, population density, and sheltering factor, a grid-based discrete risk quantification model is established to evaluate comprehensive mid-air collision risk, ground impact risk, third-party risk, and UAV turning risk. A path planning method considering the optimization of the turning points of parallelograms was proposed, and the Parallel-A* algorithm was adopted for its solution. Finally, an airspace operational capacity assessment model and a conflict simulation model for urban risk environments are developed to quantify the operational capacity of urban low-altitude airspace. Using Liuhe District in Nanjing as the experimental area, the study reveals that the environmental airspace risk decreases significantly with increasing flight altitude and eventually stabilizes. In the implementation of path planning, compared with the A* and Weight-A* algorithms, the Parallel-A* algorithm demonstrates clear advantages in terms of lower average comprehensive risk and fewer turning points. In the operational capacity assessment experiments, the airspace capacity across different altitude layers increases with flight altitude and stabilizes after comprehensive risk is reduced. This research provides a theoretical foundation for the scientific management and optimal resource allocation of urban low-altitude airspace, facilitating the safe application and sustainable development of UAVs in urban environments.

1. Introduction

The rapid advancement of urban air mobility (UAM) has led to a growing demand for UAV operations in logistics delivery [1,2,3], emergency response [4,5,6], and inspection tasks [7,8], highlighting the urgent need for airspace fine management in low-altitude environments. Given the challenges posed by multi-source risk coupling, dynamic obstacle interference, and flight efficiency constraints in complex urban low-altitude airspace, establishing a scientifically sound airspace risk assessment framework and achieving safe and efficient path planning have become critical bottlenecks restricting the sustainable utilization of low-altitude resources and the development of intelligent aviation systems.

1.1. Related Prior Work

This section will conduct a review on digital grid airspace modeling, risk assessment, path planning, and airspace capacity assessment. The specific references are listed in Table 1.
In the field of low-altitude digital grid airspace modeling, researchers have established a hierarchical and discretized management foundation. Early studies, such as the AirMatrix 3D air route network [9] proposed by Nanyang Technological University, realized the quantification of airspace capacity and throughput analysis. The grid partitioning scheme based on GeoSOT [10], utilizing a hierarchical encoding mechanism, has facilitated the establishment of dynamic geofences [11] and the detection of flight conflicts [12]. Essentially, the airspace grid system constructs a digital twin of urban airspace, where this discrete representation transforms continuous airspace into addressable computational units. This transformation provides a fundamental foundation for UAV path planning and conflict prediction while serving as a prerequisite for quantifying low-altitude airspace risks.
Low-altitude digital grid airspace modeling offers a spatial framework for the superimposed computation of multidimensional risk fields, driving the evolution of risk assessment methods from traditional collision analysis to multidimensional risk frameworks. Modern approaches decouple risk factors into mid-air collision risk [13,14,15,16,17], ground impact risk [13,14,15,17,18] and third-party risk [16,17]. Airspace grid modeling also facilitates the generation of risk maps, as each grid unit can store and map multiple risk factors. This capability provides an effective tool for UAVs in solving path planning problems, enhancing both safety and operational efficiency.
Based on the risk assessment framework, UAV path planning serves as a strategic bridge between airspace resource management and flight mission execution, with its optimization design directly determining the overall efficiency of low-altitude operational systems. The A* algorithm [19] is a classical path planning method that can identify the optimal route without requiring a complete traversal of the entire grid map. To incorporate risk considerations into path planning, the weighted A* algorithm was introduced [3,20], enabling planned routes to avoid airspace grids with high risk. However, this risk avoidance often results in an increased number of turning points along the planned trajectory. A common approach to mitigating excessive turning points is path smoothing [21,22]. However, trajectory smoothing only softens the boundaries of route inflection points without fundamentally reducing the number of UAV turns, meaning that the risks associated with UAV maneuvers persist.
As a critical component of airspace fine management, airspace capacity assessment is deeply interwoven with the aforementioned grid-based modeling and risk assessment framework. In the field of low-altitude airspace capacity evaluation, researchers have systematically explored strategies for enhancing UAV operational efficiency, safety, and overall system performance through simulation analysis [23,24], topological analysis [25], and modeling optimization [26,27]. Simulation methods [23,24] have played a crucial role in these studies by providing a controlled airspace simulation environment. Through the definition of airspace capacity as the minimum air traffic volume at which phase transitions occur in airspace evaluation metrics (such as conflict rate), simulation-based approaches have established a theoretical foundation for the quantitative analysis of low-altitude airspace capacity.
Table 1. Relevant work of digital grid airspace modeling, risk assessment, UAV path planning, and airspace capacity assessment.
Table 1. Relevant work of digital grid airspace modeling, risk assessment, UAV path planning, and airspace capacity assessment.
TypePaperMethod and StudyCore Contribution
Digital grid airspaceMohamed Salleh et al. [9]AirMatrixPropose the implementation of AirMatrix three-dimensional airway network for the quantitative analysis of airspace capacity and throughput.
Xu et al. [10]GeoSOTIntroduce the hierarchical coding mechanism of grid partitioning for GeoSOT.
Tang et al. [11]GeoSOTResearch on Dynamic Geographical Fence Establishment Based on GeoSOT.
Shi et al. [12]GeoSOTCarry out flight conflict detection based on GeoSOT.
Risk assessmentMartin et al. [13]Mid-Air Collision Risk, Ground Impact RiskA set of procedures for managing the risk assessment of UAVs in both mid-air collision risk and ground impact risk.
Civil Aviation Administration of China (CAAC) [14]Mid-Air Collision Risk, Ground Impact RiskProvide ground impact risk and mid-air collision risk assessment services for CAAC, operation responsible persons of specific types of unmanned aircraft to be operated, service providers of air traffic management and other relevant third parties.
Shao et al. [15]Mid-Air Collision Risk, Ground Impact RiskConduct risk assessment of mid-air collision risk and ground impact risk for UAV logistics delivery scenarios.
Banerjee et al. [16]Mid-Air Collision Risk, Third-Party RiskIt elaborated on the possibility of risk associated with obstacle collision and took into account the influence of abnormal conditions introduced by component failures, reduced controllability, and environmental interference.
Pang et al. [17]Mid-Air Collision Risk, Ground Impact Risk, Third-Party Risk, Risk MapsRisk is quantified by using risk maps. The risk assessment model includes risk of death, property loss and noise impact.
Primatesta et al. [18]Ground Impact Risk,
Risk Maps
Employ risk maps to define the ground risks associated with unmanned aircraft accidents.
UAV path planningAVGC et al. [19]Traditional A*Path planning algorithm based on sampling search.
Zhang et al. [3]Weighted A*Set the risk as the weight to solve the problem of setting up the logistics distribution routes for the “last mile”.
Zhang et al. [20]Weighted A*Establish a risk-based urban airspace environment model, and plan UAVs with low operational risks, low noise levels, and low transportation costs.
Jung et al. [21]Path SmoothingThe problem of generating smooth reference paths was raised under the condition that a finite discrete set of local optimal path families was given.
Wang et al. [28]Path SmoothingAn improved A* algorithm based on the optimization of key point selection and smooth path generation is proposed. The A* algorithm is combined with Bezier curves to process the smoothness of the generated path.
Airspace capacity assessmentBulusu et al. [29]Simulation AnalysisEstimate flight capacity through the assessment of flight conflicts among unmanned aerial vehicles operating in the airspace.
Starita et al. [24]Simulation AnalysisTake into account a large number of traffic scenarios to consider the uncertainties of traffic and capacity supply.
Cho et al. [25]Topological AnalysisThe topology method of setting up access-restricted and exit-restricted geographic fences is adopted for conducting airspace capacity assessment.
Vascik et al. [26]Modeling OptimizationA method of integer programming is proposed to analyze and estimate the capacity of vertical take-off and landing airports.
Zhou et al. [27]Modeling OptimizationIntroduce the traffic dynamics model and solve the capacity of the UAV in both stable and unstable states.

1.2. Our Contributions

In response to the aforementioned issues, this paper proposes a method for digital low-altitude airspace UAV path planning and operational capacity assessment in urban risk environments. The main contributions of this study are as follows:
(1) By making use of the multi-scale grid partitioning of GeoSOT and through hierarchical encoding, the spatial attributes (such as terrain complexity, physical obstacles, etc.) are mapped to a unified spatial reference. This breaks through the limitation of fixed scale of AirMatrix and enables the leap from single-dimensional management of airspace to multi-attribute coupling management.
(2) Previous approaches to airspace risk analysis only took into account environmental risks (mid-air collision risk, ground impact risk, and third-party risk). Based on the establishment of environmental risk maps, this paper further considers the risk of turning points generated by path planning, achieving a joint analysis of environmental risks and planning risks.
(3) Based on the idea of translation optimization, starting from the path structure itself, the Parallel-A* algorithm is designed to optimize the paths planned by the weighted A* algorithm. It changes the original paths and optimizes the number of inflection points.
(4) By applying the simulation analysis method and integrating the path planning algorithm proposed in this question, the assessment of airspace operation capacity is conducted. The Normalized Time Spent in Conflict ( N T S C ) is defined as the number of acceptable conflicts, and the airspace operation capacity is calculated.
In response to these challenges, this study first conducts airspace grid-based modeling and classifies “management-operation” grids for urban low-altitude airspace. A grid-based discrete risk quantification model is then developed, integrating mid-air collision risk, ground impact risk, third-party risk, and UAV turning risk. To optimize UAV flight paths, a parallelogram-based turning point optimization path planning method is introduced, minimizing risk and transportation costs, and solved using the Parallel-A* algorithm. Additionally, an airspace operational capacity assessment model and a conflict simulation model tailored to urban risk environments are established to compute airspace operational capacity. Finally, a series of simulation experiments are conducted using Liuhe District in Nanjing as the case study area.

2. Airspace Grid-Based Modeling

The grid partitioning of urban low-altitude airspace is not merely a technical innovation but represents a fundamental shift in airspace management paradigms. By discretizing continuous low-altitude airspace into computationally addressable and quantifiable independent grid units, this approach enables more refined and systematic airspace management for urban environments. This study proposes a vertical–horizontal grid partitioning method, which first performs vertical and horizontal partitioning to construct a 3D airspace grid. Subsequently, the grids are classified into management-scale and operation-scale categories, with their vertical S v and horizontal dimensions S h configured accordingly based on classification criteria.

2.1. Vertical–Horizontal Grid Partitioning

2.1.1. Vertical Partitioning

Using mean sea level as the reference plane, the study performs vertical partitioning of the low-altitude airspace within the 0–3000 m range. A vertical partitioning is performed at interval S v , generating a set of horizontal airspace layers H s e t :
H s e t = { h 1 , h 2 , , h q , }
where h q represents the altitude of the q -th horizontal airspace layer.
The upper h q _ u p and lower h q _ d o w n boundaries of each horizontal airspace h q layer can be expressed as
h q _ u p = h q + S v 2
h q _ d o w n = h q S v 2

2.1.2. Horizontal Partitioning

Layered flight is a kind of divide and conquer thinking. Through hierarchical management of airspace or tasks, it enables efficient and safe flight planning in complex scenarios and is particularly suitable for multi-aircraft collaboration or high-density airspace scenarios. For horizontal airspace grid partitioning, this study employs a GeoSOT-based approach to partition the horizontal airspace into grids with a side length of S h × S h , resulting in a multi-scale hierarchical grid system. GeoSOT grids [30] represent a form of latitude–longitude partitioning grid system, offering seamless compatibility with existing spatial data frameworks. Table 2 presents the grid sizes and scales corresponding to various levels of the GeoSOT partitioning method.
The vertical–horizontal grid partitioning schematic is illustrated in Figure 1.

2.2. Classification and Configuration of “Management-Operation” Grids

2.2.1. Management-Scale Grids

Management-scale grids are configured based on the administrative boundaries of national, provincial, municipal, and district/county-level airspace management regions. These grids are selected from GeoSOT, the partitioning scale system, to form regional management-scale grids, provincial management-scale grids, municipal management-scale grids, and district/county management-scale grids. The parameter S v can be customized by regional airspace administrators based on the type of airspace management, while S h can be configured according to specific administrative boundaries at different management levels.
The scale S h configuration method is as follows:
Step 1: Acquire the point set P = { p 1 , p 2 , , p n } defining the contour of a given administrative region, where each p i = ( x i , y i ) represents a coordinate in a two-dimensional plane.
Step 2: Compute the minimum bounding square of the point set P , where the side length of the minimum bounding rectangle is denoted as d s q u a r e .
Step 3: Map d s q u a r e to the corresponding grid level n of G e o S O T . The appropriate grid scale S h for level n can be determined using Table 2. The corresponding level n is calculated using the following formula:
n = l o g 2 ( 2 π R D o p r a t i o n )
where R represents the Earth’s radius, set as R 6371000 m.
This article refers to the “Interim Regulation on the Administration of the Flight of Unmanned Aircraft” issued by The State Council of the People’s Republic of China, Central Military Commission of the People’s Republic of China [31], and divides airspace into controlled airspace and uncontrolled airspace. The definition of controlled airspace is the airspace above an altitude of 120 m or more. The airspace prohibited in the air, the restricted airspace in the air, the surrounding airspace, the ultra-low-altitude flight airspace for military aviation, and some other areas [31] should be designated as controlled airspace. And uncontrolled airspace is the airspace outside the controlled airspace. Therefore, in this paper, the management-scale grids are classified into controlled grids and uncontrolled grids.

2.2.2. Operation-Scale Grids

The operation-scale grid is determined based on UAV performance parameters, communication latency, and positioning errors, collectively defining the operation-scale grid’s S v and S h .
(1)
Determination of Vertical Grid Scale
S v can be adjusted according to UAV performance characteristics. This study primarily considers UAV longitudinal dimensions L v _ a i r c r a f t and positioning system errors E l o c a t i o n in the vertical direction, which can be expressed as
S v = L v _ a i r c r a f t + 2 × L l o c a t i o n
(2)
Determination of Horizontal Grid Scale
The horizontal partitioning method for operation-scale grids comprehensively accounts for key factors such as UAV horizontal dimensions, operational parameters, communication latency, and positioning errors. This approach ensures a rational determination of horizontal grid scale for UAV operations in low-altitude airspace. The horizontal grid partitioning scale is jointly determined by UAV horizontal dimensions L h _ a i r c r a f t , positioning system errors L l o c a t i o n , deceleration displacement at maximum velocity L s p e e d C u t , and communication latency displacement L d e l a y , collectively defining the minimum safe separation distance D o for UAVs, which can be expressed as
D o = L h _ a i r c r a f t + 2 × ( L l o c a t i o n + L s p e e d C u t + L d e l a y )
where L s p e e d C u t represents the displacement of a UAV decelerating from its maximum flight speed V m a x to 0   m / s , calculated as
L s p e e d C u t = V m a x 2 2 × a m a x
where a m a x represents the maximum deceleration.
The displacement caused by the time delay t t r a n s in transmitting UAV positioning information to the ground control station or air traffic management platform is given by
L D e l a y = t t r a n s × V m a x
Using Equation (6), map D o to the corresponding grid level n of GeoSOT. The appropriate operational-scale grid size S h for level n can be determined from Table 2.
The vertical–horizontal grid partitioning schematic is illustrated in Figure 2.
The operation-scale grids are divided into two categories: fly-permitted grids and fly-prohibited grids. Fly-permitted grids are those areas within the airspace where UAVs are allowed to enter. Fly-prohibited grids, on the other hand, refer to regions in the airspace where UAVs are prohibited from entering. Fly-prohibited grids mainly include areas such as communication signal blind spots, physical obstacles, buildings, government and military key areas, and special event zones.

3. Discrete Quantitative Risk Assessment Model for Urban Low-Altitude Airspace Grids

The risk assessment of urban low-altitude airspace integrates multi-source heterogeneous data, including urban 3D geographic information, population density, physical obstacles, and UAV parameters, to construct a grid-based discrete quantitative risk assessment model. At its core, this model maps multidimensional risk attributes to individual grid units, generating a low-altitude urban airspace risk heatmap. This study primarily evaluates risk from four perspectives: mid-air collision risk, ground impact risk, third-party risk and UAV turning risk.

3.1. Mid-Air Collision Risk

Mid-air collision risk primarily considers the probability of UAVs colliding with physical obstacles during flight. This study employs the artificial potential field method to assign repulsive forces to physical obstacles [32], where the mid-air collision risk U f i exerted by an obstacle grid f for grid i can be expressed as
U f i = a f 2 × ( 1 d f i 1 d 0 ) 2 , d f i d f 0 , d f i d f
where d f i represents the Euclidean distance between i and f . a f denotes the potential field parameter of f , and d f is the radiation distance threshold of the mid-air collision risk potential field for f .
According to Equation (9), the smaller d f i is, the larger U f i becomes, which increases the risk of mid-air collisions generated by f ; conversely, the larger d f i is, the smaller U f i becomes, reducing the airborne collision risk associated with f . It further explains that the distance between the grid and the physical obstacles shows a negative correlation. Based on this characteristic, the risk of air collision caused by the grid of physical obstacles can be quantified. Specifically, when f itself is 1, U f i = 1 ; for its 1st-order neighborhood grid, U f i = 0.5 ; for the 2nd-order neighborhood grid, U f i = 0.25 ; and for the else grids, U f i = 0 . As shown in Figure 3.
The quantified risk of mid-air collision can be expressed as
U f i = 1 i s e t o w n f 0.5 i s e t 1 s t f 0.25 i s e t s e t 2 n d f 0 i s e t s e t 3 t h f
In environments with a high density of obstacles, grid i may simultaneously be affected by mid-air collision risks from multiple physical obstacles. Therefore, the mid-air collision risk R o b s t a c l e i experienced by grid i is the cumulative effect of the collision risks exerted by all surrounding physical obstacles, which can be expressed as
R c o l l i s i o n i = s u m ( s e t U f i )
where s e t U f i represents the set of mid-air collision risks exerted by physical obstacles on grid i , and s u m ( s e t U f i ) denotes the summation function.
Finally, the mid-air collision risk of the h q layer grid can be calculated through Formula (11), and the risk set s e t c o l l i s i o n can be obtained. Furthermore, all R c o l l i s i o n i in the set need to be subjected to m i n m a x normalization processing through Formula (11), which is as follows:
Q ( x ) = Q ( x ) Q ( x ) m i n Q ( x ) m a x Q ( x ) m i n
where Q ( x ) represents the normalized sub-cost value, Q ( x ) denotes the actual sub-cost value, and Q ( x ) m i n and Q ( x ) m a x correspond to the minimum and maximum sub-cost values, respectively.

3.2. Ground Impact Risk

In this study, ground impact risk refers to the potential threat posed by UAV operations to human safety on the ground. The ground impact risk for a given grid i can be expressed as [3]
R c r a s h i = N p e o p l e i × E n × ( 1 G S i ) × P u a v
where N p e o p l e represents the number of individuals in the impact zone during a UAV crash event; G S is the occlusion factor of the grid, reflecting the exposure level of individuals to UAV operations. The values of the sheltering factor are provided in Table 3. E n denotes the kinetic energy of UAV impact [18], calculated as
E n = m a l l g h q + 0.5 m a l l v 2
where m a l l represents the total mass of the UAV at the time of impact, which includes both the UAV’s own weight m u a v and the payload weight m c a r g o , that is m a l l = m u a v + m c a r g o . In this study, the maximum take-off weight of the UAV is used for m a l l . v represents the flight speed. P u a v represents the crash probability, which can be expressed as
P u a v = 1 1 + α β β E i m p 1 4 × G S = 1 1 + α β β 0.5 × m a l l × v i m p 2 1 4 × G S
where α represents the impact energy causing a 50% fatality rate when G S = 0.5; β denotes the impact energy threshold causing human casualties when G S 0 ; E i m p is the impact energy at the UAV crash site; v i m p 2 is the impact velocity, which can be expressed by the following formula:
v i m p 2 = v x 2 + v y 2 = v x 2 + 2 ( m u a v + m c a r g o ) ρ C d A d r o p + [ 1 e x p h q ρ C d A m a l l ]
Finally, using Equation (13), the risk set s e t c r a s h _ r i s k for h q layer is calculated, with all R c r a s h i within the set normalized using Equation (12).

3.3. Third-Party Risk

Third-party risk primarily considers the risk associated with noise pollution generated by UAV operations. Noise risk refers to the impact of UAV noise on urban residents, necessitating measures to minimize disturbance during urban airspace operations. Noise risk is influenced by three key factors [3]: (1) Noise source, the acoustic energy emitted by UAV propellers during flight. (2) Sound barriers, the ability of obstacles between the UAV and the noise receptor to attenuate sound propagation. (3) Exposure, the number of individuals affected by UAV noise. The noise risk for a given grid can be defined as [33]
R n o i s e i = H A % × ( 1 0.8 G S i ) × A i × N p e o p l e i
where L represents the noise factor; A i denotes the horizontal grid area, calculated as S h × S h ; H A % is the residential annoyance index, expressed as
H A % = 123.81 1 + e x p ( 9.99 0.15 ( L u a v L ) )
where L u a v represents the sound intensity level emitted by the UAV source; L denotes the attenuation of noise, which is dependent on the distance between residents and the UAV flight path, formulated as
L = 10 × l g ( 0.25 × π × h )
where h is the distance between residents and the UAV flight trajectory.
Similarly, using Equation (17), the risk set s e t n o i s e _ r i s k for grid h q layer is calculated, with all R n o i s e i normalized using Equation (11).

3.4. UAV Turning Risk

During UAV flight operations, changes in orientation or turning maneuvers result in energy loss and increased operational risk [34]. To address this, this study defines the UAV turning risk, which quantifies the impact of directional changes on flight safety. Assuming that a UAV performs a turning maneuver while traversing a grid i , the turning risk associated with grid i is defined as
R t u r n i = δ i δ s a f e × R m a x i
where δ i represents the turning angle, δ s a f e denotes the safe turning angle, δ s a f e = 45 ° which is predefined based on urban environmental constraints, and R m a x i is the maximum turning risk, which can be determined according to the maximum allowable turning angle of the UAV, expressed as
R m a x i = δ m a x δ s a f e
where δ m a x represents the maximum turning angle of the UAV.

3.5. Comprehensive Risk

Based on the above risk analysis, the four types of risks can be classified into environmental risks and planning risks. Environmental risks refer to the environmental factors that are planned before the flight path of the UAV, mainly including risks of mid-air collision, ground impact, and third-party risks; planning risks mainly include the turning risks of the UAV during the flight process. The turning risks and planning risks can be expressed as follows:
E i = w 1 × R c o l l i s i o n i + w 2 × R c r a s h i + w 3 × R n o i s e i
W i = R t u r n i
where w 1 , w 2 , and w 3 represent the weights corresponding to the risks of mid-air collision, ground impact, and third-party risk, respectively, and w 1 + w 2 + w 3 = 1 .
From the above, it can be known that environmental risks are pre-existing risks before path planning, while planning risks mainly include the turning risks of the UAV during flight, and the path risks after the UAV’s path planning is completed. Therefore, in this paper, the sum of the pre-existing environmental risks with the planning risks generated after path planning is taken as the comprehensive risk, which can be expressed as
R i = E i + W i

4. Parallelogram-Based Turning Point Optimization Path Planning Method

To optimize UAV route turning points and enhance flight safety and efficiency, this study proposes a UAV route planning method that incorporates turning point optimization. Building upon the Weight-A* [3] algorithm, a Parallel-A* algorithm is designed to apply parallelogram transformation to turning points, effectively reducing excessive inflection points and mitigating associated flight risk hazards in the planned trajectory.

4.1. UAV Path Planning Model

4.1.1. Objective Function

In the layered grid h q , a graph G ( N , E ) exists, where N represents the set of grid points h q , and E represents the set of edges. For low-altitude UAV path planning, the starting grid S and destination grid E have respective center coordinates ( x s , y s , h q ) and ( x e , y e , h q ) . The center coordinates of intermediate grid t along the path are denoted as ( x t , y t , h q ) , where t represents the sequence index of the traversed grids, and t = 1 , 2 , , n 1 , n , and n is the total number of grids in the planned route. The objective function consists of two primary components: airspace risk cost C r i s k _ c o s t and UAV transportation cost C t r a n s _ c o s t .
C r i s k _ c o s t = t = 1 n E t , t 1 = t = 1 n E t + E t 1 2
C t r a n s _ c o s t = t = 1 n ( P t 1 , t )
where P t 1 , t represents the transportation operating cost between t 1 to adjacent grids t , calculated as
P t 1 , t = l t 1 , t × f e × τ ( m c a r g o )
where l t 1 , t is the distance between grid i and its adjacent grid t ; f e represents the cost per unit energy consumption of the UAV [35]. τ ( m c a r g o ) is the payload m c a r g o penalty coefficient [35], defined as
τ ( m c a r g o ) = τ m a x 1 m m a x × m c a r g o + 1
where τ m a x represents the cargo weight carried by the UAV; m m a x denotes the maximum payload capacity of the UAV.
Based on the above definitions, the comprehensive objective function for UAV path planning can be formulated as
m i n C c o s t = ( C r i s k _ c o s t + 1 ) × C t r a n s _ c o s t

4.1.2. Constraints

(1)
Flight Range Constraint
d a i r c r a f t _ m i n l e n ( r S E ) d a i r c r a f t _ m a x
This constraint defines the UAV flight range limitation, ensuring that the planned flight r S E path distance l e n ( r S E ) is neither less than the UAV’s minimum flight range d a i r c r a f t _ m i n nor greater than its maximum flight range d a i r c r a f t _ m a x .
(2)
Turning Angle Constraint
0 δ j δ m a x
This constraint imposes a limit on the UAV’s maximum turning angle, ensuring that, during the path planning process, the UAV’s turning angle δ j does not exceed its maximum allowable turning capability δ m a x .
(3)
Maximum Take-Off Weight Constraint
m u a v + m c a r g o < m m a x
This constraint applies to the maximum take-off mass of the UAV, stipulating m u a v and m c a r g o that the total weight must not exceed the maximum allowable take-off weight m m a x of the UAV.

4.2. Parallel-A* Algorithm

The Weight-A* algorithm can optimize UAV path planning by balancing flight distance and airspace risk, ensuring a safe and efficient trajectory. However, given the complex and dynamic risk environment of urban airspace, the Weight-A* algorithm often increases the number of turning points to avoid high-risk grids, which can reduce flight efficiency and introduce additional risks due to frequent UAV maneuvers. To address this issue, this study proposes an improved A* algorithm based on Weight-A*, namely the Parallel-A* algorithm. This algorithm utilizes an eight-neighbor grid search strategy, integrating risk assessment and transportation cost analysis to optimize the turning points in the planned trajectory. The Parallel-A* algorithm first employs a weighted A* approach to generate an initial UAV flight path, followed by a parallelogram-based turning point optimization, which refine the trajectory and reduce excessive turns.

4.2.1. Initial Path Planning Based on Weight-A*

The cost function for path planning is defined as
f ( t ) = g ( t ) + h ( t )
where g ( t ) represents the actual cost from the starting grid s to the expanded grid t . h ( t ) denotes the estimated cost from the expanded grid t to the destination grid e . In the Parallel-A* algorithm, the actual cost g ( t ) and the heuristic function h ( t ) are formulated as follows:
g ( t ) = ( C r i s k _ c o s t S + 1 ) × C t r a n s _ c o s t S
h ( t ) = ( x e x t ) 2 + ( y e y t ) 2
where C r i s k _ c o s t S and C t r a n s _ c o s t S represent the actual environmental operational risk cost and the route planning risk cost, respectively, incurred from the starting point S to the expanded grid corresponding to the extended flight path; C t r a n s _ c o s t S denotes the actual transportation operating cost from the grid S to the expanded grid t along the extended flight path; x e and y e are the grid e coordinates.

4.2.2. Parallelogram-Based Turning Point Optimization

Since the A* algorithm [36] is constrained by grid resolution and directional limitations, it relies on h ( t ) Euclidean distance to search for and determine an optimal path. As shown in Figure 4, due to the proximity between b and f adjacent grids, the UAV will perform turning maneuvers at points a and b , leading to an excessive number of turns in the planned route. To address this issue, this study considers the risk variation during UAV route segment translation and applies a parallelogram transformation method to optimize the initially planned turning points, thereby reducing unnecessary turns in the trajectory.
As shown in Figure 5a, the flight segment can be identified a b / / c d , indicating that the segment a b is eligible for parallelogram transformation. When either a b or b c satisfies
a b / / c d   a n d   ( l e n ( a b ) l m a x   o r   l e n ( b c ) l m a x )
where l m a x represents the maximum allowable translation distance for segment shifting; l e n ( a b ) denotes the Euclidean distance between turning points a and b . When the above conditions hold, a parallel translation is applied to segment a b and b c , as illustrated in Figure 5b.
The steps parallelogram-based turning point optimization considering risk cost are as follows:
Step 1: Compute the initially planned flight segment set s e g m e n t _ p a t h _ i n i = { s 1 , s 2 , , s n } , where s n belongs to the planned route. Establish a new flight segment set s e g m e n t _ p a t h _ n e w = { } , and move to Step 2.
Step 2: Determine the number of segments in s e g m e n t _ p a t h _ i n i . If the number of segments is greater than 3, proceed to Step 3. Otherwise, add the segment from s e g m e n t _ p a t h _ i n i to s e g m e n t _ p a t h _ n e w and move to Step 7.
Step 3: Identify the first set of consecutive segments a b , b c and c d in s e g m e n t _ p a t h _ i n i . If the segments satisfy Equation (36), proceed to Step 4; otherwise, move to Step 5.
Step 4: Extract the grid point set s e t i n i corresponding to the initial segments a b and b c , and apply a parallel transformation a b 1 and b 1 c to their respective grid points s e t t r a n s . Compute the risk cost for the s e t i n i and s e t t r a n s using the formula
R i s k s e g = ρ = 1 M E ρ M
where M represents the total number of grid points in the path segment. If grid ρ is classified as a restricted no-fly zone, then R i s k s e g = + . Using Equation (37), compute the risk values for both the original R i s k s e g _ i n i and transformed segments R i s k s e g _ t r a n s , then move to Step 5.
Step 5: If R i s k s e g _ i n i R i s k s e g _ t r a n s , apply the parallelogram transformation and add the a b 1 transformed segment to s e g m e n t _ p a t h _ n e w , move to Step 2. Otherwise, move to Step 6.
Step 6: Add a b to the s e g m e n t _ p a t h _ n e w and remove a b from s e g m e n t _ p a t h _ i n i , then repeat Step 2.
Step 7: End the transformation process.
The detailed algorithm flowchart is illustrated in Figure 6.

5. Airspace Capacity Assessment Method

This section conducts a modeling and analysis of urban low-altitude airspace operational capacity under free airspace conditions. The study utilizes the Parallel-A* algorithm to generate random UAV flight paths, providing a basis for capacity evaluation.

5.1. Airspace Operational Capacity Assessment Model

This study employs the Normalized Time Spent in Conflict ( N T S C ) [23] metric to quantify the acceptable level of airspace conflicts, with the UAV count corresponding to an acceptable N T S C value defined as the airspace capacity. N T S C is defined as the cumulative ratio of conflict duration to total flight time across all UAVs operating within the airspace, expressed as
N T S C = 1 K i = 1 n t i c t i
where K represents the total number of UAV flights; t i denotes the total flight duration of the i -th UAV; t i c represents the total conflict time during which the i -th UAV encounters grid conflicts with other UAVs at the same moment. The grid conflict time refers to the duration required for a UAV to travel from the grid boundary to the grid center during its flight.

5.2. Conflict Simulation Model

The conflict simulation model operates within a predefined airspace grid and randomly generates non-repetitive UAV flight origin–destination pairs based on the number of simulated UAV flights per scenario. The Parallel-A* algorithm is employed to generate UAV flight paths. This study evaluates hourly airspace operational capacity by assigning a uniform take-off time for each UAV, formulating flight plans, and conducting simulation flights. Finally, calculate N T S C and adjust the number of drone simulation flights based on N T S C to obtain the final airspace operational capacity. The specific process is shown in Figure 7.

6. Experimental Analysis

6.1. Parameter Configuration

All the simulation experiments in this paper were conducted on a workstation equipped with an Intel(R)core(TM)i7-11800H CPU (This equipment manufacturer is Intel Corporation and it was sourced from Nanjing, China) and NVIDIA GeForce RTX 3060 Laptop(This equipment manufacturer is NVIDIA Corporation and it was sourced from Nanjing, China). For simulation analysis, this study selects geographic elevation data from Liuhe District, Nanjing. The designated airspace range is set as follows: Longitude is 118.77 ° E 118.87 ° E , latitude is 32.29 ° N 32.39 ° N , altitude is 15 m–205 m. Considering the spatial occupation in the airspace grid environment, the buildings and terrain features of Honglou District, Nanjing City are taken into account. The detailed parameters of the airspace grid environment are shown in Table 4. The UAV of ARK-40 was selected for simulation analysis (the parameters of the unmanned aerial vehicle are shown in Table 5). During the simulation process, all the parameters of the unmanned aerial vehicle were the same, and the meteorological conditions factors such as wind force and visibility parameters all met the flight requirements of the ARK-40. Table 5 also lists the S v and S h of ARK-40. To facilitate subsequent experiments, the S h is set to 10 m.

6.2. Risk Analysis

6.2.1. Basic Information Distribution Maps

This section presents the basic information distribution maps, covering the spatial distribution of physical obstacles, sheltering factor, and population density. The visualization results are illustrated in Figure 8. Furthermore, the variation of the physical obstacles with the altitude layer is presented, as shown in Figure 9. This data represents the ratio of the number of grid cells occupied by physical obstacles at each h q layer to the total number of grid cells at that layer. Figure 8a shows the 3D geographic base map of Liuhe District, constructed using high-resolution remote sensing imagery. Figure 8b presents the physical obstacle distribution model, which quantitatively represents the spatial topology of buildings, transmission towers, and other 3D structures. Figure 9 indicates a significant negative correlation between obstacle density and altitude. When the flight altitude reaches a critical threshold of 115 m, no physical obstacles exist within the airspace. This threshold provides a key reference for airspace safety planning. Figure 8c illustrates the occlusion distribution map, composed of the sheltering factor defined in Table 3. Figure 8d displays the population density distribution map. The combined analysis of occlusion distribution and population density serves as an important foundation for modeling ground impact risk and third-party risk.

6.2.2. Environmental Risk Maps

This study employs a stratified sampling method to segment the 15 205 m airspace into 10   m vertical layers, enabling a detailed analysis of environmental risk distribution across different altitude levels. Figure 10 illustrates the spatial characteristics of environmental risk distribution at various altitude h q = 15   m , 55   m , 95   m , 135   m layers. Regarding the weights assigned to the risks of mid-air collision, ground impact, and third-party risk, this paper takes into account that ground impact will cause casualties. In line with the principle of prioritizing life, the weight of ground impact risk will be higher than that of mid-air collision risk and third-party risk, that is, w 1 = 0.25 , w 2 = 0.5 ,   w 3 = 0.25 [17]. Data analysis reveals that the highest risk levels are observed at h q = 15   m altitude layers, exhibiting a strong positive correlation with the spatial distribution of physical obstacles. As flight altitude increases, obstacle density decreases exponentially. When flight altitude reaches a certain threshold h q = 135   m , the system monitoring results indicate that all architectural obstacles disappear, leading to a shift in risk composition. At higher altitudes, mid-air collision risk is significantly reduced, and ground impact risk, caused by UAV system failures, along with noise-related third-party risk, become the dominant risk factors. The environmental risk gradient curve in Figure 11 further quantifies this trend: risk values decrease with increasing flight altitude. When h q > 115   m the risk index stabilizes around the 0.15 threshold; airspace above 115 m exhibits low environmental risk, making it an optimal altitude range for UAV operations. This is also consistent with the current policies on UAVs in China [14] (where the airspace below 120 m is suitable for UAV flights), the United States [37] (where commercial UAVs are usually restricted to a height of 400 feet ≈ 122 m), and the European Union [38] (where open categories are limited to a height of 150 m (C0)).

6.3. Path Planning Analysis

6.3.1. Parameter Analysis

In order to demonstrate the influence of different types of risk cost on the Parallel-A* algorithm, we conducted four sets of path planning simulation analyses at the level of h q = 105   m . The specific designs of these four analyses are as follows: (1) Path 1: Without considering any risks, it degenerates into the A* algorithm; (2) Path 2: Considering only the risk of ground impact, that is, w 1 = 0 , w 2 = 1 ,   w 3 = 0 ; (3) Path 3: Considering only the risk of ground impact, that is, w 1 = 0.5 , w 2 = 0.5 ,   w 3 = 0 ; (4) Path 4: Taking into account all three types of risks, that is, w 1 = 0.25 , w 2 = 0.5 ,   w 3 = 0.25 . In the four path scenarios, except for Path 1, since the risk of ground impact involves personal safety and property loss, the simulation analysis of different parameters for the remaining paths also involves the risk of ground impact. The parameter settings for Path 2 are mainly oriented towards suburban scenes in open areas. The parameter settings for Path 3 mainly consider commercial areas without considering risks such as noise from third parties. The parameter settings for Path 4 mainly consider residential areas. Four sets of simulation analyses conducted 100 random path planning experiments, respectively, obtaining the average comprehensive risk R ¯ p a t h along the route and the average number of turning points T ¯ p a t h . The results are shown in Table 6. The specific formulas are as follows:
R ¯ p a t h = p = 1 N R p a t h p N
T ¯ p a t h = p = 1 N T p a t h p N
where N represents the total number of path planning iterations; R p a t h p and T p a t h p denote the comprehensive risk value and number of turning points for the p -th planned route, respectively, which can be expressed as
R p a t h p = i = 1 l e n ( p a t h ) R i
R p a t h p = i = 1 l e n ( p a t h ) 2 a n g l e [ i , i + 1 , i + 2 ]
where l e n ( p a t h ) represents the total number of grid points in the planned path p , and a n g l e [ i , i + 1 , i + 2 ] denotes the angle formed between adjacent grid points a b c , ( i , i + 1 ) and ( i + 1 , i + 2 ) , while when i , i + 1 , i + 2 = 180 ° , a n g l e [ i , i + 1 , i + 2 ] = 0 , and i , i + 1 , i + 2 < 180 ° , a n g l e [ i , i + 1 , i + 2 ] = 1 .
From Table 6, it can be seen that Path 1 has a relatively high R ¯ p a t h ; due to the consideration of the risk of ground impact, when conducting the Path 2 path planning experiment, the densely populated areas were avoided, and its R ¯ p a t h decreased by 38%; when the risk of air collision was added, the Path 3 simulation experiment also avoided the densely populated solid obstacle areas, and its R ¯ p a t h decreased by 45%; Path 4 considered all three types of risks, and compared with Path 3, the R ¯ p a t h of Path 4 was further reduced by 5%. In addition, it can also be seen that as the number of risk types increases, the complexity of risks within the airspace environment further increases, and the value of T ¯ p a t h gradually rises. This is due to the avoidance of high-risk areas during path planning. This experiment verified the optimization effect of integrating multiple risk types on path safety.

6.3.2. Algorithm Comparison

The Parallel-A* algorithm proposed in this study exhibits multi-dimensional optimization characteristics in path planning, enabling it to avoid obstacles, high-risk areas, and reduce the number of turning points. This paper also compares the A* algorithm and the Weight-A* algorithm as the control group and conducts experimental analysis with h q = 105   m . The schematic diagram of the path planning result is shown in Figure 12. As can be seen from Figure 12, the A* algorithm, due to its sole consideration of the Euclidean distance cost, has the potential safety hazard of crossing high-risk airspace in its planned path; although the Weight-A* algorithm improves the safety of the path through the risk-avoidance strategy, it has a large number of turning points; the Parallel-A* algorithm constructed in this paper has fewer turning points than the Weight-A* algorithm and avoids high-risk areas.
This paper also conducted 100 independent random experiments for A*, Weight-A*, and Parallel-A*, respectively, under the condition of h q = 105   m , as shown in Table 7. Based on the ANOVA method, the significance test was conducted on the comprehensive risks and the number of turning points of the three algorithms. The results showed that there were extremely significant differences in both sets of indicators (comprehensive risk: F = 9.67 , p = 8.49 × 10 5 ; number of inflection points: F = 133.95 , p = 3.43 × 10 5 ). Specifically, the Parallel-A* algorithm ( 1.20 ± 0.92 ) outperforms all others in terms of the comprehensive risk. Its comprehensive risk is significantly lower than that of the Weight-A* ( 1.66 ± 1.27 ) algorithm and the A* ( 2.42 ± 3.00 ) algorithm. In terms of the number of turning points, the number of turning points of the Parallel-A* algorithm ( 9.6 ± 4.52 ) is lower than that of the Weight-A* algorithm ( 15.11 ± 7.23 ) . In summary, this experiment demonstrates that the Parallel-A* algorithm can significantly reduce the number of path turning points while lowering the comprehensive risk, verifying its superiority over traditional algorithms.
Figure 13 and Figure 14 illustrate the trends in average comprehensive risk and the number of turning points for the A*, Weight-A*, and Parallel-A* algorithms at varying altitude levels. From Figure 13, it is evident that as altitude increases, the average comprehensive risk of all three algorithms gradually decreases. Notably, at all altitude levels, the Parallel-A* algorithm maintains the lowest average comprehensive risk, demonstrating superior safety performance. From Figure 14, the A* algorithm consistently exhibits the lowest number of turning points throughout the experiment. This is because the A* algorithm does not consider risk factors in path planning, resulting in fewer turns along the trajectory. Among the risk-aware algorithms, Parallel-A* and Weight-A*, the proposed Parallel-A* algorithm consistently produces fewer turning points than the Weight-A* algorithm, indicating a more efficient path structure. In conclusion, the analysis of R ¯ p a t h and T ¯ p a t h confirms that the proposed Parallel-A* algorithm achieves fewer turning points and lower comprehensive risk, demonstrating high safety and operational efficiency in UAV path planning.

6.4. Analysis of Low-Altitude Airspace Operational Capacity

As can be seen from Section 6.3, the Parallel-A* algorithm designed in this paper has low risks and few inflection points. Therefore, based on the Parallel-A* algorithm, this paper also generates UAV flight paths with low comprehensive risks for conducting airspace operation capacity assessment. Due to the fact that UAV flight involves different operational scenarios and the differentiated management requirements of low-altitude flight management service departments, the N T S C threshold can be dynamically adjusted according to specific needs. Therefore, this paper provides an analysis of airspace operation capacity under different thresholds. Figure 15 analyzes the situation of the airspace operation capacity varying with h q [ 45   m , 205   m ] under different conflict thresholds ( N T S C = 0.05 , 0.01 , 0.015 , 0.020 , 0.025 , 0.03 ). To facilitate a better analysis, Figure 15 also presents the variation of R i with h q . As can be seen from Figure 15, at the same h q , the increase of N T S C will further enhance the capacity of spatial operation. Furthermore, as h q increases, the spatial operation capacity of the same spatial domain under N T S C will increase accordingly and become stable. When the number of physical obstacles in the spatial domain is zero (that is, when h q is around 115 m), the spatial capacity will tend to stabilize. It can also be observed that the trend of airspace operation capacity and R i is opposite. The smaller R i is, the greater the airspace operation capacity will be. This phenomenon indicates that the airspace operation capacity will increase as the overall risk of airspace decreases.

7. Conclusions

This study develops a digital low-altitude airspace grid-based model tailored for urban risk environments, focusing on UAV path planning and operational capacity assessment. By constructing management-scale and operation-scale grids of vertical and horizontal partitioning, integrating multi-source data such as urban 3D geographic information, population density, and parameters of UAV, a risk discretization quantitative assessment model was established. The risks of mid-air collision, ground impact, third-party risk, and turning risk of unmanned aerial vehicles were systematically analyzed. To enhance the flight efficiency of UAVs and reduce risks, a method for optimizing a parallelogram-based turning point optimization path planning method considering both risks and transportation costs was proposed. The Parallel-A* algorithm was established to solve the path. Furthermore, an airspace operational capacity assessment model and a conflict simulation model are established based on the Parallel-A* algorithm, providing a theoretical foundation for airspace capacity estimation in urban low-altitude airspace under risk conditions.
Using Liuhe District, Nanjing as the experimental area, this study analyzes the impact of buildings, sheltering factor, and population density on UAV operations and validates the effectiveness of the proposed method through simulation experiments. The results indicate that as altitude increases, the comprehensive risk gradually decreases and stabilizes. In the four sets of path planning analyses under different risk parameters, the path planned by comprehensively considering the three types of risks has the smallest comprehensive risk, which verifies the optimization effect of integrating multiple risk types on path safety. In the comparative experiments of different path planning methods, the algorithm proposed in this paper outperforms the traditional A* and Weight-A* algorithms in terms of average comprehensive risk and the number of turning points. This fully demonstrates the advantages of the Parallel-A* algorithm in risk avoidance and efficiency improvement. Meanwhile, the research has found that the operational capacity of low-altitude airspace in cities increases as the comprehensive risk decreases, and stabilizes after the comprehensive risk is reduced.
This research provides a scientific basis for the rational utilization and management of urban low-altitude airspace, facilitating the optimization and sustainable allocation of airspace resources. Furthermore, it lays a solid foundation for the large-scale deployment and safe operation of UAV applications in urban environments, offering significant theoretical contributions and practical value. Future research will extend to three-dimensional path planning and divide the urban environment into regions. Dynamic risk environment parameters will be set according to the specific environmental requirements of each region to meet the demands of three-dimensional obstacle avoidance and dynamic height optimization in complex urban environments.

Author Contributions

Methodology, Writing—original draft preparation, Project administration, O.F.; Conceptualization, H.Z.; Software, W.T.; Visualization, F.W.; Visualization, D.F.; Validation, G.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Social Science Fund of China [Grant number: 22&ZD169]; Research on Key Technologies of Multi-Scale Intelligent Situational Awareness For Air Traffic Control Operation Safety In Civil Aviation [Grant Number: U2133207]; Research on Aircraft Autonomic Operation Technology by Air-Ground Information Synergetic Sharing [Grant Number: MJZ1-7N22]; National Natural Science Foundation of China, [Grant Number: U2333214]; Project Funded by China Postdoctoral Science Foundation [Grant Number: 2023M741687].

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 that there are no known competing financial interests or personal relationships that could have appeared to influence the work reported in this paper.

Abbreviations

The following abbreviations are used in this manuscript:
UAVUnmanned Aerial Vehicle
UAMUrban Air Mobility
CAACCivil Aviation Administration of China

References

  1. Wu, K.; Lan, J.; Lu, S.; Wu, C.; Liu, B.; Lu, Z. Integrative Path Planning for Multi-Rotor Logistics UAVs Considering UAV Dynamics, Energy Efficiency, and Obstacle Avoidance. Drones 2025, 9, 93. [Google Scholar] [CrossRef]
  2. Farrag, T.A.; Askr, H.; Elhosseini, M.A.; Hassanien, A.E.; Farag, M.A. Intelligent Parcel Delivery Scheduling Using Truck-Drones to Cut down Time and Cost. Drones 2024, 8, 477. [Google Scholar] [CrossRef]
  3. Zhang, H.; Wang, F.; Feng, D.; Du, S.; Zhong, G.; Deng, C.; Zhou, J. A Logistics UAV Parcel-Receiving Station and Public Air-Route Planning Method Based on Bi-Layer Optimization. Appl. Sci. 2023, 13, 1842. [Google Scholar] [CrossRef]
  4. Callewaert, N.; Pareyn, I.; Acke, T.; Desplinter, B.; Van de Pitte, K.; Van Vooren, J.; De Meyer, M.; Seeldraeyers, E.; Peeters, F.; De Meyer, S.F.; et al. Limited Impact of Drone Transport of Blood on Platelet Activation. Drones 2024, 8, 752. [Google Scholar] [CrossRef]
  5. Tang, P.; Li, J.; Sun, H. A Review of Electric UAV Visual Detection and Navigation Technologies for Emergency Rescue Missions. Sustainability 2024, 16, 2105. [Google Scholar] [CrossRef]
  6. Zhou, Y.; Jin, Z.; Shi, H.; Shi, L.; Lu, N.; Dong, M. Enhanced Emergency Communication Services for Post-Disaster Rescue: Multi-IRS Assisted Air-Ground Integrated Data Collection. IEEE T Netw. Sci. Eng. 2024, 11, 4651–4664. [Google Scholar] [CrossRef]
  7. Tan, Y.; Yi, W.; Chen, P.; Zou, Y. An adaptive crack inspection method for building surface based on BIM, UAV and edge computing. Autom. Constr. 2024, 157, 105161. [Google Scholar] [CrossRef]
  8. Aela, P.; Chi, H.; Fares, A.; Zayed, T.; Kim, M. UAV-based studies in railway infrastructure monitoring. Autom. Constr. 2024, 167, 105714. [Google Scholar] [CrossRef]
  9. Mohamed Salleh, M.F.B.; Wanchao, C.; Wang, Z.; Huang, S.; Tan, D.Y.; Huang, T.; Low, K.H. Preliminary concept of adaptive urban airspace management for unmanned aircraft operations. In Proceedings of the 2018 AIAA Information Systems-AIAA Infotech@ Aerospace, Kissimmee, FL, USA, 8–12 January 2018; p. 2260. [Google Scholar]
  10. Xu, X.Y.; Wan, L.J.; Chen, P.; Dai, J.B.; Cai, M. An Airspace Raster Representation Method Based on GeoSOT Grid. J. Air Force Eng. Univ. (Nat. Sci. Ed.) 2021, 22, 15–22. [Google Scholar]
  11. Tang, X.M.; Gu, J.W.; Zheng, P.C.; Li, T. A Method for Unmanned Aerial Vehicle (UAV) Dynamic Geographic Fence Planning Based on Spatial Gridization. China Patent 202010909173.0A, 2020. [Google Scholar]
  12. Shi, H.F.; Wang, Z.Y.; Zheng, Y.; Xu, Y.B. Refined Management System of Airspace Resources Based on BeiDou Grid Location Code. J. Civ. Aviat. 2022, 6, 44–47. [Google Scholar]
  13. Martin, T.; Huang, Z.F.; McFadyen, A. Airspace risk management for UAVs a framework for optimising detector performance standards and airspace traffic using JARUS SORA. In Proceedings of the 2018 IEEE/AIAA 37th Digital Avionics Systems Conference (DASC), London, UK, 23–27 September 2018; pp. 1516–1525. [Google Scholar]
  14. CAAC Management Regulations for Trial Operation of Specific Types of UAVs. Available online: https://www.caac.gov.cn/XXGK/XXGK/GFXWJ/201902/t20190201_194511.html (accessed on 1 February 2019).
  15. Shao, P. Risk assessment for UAS logistic delivery under UAS traffic management environment. Aerospace 2020, 7, 140. [Google Scholar] [CrossRef]
  16. Banerjee, P.; Gorospe, G.; Ancel, E. 3D representation of UAV-obstacle collision risk under off-nominal conditions. In Proceedings of the IEEE Conference on Aerospace, Big Sky, MT, USA, 6–13 March 2021; pp. 1–7. [Google Scholar]
  17. Pang, B.; Hu, X.; Dai, W.; Low, K.H. UAV path optimization with an integrated cost assessment model considering third-party risks in metropolitan environments. Reliab. Eng. Syst. Safe 2022, 222, 108399. [Google Scholar] [CrossRef]
  18. Primatesta, S.; Rizzo, A.; la Cour-Harbo, A. Ground Risk Map for Unmanned Aircraft in Urban Environments. J. Intell. Robot. Syst. 2020, 97, 489–509. [Google Scholar] [CrossRef]
  19. Harrelson, A.V.G.C. Computing the Shortest Path: A* Search Meets Graph Theory. Proc. Soda 2005, 2005. [Google Scholar] [CrossRef]
  20. Zhang, H.H.; Zhang, L.D.; Liu, H.; Gang, H. Track Planning Model for Logistics Unmanned Aerial Vehicle in Urban Low-altitude Airspace. J. Transp. Syst. Eng. Inf. Technol. 2022, 22, 256–264. [Google Scholar]
  21. Jung, D.; Tsiotras, P. On-line path generation for unmanned aerial vehicles using B-spline path templates. J. Guid. Control Dyn. 2013, 36, 1642–1653. [Google Scholar] [CrossRef]
  22. Damilano, L.; Guglieri, G.; Quagliotti, F.; Sale, I.; Lunghi, A. Ground control station embedded mission planning for UAS. J. Intell. Robot. Syst. 2013, 69, 241–256. [Google Scholar] [CrossRef]
  23. Bulusu, V.; Sengupta, R.; Liu, Z. Unmanned aviation: To be free or not to be free? In Proceedings of the 7th International Conference on Research in Air Transportation, Philadelphia, PA, USA, 20–24 June 2016. [Google Scholar]
  24. Starita, S.; Strauss, A.K.; Fei, X.; Jovanović, R.; Ivanov, N.; Pavlović, G.; Fichert, F. Air traffic control capacity planning under demand and capacity provision uncertainty. Transp. Sci. 2020, 54, 882–896. [Google Scholar] [CrossRef]
  25. Cho, J.; Yoon, Y. How to assess the capacity of urban airspace: A topological approach using keep-in and keep-out geofence. Transp. Res. Part C Emerg. Technol. 2018, 92, 137–149. [Google Scholar] [CrossRef]
  26. Vascik, P.D.; Hansman, R.J. Development of vertiport capacity envelopes and analysis of their sensitivity to topological and operational factors. In Proceedings of the AIAA Scitech 2019 Forum, San Diego, CA, USA, 7–11 January 2019; p. 526. [Google Scholar]
  27. Zhou, J.; Jin, L.; Wang, X.; Sun, D. Resilient uav traffic congestion control using fluid queuing models. IEEE T Intell. Transp. 2020, 22, 7561–7572. [Google Scholar] [CrossRef]
  28. Wang, Y.L.; Zhang, S.; Wu, Y.J. Path Planning Algorithm Based on Improved A* Smoothness. Comput. Appl. Softw. 2025, 42, 258–263. [Google Scholar]
  29. Bulusu, V.; Polishchuk, V.; Sengupta, R.; Sedov, L. Capacity estimation for low altitude airspace. In Proceedings of the 17th AIAA Aviation Technology, Integration, and Operations Conference, Denver, CO, USA, 5–9 June 2017; p. 4266. [Google Scholar]
  30. Jin, A.; Cheng, C.Q. Spatial Data Coding Method Based on Global Subdivision Grid. J. Geomat. Sci. Technol. 2013, 30, 284–287. [Google Scholar]
  31. Interim Regulation on the Administration of the Flight of Unmanned Aircraft; The State Council of the People’s Republic of China, Central Military Commission of the People’s Republic of China: Beijing, China, 2024.
  32. Park, S.; Lee, M.C.; Kim, J. Trajectory Planning with Collision Avoidance for Redundant Robots Using Jacobian and Artificial Potential Field-based Real-time Inverse Kinematics. Int. J. Control Autom. Syst. 2020, 18, 2095–2107. [Google Scholar] [CrossRef]
  33. Xinhui, R.; Caixia, C. Construction and application of third-party risk model for unmanned aerial vehicle operation in urban environment. China Saf. Sci. J. 2021, 31, 15–20. [Google Scholar]
  34. Zhou, R.J. Research on UAV Path Planning. Master’s Thesis, University of Electronic Science and Technology of China, Chengdu, China, 2023. [Google Scholar]
  35. Zhang, Q.Q.; Xu, W.W.; Zhang, H.H.; Zou, Y.Y.; Chen, Y.T. Path planning for logistics UAV in complex low-altitude airspace. J. Beijing Univ. Aeronaut. Astronaut. 2020, 46, 1275–1286. [Google Scholar]
  36. Baganoff, F.K.; Maeda, Y.; Morris, M.; Bautz, M.W.; Townsley, A.L.K. Chandra X-Ray Spectroscopic Imaging of Sgr A* and the Central Parsec of the Galaxy. 2001. Available online: https://ui.adsabs.harvard.edu/abs/2003ApJ...591..891B/exportcitation (accessed on 8 February 2001).
  37. Beard, R.W.; McLain, T.W. Small Unmanned Aircraft: Theory and Practice; Princeton University Press: Princeton, NJ, USA, 2012. [Google Scholar]
  38. Huttunen, M. The u-space concept. Air Space Law 2019, 44, 69–89. [Google Scholar] [CrossRef]
Figure 1. Vertical–horizontal grid partitioning schematic.
Figure 1. Vertical–horizontal grid partitioning schematic.
Drones 09 00320 g001
Figure 2. Schematic of operation-scale grid.
Figure 2. Schematic of operation-scale grid.
Drones 09 00320 g002
Figure 3. Quantification of the risk of mid-air collisions.
Figure 3. Quantification of the risk of mid-air collisions.
Drones 09 00320 g003
Figure 4. Parallel-A* algorithm example. In this figure, “s-a-b-d-f” represents the path planning by A* algorithm, and “s-a-c-d-f” represents the path planning by the Parallel-A* algorithm.
Figure 4. Parallel-A* algorithm example. In this figure, “s-a-b-d-f” represents the path planning by A* algorithm, and “s-a-c-d-f” represents the path planning by the Parallel-A* algorithm.
Drones 09 00320 g004
Figure 5. Schematic of the parallelogram transformation method. In this figure, “a-b-c-d” represents the initial pathby A* algorithm, and “a-b1-c-d” represents the trans path by the Parallel-A* algorithm.
Figure 5. Schematic of the parallelogram transformation method. In this figure, “a-b-c-d” represents the initial pathby A* algorithm, and “a-b1-c-d” represents the trans path by the Parallel-A* algorithm.
Drones 09 00320 g005
Figure 6. Algorithm flowchart of parallelogram-based turning point optimization path planning method.
Figure 6. Algorithm flowchart of parallelogram-based turning point optimization path planning method.
Drones 09 00320 g006
Figure 7. Conflict simulation process.
Figure 7. Conflict simulation process.
Drones 09 00320 g007
Figure 8. Basic information distribution maps.
Figure 8. Basic information distribution maps.
Drones 09 00320 g008
Figure 9. Proportion of physical obstacles by altitude.
Figure 9. Proportion of physical obstacles by altitude.
Drones 09 00320 g009
Figure 10. Environmental risk distribution maps at different altitudes. The red part in the picture indicates the prohibited entry area of the grid.
Figure 10. Environmental risk distribution maps at different altitudes. The red part in the picture indicates the prohibited entry area of the grid.
Drones 09 00320 g010
Figure 11. Environmental risk gradient curve.
Figure 11. Environmental risk gradient curve.
Drones 09 00320 g011
Figure 12. Path planning result diagrams of A*, Weight-A*, and Parallel-A* algorithms. The red part in the picture indicates the prohibited entry area of the grid.
Figure 12. Path planning result diagrams of A*, Weight-A*, and Parallel-A* algorithms. The red part in the picture indicates the prohibited entry area of the grid.
Drones 09 00320 g012
Figure 13. Variation of average comprehensive risk with altitude.
Figure 13. Variation of average comprehensive risk with altitude.
Drones 09 00320 g013
Figure 14. Variation of average number of turning points with altitude.
Figure 14. Variation of average number of turning points with altitude.
Drones 09 00320 g014
Figure 15. Variation of airspace capacity and with altitude.
Figure 15. Variation of airspace capacity and with altitude.
Drones 09 00320 g015
Table 2. Grid sizes and scales corresponding to various levels in the GeoSOT partitioning method.
Table 2. Grid sizes and scales corresponding to various levels in the GeoSOT partitioning method.
LevelGrid SizeScaleLevelGrid SizeScale
0512° 1716″512 m
1256° 188″256 m
2128° 194″128 m
364° 202″64 m
432° 211″32 m
516° 221/2″16 m
61024 km231/4″8 m
7512 km241/8″4 m
8256 km251/16″2 m
9128 km261/32″1 m
1032′64 km271/64″0.5 m
1116′32 km281/128″25 cm
128′16 km291/256″12.5 cm
134′8 km301/512″6.2 cm
142′4 km311/1024″3.1 cm
151′2 km321/2048″1.5 cm
1632″1 km
Table 3. Sheltering factor values.
Table 3. Sheltering factor values.
ValuesClassification
0.00No obstacles
0.25Sparse trees
0.50Vehicles and low-rise buildings
0.75High buildings
1.00Industrial buildings
Table 4. Airspace grid environment and route planning model parameters.
Table 4. Airspace grid environment and route planning model parameters.
ParameterValueParameterValue
a m a x / m / s 2 6 β / J 100
L l o c a t i o n / m 4 L u a v / d B 110
ρ / ( k g / m 3 ) 1.225 h u a v /m 100
C d 0.3 τ m a x 3
t t r a n s 0.1 d a i r c r a f t _ m i n /km 0.5
P u a v 6.04 10 5 d a i r c r a f t _ m a x / k m 27.5
α / J 10 6 δ m a x 180
Table 5. UAV parameters.
Table 5. UAV parameters.
ModelWingspan/m V m a x /
( m / s )
m a l l /
k g
S o / m S v / m S h / m Number   of   Horizontal   Grids Maximum Wind Resistance Level/Grade
ARK - 40 2.36 × 1.2 × 0.6 14 46 45.82648.43 173 × 173 7
Table 6. The simulation analysis results of four sets of path planning. In this table, “↓” represents the growth percentage rate, while “↑” represents the decline percentage rate.
Table 6. The simulation analysis results of four sets of path planning. In this table, “↓” represents the growth percentage rate, while “↑” represents the decline percentage rate.
Computational ResultsPerformance Ratio Compared with Path 1
R ¯ p a t h T ¯ p a t h R ¯ p a t h T ¯ p a t h
Path 12.423.51100%0%
Path 21.517.6638%↓118%↑
Path 31.328.5345%↓143%↑
Path 41.209.6050%↓173%↑
Table 7. Analysis of comprehensive risk and number of turning points in path planning of A*, Weight-A*, and Parallel-A*.
Table 7. Analysis of comprehensive risk and number of turning points in path planning of A*, Weight-A*, and Parallel-A*.
AlgorithmComprehensive Risk
(Mean ± SD)
Number of Turning Points
(Mean ± SD)
Weight-A* 1.66 ± 1.27 15.11 ± 7.23
Parallel-A* 1.20 ± 0.92 9.6 ± 4.52
A* 2.42 ± 3.00 3.51 ± 1.37
ANOVA Results (F-value/p-value) F = 9.67
p = 8.49 × 10 5 < 0.05
F = 133.95
p = 3.43 × 10 5 < 0.05
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

Feng, O.; Zhang, H.; Tang, W.; Wang, F.; Feng, D.; Zhong, G. Digital Low-Altitude Airspace Unmanned Aerial Vehicle Path Planning and Operational Capacity Assessment in Urban Risk Environments. Drones 2025, 9, 320. https://doi.org/10.3390/drones9050320

AMA Style

Feng O, Zhang H, Tang W, Wang F, Feng D, Zhong G. Digital Low-Altitude Airspace Unmanned Aerial Vehicle Path Planning and Operational Capacity Assessment in Urban Risk Environments. Drones. 2025; 9(5):320. https://doi.org/10.3390/drones9050320

Chicago/Turabian Style

Feng, Ouge, Honghai Zhang, Weibin Tang, Fei Wang, Dikun Feng, and Gang Zhong. 2025. "Digital Low-Altitude Airspace Unmanned Aerial Vehicle Path Planning and Operational Capacity Assessment in Urban Risk Environments" Drones 9, no. 5: 320. https://doi.org/10.3390/drones9050320

APA Style

Feng, O., Zhang, H., Tang, W., Wang, F., Feng, D., & Zhong, G. (2025). Digital Low-Altitude Airspace Unmanned Aerial Vehicle Path Planning and Operational Capacity Assessment in Urban Risk Environments. Drones, 9(5), 320. https://doi.org/10.3390/drones9050320

Article Metrics

Back to TopTop