Next Article in Journal
RF Source Localization Using Multiple UAVs through a Novel Geometrical RSSI Approach
Next Article in Special Issue
LightMAN: A Lightweight Microchained Fabric for Assurance- and Resilience-Oriented Urban Air Mobility Networks
Previous Article in Journal
Autonomous Landing of an UAV Using H Based Model Predictive Control
Previous Article in Special Issue
A Framework to Develop Urban Aerial Networks by Using a Digital Twin Approach
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Study of Urban Logistics Drone Path Planning Model Incorporating Service Benefit and Risk Cost

1
The College of Civil Aviation, Nanjing University of Aeronautics and Astronautics, Nanjing 211106, China
2
Civil Aviation Electronic Technology Co., Ltd., Chengdu 610043, China
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
Drones 2022, 6(12), 418; https://doi.org/10.3390/drones6120418
Submission received: 25 November 2022 / Revised: 13 December 2022 / Accepted: 13 December 2022 / Published: 15 December 2022
(This article belongs to the Special Issue Urban Air Mobility (UAM))

Abstract

:
The application of drones provides a powerful solution for “the last-mile” logistics services, while the large-scale implementation of logistics drone services will threaten the safety of buildings, pedestrians, vehicles, and other elements in the urban environment. The balance of risk cost and service benefit is accordingly crucial to managing logistics drones. In this study, we proposed a cost-benefit assessment model for quantifying risk cost and service benefit in the urban environment. In addition, a global heuristic path search rule was developed to solve the path planning problem based on risk mitigation and customer service. The cost-benefit assessment model quantifies the risk cost from three environmental elements (buildings, pedestrians, and vehicles) threatened by drone operations based on the collision probability, and the service benefit based on the characteristics of logistics service customers. To explore the effectiveness of the model in this paper, we simulate and analyse the effects of different risk combinations, unknown risk zones, and risk-benefit preferences on the path planning results. The results show that compared with the traditional shortest-distance method, the drone path planning method proposed in this paper can accurately capture the distribution of risks and customers in the urban environment. It is highly reusable in ensuring service benefits while reducing risk costs and generating a cost-effective path for logistics drones. We also compare the algorithm in this paper with the A* algorithm and verify that our algorithm improves the solution quality in complex environments.

1. Introduction

The daily parcel of e-commerce enterprises has attracted huge attention due to their rapidly growing volume. In 2021, the global parcel shipping volume exceeded 159 billion parcels, which is expected to reach 256 billion in 2027 at a compound annual growth rate of 8.5 per cent [1]. Meanwhile, the variability of customer demand characteristics, such as different service locations and service times, has led to the need for logistic service providers to invest large-scale capacity and resources in “the last mile” transportation of parcels [2]. Thus, more and more companies are trying to find innovative and autonomous delivery methods for “the last mile” transport, such as drone logistics, to improve the quality of logistics. With the development of technology, drones’ airworthiness and cargo-carrying capacity have improved significantly. Electric-powered logistics drones are not restricted by road networks and can reduce environmental costs and increase service flexibility [3]. The contactless services provided by drone logistics are also widely recognised due to the coronavirus outbreak [4]. Overall, the above advantages make drone logistics a powerful solution to solving the problems of traditional logistics [5]. Internationally renowned logistics companies such as Amazon, DHL Express, and Jingdong Logistics have begun developing drone logistics versions [6]. Statistics from BusinessWire also show that the global business value of drone package delivery has grown from USD 0.68 billion in 2020 to approximately USD 1 billion in 2021 and is expected to be USD 4.4 billion in 2025 [7].
However, the accident risks associated with the large-scale application of logistics drones must be effectively assessed and managed. The drone would not only threaten the safety of people and vehicles on the ground in urban environments [8], but also may collide with high-rise buildings [9]. To ensure the safety of other aircraft, people, and property after a drone crash, aviation organisations, including the Federal Aviation Authority (FAA), require a risk mitigation assessment in the pre-flight state [10]. Hence, the study of path risk assessment and mitigation methods is a critical technical prerequisite for logistics drone applications.
Throughout the existing research, the vehicle path problem is a classical mathematical model for studying urban last-mile logistics. It is based on the travelling salesman problem (TSP) [11], which ensures the minimum transportation time or cost by planning the service sequence of customers. The existing research evolved on the basis of this problem model. Murray and Chu [12] proposed a collaborative path-planning model for trucks and drones considering drone service range and load capacity constraints. In this work, they reported two new variants of the traditional TSP problem, the flying sidekick travelling salesman problem (FSTSP) and the parallel drone scheduling travelling salesman problem (PDSTSP). Yurek and Ozmutlu [13], Freitas and Penna [14], and Mbiadou Saleu et al. [15] also presented various algorithms for these problems. The above-simplified approaches assumed that the order of customer service at different locations remains consistent with the drone’s service path, while ignoring the problem of safety risks inevitably involved in the actual operation. Inspired by this factor, existing studies have started to consider the risk assessment of drone operations. These mainly include the risk of collision in flight and the impact on the ground.
Falling drones would threaten the safety of pedestrians and vehicles on the ground. Mitici and Blom [16] proposed a mathematical model for collision probability estimation, which provides a research solution for the collision risk assessment of drones. Bertrand et al. [17] studied the probability of drone operations threatening road traffic, defined the range of ground a falling drone could affect, and developed a collision probability model to identify high-risk areas in the road network. Koh et al. [18] and Clothier et al. [19] studied the extent of injury to pedestrians struck by drones and proposed weight limits for drones based on the associated injury scales and criteria. Drone aerial collision risks mainly originate from buildings, no-fly zones, unstable weather, and other drones [20]. To assess the risk of aerial collisions, existing studies have established various collision models, mainly including the REICH model, the EVENT model, and the position probability model based on the concept of position error. The REICH model [21] lays the foundation of flight safety interval assessment and is mainly applied to assess the risk of collision between two aircraft in parallel flight paths. It finds that the collision probability and relative velocity in each direction determine the flight collision risk. The EVENT model proposed by Brooker [22] combines radar and controller operations to analyse lateral and longitudinal separation, which can calculate the probability of collision risk in each direction. The probabilistic model based on position error focuses on collecting and processing information about the positioning error and trajectory deviation of the drone, in order to predict the probability of the flight trajectory conflicting with the risk area [23].
Based on the conflict risk assessment research, most research on drone path risk mitigation aims to find no-conflict paths. One intuitive approach is geometry-based. The closest proximity point approach is used to solve the potential conflict warning problem by measuring the position between two drones, thus avoiding collision risk and ensuring the safety of the planned path [24,25]. As an improvement to the geometric method, Fan et al. [26] and Tang et al. [27] introduced artificial potential fields (APF) and simulated the environment by designing virtual attractive and repulsive potential fields for autonomous guidance of the drone to avoid obstacles. Driven by efficiency, many researchers have tried to use heuristic search to find the optimal no-conflict path. For example, a node-based optimal algorithm is a special form of dynamic programming. When a map or graph is already constructed, they first define a cost function, and then search each node and arc to find a path with minimum cost. It mainly includes the A* algorithm [28], Lifelong Planning A* (LPA) [29], Theta* [30], Lazy Theta* [31], D*-Lite [32], Harmony Search [33], etc. Evolutionary algorithm, which contains genetic algorithm [34], memetic algorithm [35], particle swarm optimisation [36], ant colony optimisation [37], and shuffled frog leaping algorithm [38]. The evolutionary algorithm starts by selecting randomly feasible solutions as the first generation. Then, taking the environment, drone capacity, goal, and other constraints into consideration, the planner evaluates the fitness of each individual. In the next step, a set of individuals is selected as parents for the next generations according to their fitness. The last step is a mutation and crossover step and stops the process when a pre-set value is achieved. The best fitness individual is decoded as the optimal path. Recent studies have treated drones as intelligent agents for stochastic dynamic threats in urban environments and used reinforcement learning to guide drones to avoid collisions [39,40,41].
Nevertheless, it is still an open problem for drone logistics to plan effective service paths in complex urban environments and ensure service completion based on reducing the threat to pedestrians, vehicles, buildings, etc. Many works focus on only considering obstacles in the environment during the finding phase of collision-free paths, while little attention has been paid to the fact that the risk cost from the threat is simultaneous with the service benefit of providing services to customers. To address the shortcomings in the above studies, we propose an urban environment model considering the coupling effect of customer service requirements and complex risks and develop a path point search strategy for improving the exploration of feasible paths in the environment. We summarise the main contributions of this paper as follows.
(1)
We studied the complex risk factors of drone operation in urban environments and established a risk quantification model, which considers three primary risk sources in urban environments, including pedestrians, vehicles, and buildings.
(2)
We established a logistics service benefit quantification model and proposed a multi-drone path planning method that integrates risk cost and service benefit, with the goal of guiding drones to find a path with the highest service benefit and lowest risk cost under the constraints of flight performance indicators, such as energy consumption and step length.
(3)
We proposed a path point search strategy to solve a dynamic path planning problem driven by customer demand and risk. The strategy ensures that drones can adjust local paths in dynamic environments through regular global searches.
The rest of this paper is organised as follows: Section 2 analyses the critical elements affected by drones in the urban environment and illustrates the concept of path planning that combines customer needs and risks. The proposed methodology is described in Section 3, followed by simulation validations and case studies in Section 4. The summary of our work is in Section 5.

2. Problem Definition

Drones operate at low altitudes below 400 feet above the ground in cities. Once there is a collision, they can cause threats to buildings and other non-cooperative drones in the air. On the other hand, they can threaten pedestrians and vehicles on the ground when a crash occurs [42,43]. We conclude the primary environmental elements threatened by drone operations into four categories as follows.
(1)
Drone impacts pedestrians, causing fatalities;
(2)
Drone impacts vehicles, causing traffic accidents;
(3)
Drone impacts high-rise buildings, resulting in property loss;
(4)
Drone collision with other non-cooperative drones.
In this work, we ignore other risk factors, such as noise and privacy impacts on the public, due to their insignificance [44]. Pedestrians, vehicles, buildings, and logistics service customers are randomly dispersed in the city. Therefore, the core problem in logistics drone path planning is quantifying risk cost and service benefit for different locations. The urban environment for drone flight is divided into discrete 2D grids, and each grid’s risk cost and service benefit are derived from environmental risk elements and customer demand. The cost-benefit value within each grid is used to guide drones to serve more customers and avoid high-risk areas in the complex urban environment.
The technology framework of the proposed work is presented in Figure 1. There are five steps to quantify risk cost and service benefit in the environment. First, the threat of drone operations to pedestrians, vehicles, and buildings in the city is analysed. Then, we develop three risk cost assessment models to quantify the various types of risk costs from the above elements under threat. Thirdly, we develop a service benefit assessment model based on the characteristics of logistics customers. Fourth, we synthesise the integrated risk cost and service benefit into cost-benefit values. Fifth, we construct the cost-benefit map. The urban environment is gridded, and the cost-benefit value calculation method of the flight path is established. Based on the cost-benefit map, we propose a drone path planning model with energy limitation constraints and a search algorithm with heuristic factors. To explore the effectiveness of the model in this paper, we next simulate and analyse the effects of different risk combinations, unknown risk zones, and risk-benefit preferences on the path planning results. We also compare the algorithm of this paper with the A* algorithm to verify the solving ability of this paper’s algorithm. Finally, the reusability of the method in this paper is demonstrated by statistical analysis.

3. Materials and Methods

3.1. Risk Assessment Model

This section presents a quantitative model of the integrated risk cost. We analyse the risks derived from the operation of drones in an urban environment. Figure 2 depicts the impact of considering risk cost mitigation on path planning results. The environment is divided into equal-sized grids, and the risk cost within each grid is calculated according to the integrated risk model. The colours in the map show the distribution of risk cost, with red representing areas of high risk cost and blue representing areas of low risk cost. The dashed line indicates the path with the shortest distance from the starting point to the end, and the solid line is the path that considers risk cost mitigation, which chooses the area with lower risk cost to pass, and the final path has a much lower risk cost than the shortest path.

3.1.1. Quantifying the Risk Cost Associated with Pedestrians

The risk cost of a drone striking a pedestrian is modelled according to the three components of collision [45,46]: (a) a drone crash, (b) a drone striking pedestrians, and (c) resulting in the death of pedestrians, as shown in Figure 3.
We quantify the risk cost due to drones affecting pedestrians by potential fatalities as in Equation (1):
C o s t 1 = C o s t p = P c r a s h S d ρ p P d
where C o s t 1 is the quantified value of pedestrian risk cost, P c r a s h is the probability of a drone crash, S d is the exposed area of the ground impacted by the falling drone, ρ p is the population density, and P d is the fatality rate associated with the kinetic energy of the drone. The speed of the drone hitting the ground is shown in Equation (2):
v d = 0 t g f d t = 0 t g f d S d ρ A v d r e a l 2 2 m d t = 2 m g f d S d ρ A 1 e H f d S d ρ A m
where g = 9.8 m / s 2 , f is the resistance acceleration, f d is the drag coefficient, ρ A is the air density, v d r e a l is the actual airspeed of the falling drone, m is the mass of the drone, H is the height of the drone falling point. The energy generated by the descending drone is shown in Equation (3)
E f d = 1 2 m v d 2
Considering that the buffering effect of buildings and trees can mitigate the injury of falling drones to pedestrians, a sheltering factor S f , S f ( 0 , 1 ] is introduced to consider this sheltering effect when calculating risk costs. A higher value implies a better sheltering effect and a lower probability of death. By combining the sheltering element into the kinetic energy equation, the lethality P d of a falling drone can be obtained as shown in Equation (4):
P d = 1 + μ ν ( ν E f d ) 1 4 S f 1
where μ is the energy that might cause a 50% fatality with S f = 0.5 , ν is the impact energy threshold required to cause fatality as S f approaches zero. The values of S f for different environments are shown in Table 1.

3.1.2. Quantifying the Risk Cost Associated with Vehicles

Vehicles are another key element in the urban environment that can shelter falling drones; different from buildings and trees, the sheltering effect of vehicles mainly occurs while driving. Similar to the modelling of drone strikes on pedestrians, falling drones cause road traffic accidents in three components [17]: (a) a drone crash, (b) a drone striking vehicles, (c) resulting in traffic accidents, and (d) causing human fatalities, as shown in Figure 4.
Quantify the risk cost due to drones affecting vehicles by potential fatalities, as shown in Equation (5)
C o s t 2 = C o s t V = P c r a s h P V N V
where P V is the probability of a falling drone hitting a vehicle, proportional to the traffic density, and N V is the average number of fatalities caused by a crash. The probability of a drone hitting vehicles on the ground is defined as the ratio of the total area occupied by vehicles to the entire scope of the road, as shown in Equation (6)
P V = S V ¯ ρ V D r o a d
where S V ¯ is the average projected area of the vehicle, ρ V is the traffic density, and D r o a d is the road width.

3.1.3. Pedestrian Density and Vehicle Density

The density distribution of pedestrians and vehicles in the urban environment can directly affect the risk cost of drone operations. Their density distribution is highly correlated with attractive facilities [48]. To quantitatively assess this correlation, gravity models are used to calculate pedestrian and vehicle density [49]. Inspired by gravity models, the pedestrian density in urban environments is shown in Equation (7).
ρ P = e ( 1 r 2 ) ρ P 0
Where ρ P 0 is the average pedestrian density, r is the distance from the centre of gravity. If there is an increase in r , it leads to a decrease in ρ P , as shown in Figure 5.
Similarly, the road traffic density distribution is shown in Equation (8):
ρ V = e ( 1 r 2 ) ρ V 0
where ρ V 0 is the average traffic density.

3.1.4. Quantifying the Risk Cost Associated with Buildings

As shown in Figure 6, the operation of drones in urban airspace inevitably involves potential conflicts with buildings, and this potential conflict incurs risk costs [50]. Considering the overlapping locations of logistics customers and buildings, buildings cannot simply be set up as no-fly grids.
The flight risk decreases as the distance between the drone and the building increases. However, due to the different sizes and shapes of buildings in the city, the influence range of buildings on drones is also different. For a normal distribution, setting different variances can reflect the different influence ranges of buildings, which is simple compared to other distributions or describing the shape and dimensions of the buildings. To simplify the model calculations, the distribution of the risk cost due to the influence of the building is assumed to be a normal distribution with different variances [51].
For n independent buildings in the map, given the central location B i = ( X i , Y i ) of the i -th building, C o s t B u ( x , y ) denotes the risk cost of the point ( x , y ) when considering the impact of the building B i , as shown in Equation (9)
C o s t 3 = C o s t B u ( x , y ) = 1 2 π σ e d 2 2 σ 2
where d = ( x X i ) 2 + ( y Y i ) 2 , i 1 , 2 , , n indicates the Euclidean distance between the drone and the centre of the building.

3.1.5. Comprehensive Risk Model

In the previous section, risk cost quantification models were constructed for three elements: pedestrian, vehicle, and building. The different calculation methods would obtain different values of risk cost magnitude, which cannot be measured by the same standard. Therefore, the risk costs of the three elements need to be standardised to describe the total risk cost in the urban environment.
The risk costs of all three elements can be calculated through a particular distribution, and then each type of risk cost contained in a raster would be divided by the maximum risk value generated by the risk source separately. It is guaranteed that all risk cost values for each type are in the range of ( 0 , 1 ] .
The weights of the three risks may vary with the difference in their importance or preference, and the contribution of each risk may also vary with the cost [52]. For example, aviation regulators emphasise the risk of pedestrian fatalities caused by drones. The risk cost of pedestrians will be weighted much more than the other two factors. Traversing the areas with high pedestrian density will result in higher costs, so the planned paths will be more inclined to avoid these areas.
For point ( x , y ) , its cumulative risk value needs to consider a pedestrian risk zones, b vehicle risk zones, and c building risk zones. The total risk cost of the point ( x , y ) is calculated as shown in Equation (10),
R t o t a l ( x , y ) = α i i = 1 a C 1 i C 1 max i + α j j = 1 b C 2 j C 2 max j + α k k = 1 c C 3 k C 3 max k
where α i , α j , α k are the weighting factors, α i + α j + α k = 1 .
The cumulative risk R t o t a l ( x , y ) of the path C is shown in Equation (11)
( x , y ) C R t o t a l ( x , y )

3.2. Drone Path Planning Model Based on Risk Cost and Service Benefit

The flight path of drones performing logistics services needs to mitigate the path risk cost based on ensuring service completion. Therefore, the objectives of logistics drone path planning include risk mitigation and customer service. The integrated risk cost quantification model established in the previous section can be used for risk mitigation. Customers’ locations in cities often overlap with risk factors, such as buildings, crowds, and roads. This would cause drone service paths to pass through risk areas, so it is necessary to balance the path risk cost and service benefit. Figure 7 depicts the impact of considering risk cost mitigation and service benefits on the path planning results. The solid white arrows indicate the shortest path, the white dashed arrow is the path considering risk cost mitigation, and the white dotted line indicates the path that balances risk cost and service benefit, where the path is changed to fulfil customer needs based on the most risk cost-effective path.
In this section, our primary work is to establish a multi-drone path planning method to guide drones to find a path with the highest service benefit and lowest risk cost under the constraints of flight performance indicators such as energy consumption and step length. Furthermore, a global search strategy is proposed to solve the above paths.

3.2.1. Service Benefits Modelling

Assume that each customer has an initial requirement C d e m a n d j 0 that needs to be handled by drone. We also assume that the drone can only serve a certain distance from the customer’s location. Therefore, for a customer j , the range that can be served is denoted as s ( p j , R ) , where p j is the location of the customer j and R is the radius of the acceptable service range. Service starts when the drones enter the service range of the customer j . Each drone has a constant service speed τ . The remaining demand C d e m a n d j of the customer served by k drones simultaneously over time Δ t is shown in Equation (12)
C d e m a n d j t = C d e m a n d j t + Δ t τ k Δ t
Assuming a nonlinear relationship between customer residual demand C d e m a n d j and service revenue C b ( C d e m a n d j ) , this paper uses a sigmoid-like function to improve performance, as shown in Equation (13)
C b ( C d e m a n d j ) = 1 exp ( C d e m a n d j ) χ C d e m a n d j + ψ
where χ and ψ are control parameters. For each customer, the service revenue C b ( C d e m a n d j ) decreases rapidly with its remaining demand C d e m a n d j . It is guaranteed that serving the customer with the highest remaining demand generates the greatest revenue, thus increasing global customer service completion.

3.2.2. Energy Consumption Modelling of Drones

Assuming that the lifting and lowering process of the drone is ignored and only straight-line flight is considered, the energy consumed for moving a distance d at a constant speed v is shown in Equation (14),
E v = P ( w ) d v ,   Δ E v = P ( w ) Δ t
where P ( w ) is the power of the drone moving at a constant speed v . For the n-rotor drone, its power is shown in Equation (15),
P ( w ) = ( W + w ) 3 2 g 3 2 ρ A ς n
where W is the self-weight of the drone, w is the weight of the load carried by the drone, ρ A is the fluid density of air, ς is the area of the rotating blades, and g is the acceleration of gravity. The total power of the drone is shown in Equation (16),
E t o t a l = η C V n
where η is the energy conversion efficiency, C is the capacity of the cell, and V n is the nominal voltage of the n cells.
The drone departs with an empty load. As the drone services the customer, the drone’s load increases while the customer’s remaining demand decreases. After the current customer is served, the drone maintains the current load until it starts serving the next customer.
Assuming that the demand is proportional to the load and the scale factor is ε , then for a drone i serving x customers at the same time, the load varies with time, as shown in Equation (17),
w i t + Δ t = w i t + τ x ε Δ t

3.2.3. Global Path Planning Model

Based on the risk cost and service benefit quantification model, We introduce a cost-benefit matrix to measure the benefits and costs between any two points on the map. The map is represented as an N × N grid, and the cost-benefit matrix T C m n between any points p m and p n is shown in Equation (18)
T C m n = d p m , p n + M b e n e f i t 1 + n s ( p j , R ) C b ( C d e m a n d j ) + M r i s k ( x , y ) C R t o t a l ( x , y )
where p m , m 1 , 2 , , N 2 is the current position of the drone, p n , n 1 , 2 , , N 2 is the next position of the drone. d p m , p n is the Euclidean distance between p m and p n . n s ( p j , R ) C b ( C d e m a n d j ) is the benefit generated by the demand of all customers that can be served at point p n . M b e n e f i t and M r i s k are the coefficients of service benefit and risk cost, which affect the path planning strategy. In practice, M b e n e f i t and M r i s k can be adjusted according to preference. For example, if the tolerance for risk cost is poor, then M r i s k can be set to a higher value to amplify the impact of risk cost.
The goal of the present work is to plan a service path with minimum total cost. The total cost includes the risk cost and the inverse of the service benefit. The objective function is shown in Equation (19)
min : T C ( P ) = e i r P T C ( e i r ) , i > 0 , r = i + 1
where P is the flight path consisting of edge e , T C ( P ) is the total cost of the path P , and T C ( e i r ) is the cost of the edge e i r .
According to the drone energy consumption model, the power available for flight is limited. Therefore, the logistics drone must complete the service and reach the endpoint as soon as possible before consuming the planned available power. The constraint is defined as
l i r l min , e i r P , r = i + 1 , i , r > 0
E c o n s u m e = e i r P E c o n s u m e i r E p l a n
( x i x i 1 , y i y i 1 ) T ( x i + 1 x i , y i + 1 y i ) ( x i x i 1 , y i y i 1 ) ( x i + 1 x i , y i + 1 y i ) cos β max
Equation (20) represents the shortest distance constraint for an edge between two adjacent nodes in the drone path, l min is the minimum distance of the edge, and l i r is the length of the edge e i r . Equation (21) represents that the total energy consumption of the drone must not exceed the available power, E c o n s u m e is the total energy consumption of the path P , E c o n s u m e i r is the energy consumption of each side e i r in the path P , and E p l a n is the total available power. Equation (22) represents the constraint on the maximum turning angle of the drone, ( x i , y i ) , ( x i 1 , y i 1 ) , ( x i + 1 , y i + 1 ) are the coordinates of three consecutive path points, and β max is the maximum acceptable turning angle.

3.2.4. Path Planning Algorithm

To solve the least-cost flow problem for large scale in this study, heuristic methods (e.g., A* algorithm) have better performance in terms of computational time to solve the path planning problem. The standard A* algorithm generally uses the Manhattan or Euclidean distance to select the following move location. However, in the cost-benefit environment established in this paper, the cost of each raster is different and unevenly distributed, so considering only the distance cannot reflect the actual cost of the path. As the complexity of the environment increases, the traditional A* algorithm has difficulty finding a suitable path and deadlocks. Therefore, the following path search rule is proposed to improve the environment’s exploration, and the rule’s effectiveness is verified in the experimental stage.
(1) Environmental exploration strategy
In this work, a heuristic factor is set according to the Boltzmann distribution to ensure a complete exploration of the environment. The drone is currently at the path point p i , i 1 , 2 , , N 2 , and the probability of the point p r , r 1 , 2 , , N 2 being selected as the next path point is calculated based on the value T C i r , as shown in Equation (23)
p ( i , r ) = exp T T C i r k R , k i exp T T C i k
where T is the temperature parameter that controls the degree of environment exploration, R is the set of all N 2 points in the map. At the beginning of exploration, since the drone knows little information about the environment, a smaller T value is set to ensure that the drone can explore the environment quickly in the early stages. As the exploration time increases and the drone has enough information about the environment, the value of T is increased to ensure that the algorithm can reach convergence within a specific time.
(2) Original global path generation rules
A sequence of points forms a drone path. The calculation of the cost-benefit value T C m n for the drone moving between two points in the map is established in Equation (18). The path point exploration rule based on the cost-benefit value T C m n is established in Equation (23). Based on this, our global path planning is divided into two steps. Based on this, our global path planning is divided into two steps. Firstly, based on the cost-benefit value in the environment at the planning start time t 0 , a series of paths satisfying the constraints are iteratively generated according to the global search method (as shown in Algorithm 1), and the path with the optimal cost-benefit value is selected as the original global path. The second step performs local replanning on the basis of the original global path (as shown in Algorithm 2). The generation of the original global path is described as follows.
(1) For the i -th drone ( UAV i ), for each e p i s o d e repeat (2)–(6).
(2) Initialise P a t h i to an empty list P a t h i . The initial position P 0 of the drone is the first point P a t h i [ 1 ] in P a t h i .
(3) For each step in each e p i s o d e , repeat (4)–(5).
(4) For the current location point p s , select the next point p s + 1 according to the Boltzmann exploration strategy.
(5) Add p s + 1 to P a t h i , as the s + 1 -th path point P a t h i [ s + 1 ] . Return to (3) until the target point is reached or the power is exhausted.
(6) Finish this e p i s o d e , e p i s o d e + 1 , and return to (2).
(7) Until e p i s o d e = M A X , the learning process ends and the current optimal P a t h is output.
The process of global path planning is defined in Algorithm 1.
Algorithm 1 Original global path generation
 1
For i in U A V n u m do
 2
For e p i s o d e 0 t o M A X do
 3
   P a t h i P a t h i  
 4
   P a t h i [ 1 ] P 0
 5
  For p s P 0   t o   T arg e t do
 6
    p s + 1 B o l t z m a n n
 7
    P a t h i [ s + 1 ] p s + 1
 8
    s = s + 1
 9
  End for
 10
   e p i s o d e = e p i s o d e + 1
 11
End for
 12
End for
(3) Drones Movement and local path replanning rules
Based on the original global path defined in Algorithm 1, we need to further establish the rules that the drone moves according to the original path and simulate the actual operation of the drone on the original path. During the flight of drones, new risk areas may appear on the map as time changes, causing the subsequent part of the original global path to cross high-risk cost areas, and then the original path needs to be locally replanned. The reason for the above situation is that global path planning is carried out at time t 0 , and some risk zones in the environment do not exist at this time but appear at time t = t 0 + Δ t (e.g., the temporary gathering of pedestrians due to time-predictable activities). This risk zone needs to be addressed by local path replanning rules during the actual flight of the UAV based on the original global path. This does not require real-time path planning, only further pre-planning for new risk zones that are known to occur during flight. The process of local path replanning by the drones to avoid the newly generated risk zone is defined in Algorithm 2.
For the i th drone ( UAV i ) S c a n is executed after moving one step along the original path. After S c a n is executed, there are two scenarios. The first scenario is the discovery of new obstacles (including other drones), and the cost-benefit matrix will be recalculated for replanning the subsequent paths. The second scenario is that the surrounding environment remains unchanged, and the path also keeps the same. For each time interval Δ t , the step length of the drone movement is fixed as S t e p . If the distance between the current position and the subsequent path point is less than S t e p , the drone will move directly to the subsequent path point.
Algorithm 2 Drone Movement and local path replanning
13 For i in U A V n u m do
14 P a t h i P a t h p o i n t   G e n e r a t i o n (   )
15 End for
16 For i in U A V n u m do
17If p o s i = = Target then
18   Stop ( i )
19else
20   O b s t a c l e S c a n
21  If O b s t a c l e then
22    P a t h i P a t h p o i n t   G e n e r a t i o n (   )
23  End if
24  If p o s i = = P a t h i [ 1 ] then
25    P a t h i P a t h i [ 2 e n d ]
26  End if
27   p o s i = = Move ( S t e p , P a t h i [ 1 ] )
28 
  For j with UAV i in ( P j , R ) do
29 
C d e m a n d j C d e m a n d j τ
30 
E v E v P ( w i ) Δ t
31    w i w i + ε τ
32  End for
33End if
34 End for

4. Results

In order to validate the path planning model coupling risk cost and service benefit, we perform simulations and analyses in a constructed urban environment containing pedestrian risk zones, vehicle risk zones, building risk zones, and logistics customers.
First, the urban environment model is constructed based on the modelling of risk areas and customer demands above. Then, we apply the proposed path search algorithm to search the logistics service path with the lowest risk cost and the highest service benefit.
Based on the above, the effect of risk combinations and the dynamic addition in risk areas are investigated to verify the reliability of the model and algorithm, which can mitigate the three risk costs while ensuring the response to the dynamic environment. Next, sensitivity analysis is conducted for the risk and benefit coefficients to study the balance of risk cost and service benefit in path planning. To evaluate the effectiveness of the algorithm proposed in this paper, the three most critical metrics in logistics path planning, namely, service completion, average path length, and average risk, are considered to compare with the A* algorithm. Finally, simulations and statistical analyses were performed to evaluate the effectiveness of the proposed path planning model for balancing risk cost and service benefit when extended to other urban environments.

4.1. Path Planning for Multiple Drones

The urban environment model proposed in this paper includes pedestrian risk, vehicle risk, and building risk, and it is verified that drones can ensure the completion of customer service while reducing the cost of path risk. In this section, the required parameters for simulation experiments are shown in Table 2 [46,53,54], and the optimisation effect of the model in this study compared with the traditional method is analysed.
The flight area with a range of 1000 × 1000 m is divided into 50 × 50 grids. In the environment model, we assume that the drone starting points are represented by black circles; the endpoint is represented by a black cross; the building risk zones are randomly generated variance σ ; the crowd risk zones and the road vehicle risk zones are randomly generated risk radius r ; the customer zones to be served are assigned random initial demand d j ( 0 , 10 ] .
Considering that the size of the drones is much smaller than the size of the grids, in this paper, we use the integral method to obtain the path risk cost, and the calculation result is not affected by the size of the grids and drones. Therefore, the drone is considered a prime point to simplify the calculation. The drone path planning is guided based on the risk cost distribution consisting of pedestrians, buildings, and vehicles in the environment and the service benefit distribution determined by the customer’s location and acceptable service range. The path planning is performed in MATLAB using the algorithm described above. The initial environment modelling and path planning results are shown in Figure 8. The paths of the three drones departing from different locations are represented by three colours. Path group 1 represents the result of path planning considering the balance of service benefit and risk cost, where Drone 1 serves Customers 1, 2, and 3 according to the solid red path, Drone 2 serves Customers 4 and 5 according to the solid blue path, Drone 3 serves Customers 4, 5, and 6 according to the solid green path. Path group 2 is the path only considering customer service without risk. Path group 3 is the path only considering risk without customer service. The colours in the map show the distribution of risk cost, with red representing areas of high risk cost and blue representing areas of low risk cost. The contour lines represent the distribution of risk cost due to building risk and pedestrian risk, and road 1 and road 2 represent the vehicle risk cost distributed along the road. The specific path parameters are shown in Table 3.
As shown in Figure 8 and Table 3, the result of path planning without considering the risk model (path group 2; no risk considered) traverses the high-risk area to ensure the shortest path to complete the customer service and reach the endpoint, resulting in increased risk cost. The path without considering customer service (path group 3; no customer considered) ignores customers overlapping with the location of high-risk areas for ensuring the shortest length and lowest risk cost path to reach the endpoint. The customers overlapping with high risk cost areas are completely ignored, leading to a decrease in service completion. The model of this paper, which considers both risk avoidance and customer service completion as the driving force, can balance the risk cost and service benefit. Risk cost is reduced by 81.25% compared with path group 2, and service completion is improved by 57.00% compared with path group 3.

4.2. Path Planning with Different Risk Combinations

According to the result in the previous subsection, it can be seen that the model obviously mitigates the risk cost in path planning. However, the comprehensive risk model proposed considers three types of risks: pedestrian, vehicle, and building. The path planning results also are affected to an extent by the difference in risk models.
Therefore, further quantitative analysis is required to study the effects of different risk combinations on drone path planning and risk costs in urban environments. This section simulates and studies path planning in the above flight area with four risk combinations: (a) Group A considers three risks, (b) Group B considers pedestrians and buildings, (c) Group C considers buildings and vehicles, (d) Group D considers pedestrians and vehicles, and (e) Group E does not consider risks.
Figure 9 presents the effect of different risk combinations on path planning. Path A has a total risk cost of 6.20. Path E is the worst because it does not mitigate any risks, with 433.23% higher total risk cost than Path A. Path B and Path C have similar results, with Path C being 7.99% higher than Path B due to dense pedestrian areas being more relevant to buildings. The risk cost of Path D increases by 53.99% relative to Path A. Due to the gravity model, the distribution of pedestrians and vehicles is associated with buildings, and disregarding building risks leads to a subsequent small increase in pedestrian and vehicle risks, but this increase is significantly lower than Path B and Path C, where the corresponding risks are not considered.
The average path length is affected by the combination of risks, and Path E has the shortest length without considering risks. Considering all three risk types, the model proposed in this paper only increases the path length by 12.00% over Path E.
For the increase in path length, on the one hand, the 12.00% increase in path length is minimal compared to the 433.23% increase in risk. On the other hand, we add the constraint of drone energy consumption to the path planning model. Although the length of Path A increases, it still completes all customer service requirements and reaches the target point within the energy consumption constraint, indicating that the increase in path length is negligible.
The results show the path planning under different risk combinations to further understand the differences in the various types of risk costs of the path planning results while considering the risk combinations.
This paper investigates each type of risk cost (pedestrian risk cost R1, vehicle risk cost R2, and building risk cost R3) in the above five risk combinations. The results are shown in Table 4. Path C was planned without considering the risks associated with pedestrians in the environment. The drone path enters dense pedestrian areas, resulting in a pedestrian risk cost R1 of 15.48, which is higher than the case of Path A and Path B, where pedestrian risk is considered. On the contrary, the risk combination considered in Path B includes pedestrian risk, thus avoiding the area with high pedestrian risk costs. However, vehicle risk is not considered, resulting in a higher vehicle risk cost of 14.47. The exclusion of building risk in Path D leads to an increase in building risk by 452.63%.
The gravity model leads to an overlap of the three risk types, which is similarly demonstrated in the variation of the three types of risk cost. Path B ignores vehicle risk, while pedestrian risk and building risk increase respectively by 6.27% and 94.74%; Path C ignores pedestrian risk, but vehicle risk and building risk increase respectively by 16.92% and 573.68%; Path D ignores building risk, and pedestrian and vehicle risk increase respectively by 68.35% and 7.52%. Although Path D ignores the building risk, the drone path does not intrude into the high building risk zones due to the presence of pedestrian risk, so the building risk is reduced by 17.97% compared to Path B. The relevance of the variation in different risk cost types also proves the importance of studying the integrated risk assessment model in this paper.
Path E presents that all three types of risk values are the highest among the five paths due to the correlation of various risk areas in the urban environment, such as the dense distribution of pedestrians and vehicles around the buildings. Therefore, the path planning results without considering any risk, the cost of all three risk categories is higher than the value of the corresponding risk category in any other combination.
For the mitigation effect of each type of risk, comparing Path E with Path A, it is shown that Path E in construction risk is 1.33 and Path A is 0.19, decreasing the risk by about 85.61%. Path E in vehicle risk is 15.11, and Path A is 2.66, decreasing the risk by approximately 82.40%. Path E for pedestrian risk is 16.62, and Path A is 3.35, decreasing the risk by about 79.85%. The total risk is reduced by approximately 81.25%. As a result, the model in this paper has a good mitigation effect on all three types of risks, and the proportion of the three risk reductions is kept at about 80.00%.
We can conclude that more risk sources in path planning can effectively mitigate the total path risk cost. This is because capturing more comprehensive risk sources is beneficial for avoiding more high-risk areas. It also further demonstrates the importance of our analysis and modelling for various types of elements threatened by drones in cities, which can guarantee the effectiveness of capturing risk costs in path planning.

4.3. Temporary Response Effect of the New Risk Area

During the process of drone logistics transportation in urban environments, the obstacles and risk areas in the environment can basically be examined and commanded to go around in the global path pre-planning stage before starting the mission due to the more comprehensive network coverage. However, due to the complexity of the urban environment, it is still challenging to avoid unknown obstacles in advance, such as flocks of birds, which require commanding the drone to change its route to avoid them.
In the path planning algorithm of this study, the drone scans the global environment at each step. Once there are new risk areas that affect the original flight path of the drone, the subsequent path is replanned to ensure that the drone adapts to the dynamic urban low-altitude environment. This section focuses on analysing the effect of the avoidance strategy proposed by the algorithm.
As shown in Figure 10 and Table 5, when a new risk area appears at the location of the point (0.2, 0.9), drone 1 moves one step according to the original path and finds that the subsequent original path passes through the new high risk cost area, so a local path replanning is performed to avoid the new risk area. The red dashed line in Figure 10 represents the locally replanned path of drone 1, and the solid red line indicates the original path. The solid blue line indicates the path of drone 2, the solid green line indicates the path of drone 3. As the new risk zone does not affect the original paths of drone 2 and drone 3, the paths of these two drones do not change. For analysing the impact on drone 1, which was replanned to avoid the new risk zone, we further compared and analysed the path parameters. The path length of drone 1 increased from 1.62 of the original path to 1.69, and the growth rate was 4.32%. The path risk cost was affected by the new risk zone, which increased from 5.20 to 5.22, with a growth rate of 0.35%. The service completion was always 100%, indicating that the path length increase was negligible. It is clear that the avoidance strategy proposed by the algorithm allows the drone to change the original path before entering the new risk zone. It could ensure that the risk cost from the new risk zone is mitigated and the increase in path length is minimal.
In order to further study new risk zones, this paper investigates the effect of the number of new risk zones on the path planning results. As shown in Figure 11, the length of path 1 increased by about 3.99% on average with the addition of each new risk area, the service completion always remained at 1, and the path risk cost increased by about 0.30% on average.
In summary, the temporary response of the algorithm to new risk zones can reduce new risk costs on the basis of service completion. The avoidance strategy is influenced by the time when the risk zone is discovered. The above discussed that a new risk zone is discovered before the drone enters that risk zone. Because the avoidance strategy requires the drone to scan and judge whether there is a new risk zone once in each step, it can guide the drone to update the next path point in time to avoid the risk zone. In the case that the drone has already entered the new risk zone when it is found, it is obvious that the drone will change the next path point according to the strategy, thus leaving the risk zone with the shortest distance. This case does not need to be discussed.

4.4. Sensitivity Analysis on Coefficients

After the above analysis, it can be seen that the model in this paper has a good effect on mitigating the path risk cost based on the assurance of service completion. Trade-off effects of service benefits and risk costs will be discussed in this part. In the model, the parameter M b e n e f i t determines the priority for the service, thus affecting service completion. When M r i s k has a fixed value, a larger M b e n e f i t makes the drone more inclined to satisfy more customers, and the drone will bear more risk costs and path lengths due to the overlap of customer locations and risk areas. On the contrary, a smaller M b e n e f i t means that the drone will ignore some customers but reach the destination directly with a shorter path and lower risk cost. As shown in Figure 12, service completion and average risk will increase with the increase of M b e n e f i t .
Since M b e n e f i t is the coefficient of customer service benefit, its change had the most significant impact on service completion among the three indicators, which was 0.51 when M b e n e f i t = 0 and increased to 1 when M b e n e f i t = 2 with a growth ratio of 49%; while the average path length increased from 1.07 to 1.165 with a growth ratio of 8.87%; the average path risk increased from 1.385 to 1.832 with a growth ratio of 32.27%.
Average path length and average path risk increased much less than service completion. Due to the increase in M b e n e f i t , drones tend to complete more services, resulting in the drones needing to detour farther to reach the customer service area. The path risk also increased due to the overlap of customers and risk areas. However, since the minimisation objective in this paper’s model includes path length and risk cost, this constraint ensures that the path length and risk cost remain stable when customer service completion increases rapidly. It can be found that our model achieves a flexible balance of service benefit with risk and path cost by adjusting M b e n e f i t .
Similar to parameter M b e n e f i t , M r i s k controls the drone’s tolerance for risk. When M r i s k increases, drones are more inclined to avoid the risk zone to reduce path risk, which leads to a rapid decrease in the average risk. The average path risk decreases by 79.09%, with a 52.90% decrease from M r i s k = 0 to M r i s k = 10 and a 26.19% decrease from M r i s k = 11 to M r i s k = 20 . Customer service completion remained at 100% when M r i s k 10 . Due to the overlap between customer location and risk area, when M r i s k 11 , the coefficient of risk cost was much higher than customer service benefit, drones tended to avoid risk instead of serving customers in the risk area, leading to a decrease in customer service completion rate, which decreased by 25% when M r i s k = 20 .
With the increase of M r i s k , drones tend to move away from the risk area, leading to an increase in path length. Due to customer demand, the drone still needs to enter the customer area while avoiding the risk area, so the path length grows faster with an increase of 16.37% when M r i s k 10 . In the stage of M r i s k = 11 to M r i s k = 20 , the influence of the customer is significantly weaker than the risk area, which can be proved by the 25% drop in demand completion analysed above. A sufficiently large M r i s k value made the drone less likely to extend the detour distance, which can be demonstrated by the average risk value decreasing by 26.19% from M r i s k = 11 to M r i s k = 20 , which is about 50% less than M r i s k = 0 to M r i s k = 10 . The reasons mentioned above eventually led to a significant slowdown in the growth of drone path length, which increased by only 0.5% from M r i s k = 11 to M r i s k = 20 . The results for the parameter M r i s k are shown in Figure 13.
According to the analysis of the above results, it is evident that the adjustment of the coefficients M r i s k and M b e n e f i t changes the preference for risk and benefit in path planning, which leads to significant differences in the parameters of the planning results (average path length, service completion ratio, average risk cost). It also further demonstrates the importance of our proposed path planning approach that considers balancing risk cost and service benefit, which can reflect the process of completing customer service while avoiding risks in the actual operation of logistics drones.
Another critical parameter affecting drone paths in complex urban environments is the acceptable service range for customers. Due to the fact that customer locations often overlap with high risk cost areas such as buildings, pedestrians, and vehicles, part of the customer demand may be discarded if the acceptable service range decreases and the drone path needs to traverse more high-risk cost areas to complete the service. Therefore, we further analyse the impact of acceptable service range R on path planning results.
According to the results shown in Table 6, it can be seen that as the acceptable service range decreases, the overall service completion decreases significantly due to balancing the risk cost and service benefit, and the path risk cost will decrease due to ignoring some customers. The acceptable service range decreases from 200 m to 100 m, and the service completion decreases by 57.00%, while the average path risk cost only increases by 12.26%. This is because the reduction of the acceptable service range causes the drone needs to traverse more high-risk cost areas to complete the service, which is detrimental to the goal of balancing risk cost and service benefit, so the drone discards part of the customer requirement. When R = 150   m , only the service to Customer 2 was dropped due to balancing risk cost and service benefit, so service completion decreased. However, providing service to Customers 4, 5, and 6 leads to a 5.97% increase in risk cost due to the reduction in the acceptable service range.
The variation of completion degree in customer demand shows that the reduction of the acceptable service range does not affect the completion degree for Customers 1 and 3, which do not overlap with the high-risk cost area. Meanwhile, Customers 2, 4, 5, and 6, which overlap with high-risk cost areas, were not served. The comparative experimental results of adjusting the risk cost preference parameter M r i s k also demonstrate that the purpose of discarding some customer demands is to balance the service benefits and risk costs. For the case that the acceptable service range was 100 m, the drone path accepted a higher risk cost when M r i s k = 5 ; thus, Customers 4, 5, and 6 that were not served at M r i s k = 20 could be served, and the service completion was improved to 90%. While path risk costs increased by 83.06% due to serving customers whose acceptable service ranges overlap with high risk cost areas.
In summary, it is important to improve the acceptable service range of customers for logistics drone risk management. Logistics drone companies also need to adjust the risk cost and service benefit preferences according to the acceptable service range and customers’ location in order to ensure service quality.

4.5. Algorithm Effectiveness Comparison

We propose path point generation rules with an exploration strategy to adapt the scenario for multi-drone logistics operations in urban environments and verify the effectiveness of our algorithm in this section. The A* algorithm [55] is a standard algorithm for path planning by limiting the selectable actions of drone movements. We consider that both the A* algorithm and the algorithm proposed in this paper are node-based optimal algorithms, while the A* algorithm performs local merit by limiting the candidate nodes at the current location when selecting the next location. The algorithm in this paper is a global merit algorithm that selects any point within the map in the form of probability by setting heuristic factors. So, we take the A* algorithm as the benchmark for comparison, which is a more relevant comparison. In addition, we choose the genetic algorithm as another comparison algorithm because it treats paths as individuals and selects individuals with higher fitness through the calculation of individual fitness functions. This approach is consistent with the global merit strategy for node search, and the comparison shows the effectiveness of the method in this paper more clearly.
Based on the A* algorithm, at each step of path planning, a drone can choose among one of a fixed number of equally distributed directions to move one unit step. In our experiments, we set up eight directions for drones and thus have eight candidate nodes p i for a drone to choose from at each step. To apply the A* algorithm in the constructed environment, it is required to specify the cost-benefit function of performing an optional action at the current location, as shown in Equation (24)
A i P i = d i , p i + M r i s k R P i + M b e n e f i t 1 + P i s ( p j , R ) C b ( C d e m a n d j )
where i is the current position, p i is the candidate point specified for the next step, d i , p i is the Euclidean distance between i and p i , R P i and C b ( C d e m a n d j ) are risk cost and service benefit consistent with the previous definition.
For genetic algorithms, we need to specify the calculation of individual fitness, as shown in Equation (25)
A i = 1 d i + 1 M r i s k R i + C b i C d e m a n d 0 C d e m a n d e n d M b e n e f i t
where i is the i -th path individual, d i is the path length of individual i , R i is the total path risk cost of individual i , C d e m a n d e n d is the remaining customer demand after the drone provides service by path, C d e m a n d 0 is the initial total customer demand, C b i C d e m a n d 0 C d e m a n d e n d is the benefit of the service completed by path i .
According to the comparison with the results of the genetic algorithm, the quality of the results obtained by the algorithm in this paper is basically consistent with the method of directly generating the overall path. There was a difference in path length of about 2% and a difference in risk cost of about 5%. The similarities in the values and trends of the results demonstrate that applying the global merit strategy in the node search process can improve the quality of the results. Service completion is the most important index to measure the result of logistics service path planning in a complex urban environment. As shown in Table 7 and Table 8, compared with the A* algorithm, the service completion of our algorithm is significantly higher, with an improvement of 20–40%. The path planning results of the algorithm in this paper have a slightly higher average risk than the A* algorithm. While the difference between the two algorithms’ path lengths remains between 1 and 2%, proving that the increase in risk basically comes from the existence of an overlap between the customer location and the risk area.
The mentioned indexes show that the proposed search rule promotes the drone’s exploration of the environment compared to the A* algorithm. Furthermore, the shortest path could be found based on the guarantee of completing the service. In addition, the algorithm can flexibly respond to the change of risk factor k, which ensures the risk tolerance of drones. It avoids the situation that the original algorithm cannot complete the path planning in the complex environment.
As M r i s k increased significantly, the drone was more sensitive to risks in the environment. This is equivalent to a more complex risk area in the environment, which requires more detours to avoid, and the A* algorithm fails to find a valid path and deadlocks in this situation. The path search rule proposed in this study still guarantees 100% service completion, while the average path length and average risk have a smooth change. It indicates that the solving ability of our algorithm is still acceptable.
As for the benefit coefficient M b e n e f i t , the search rule proposed in this study can better show the change in the preference for customer demand. The service completion was 100% when M b e n e f i t = 0.2 , which increased by 34% compared with M b e n e f i t = 0.01 , and remained at 100% completion. For the A* algorithm, when M b e n e f i t = 0.2 , the service completion was 61%, with an increase of 16%, indicating that the A* algorithm is worse in response to the demand factor M b e n e f i t . The main reason for this difference is that the path search rule proposed in this paper can guarantee a comprehensive exploration of the environment.

4.6. External Validity Analysis

The effectiveness of the proposed path planning model needs to be validated in balancing risk costs and service benefits when extended to other urban environments. In this work, external validity is performed, and 100 different urban environments are randomly generated.
Randomly generated pedestrian density and vehicle density were in the range [ 5 , 25 ] × 10 3 ( p e o p l e / k m 2 ) [56]. The buildings in all environments had randomly generated variance σ . The flight area range was 1000 × 1000   m and was divided into 50 × 50 grid areas. We set up the customer area to be served and assigned a random initial demand of d j ( 0 , 10 ] . The results of path planning without considering risk and the cost-benefit model proposed in this paper were calculated separately in 100 independent environments. The path risk costs obtained from these two methods were compared to demonstrate the risk mitigation effect of the model in this paper. The total risk cost for each simulation is shown in Figure 14. Among the 100 generated samples (urban model), the average customer service completion rate of the paths planned by the model in this study reached 98.68%, and all showed good risk mitigation effects.
To test the effectiveness of risk mitigation, the results were further statistically analysed to calculate the percentage of risk mitigation at the 95% confidence level. Two sample groups were considered, the risk-mitigated group (Group 1) and the risk-unmitigated group (Group 2). There were 100 samples within each group. Due to the large sample size ( n 1 , n 2 30 ) , a normal distribution could be used to calculate confidence intervals. The results of calculating the sample means ( x 1 ¯ and x 2 ¯ ) and sample variances ( s 1 2 and s 2 2 ) for the two groups are shown in Table 9. μ 1 and μ 2 are the population means. ( μ 2 μ 1 ) / x 2 ¯ is the confidence interval for the risk mitigation effect, where μ 2 μ 1 was estimated by the following equation: ( x 2 ¯ x 1 ¯ ) ± Z α / 2 s 1 2 / n 1 + s 2 2 / n 2 .
The results show the 95% confidence interval for the risk mitigation effect ( μ 2 μ 1 ) / x 2 ¯ [ 0.6962 , 0.7312 ] . In any urban environment, path planning with the cost-benefit model proposed in this paper mitigates the average total risk by [ 69.62 % , 73.12 % ] at the 95% confidence level and can effectively reduce the risk cost of path planning results for all types of urban environments based on customer service completion.

5. Conclusions

Owing to the complexity of the urban environment, it is still a challenging task to mitigate the security threats from drones while ensuring service completion in logistics drone path planning. To address this issue, we propose a model that couples customers and risk, and guides path planning in logistics drones by means of quantifying and balancing the risk cost and service benefit. The results show that compared to traditional approaches considering only obstacle avoidance, the model proposed in this paper can capture various risks and customers dispersed in all types of urban patterns and mitigate the path risk while ensuring customer service completion. In addition, the different risk and benefit preferences would greatly affect the path planning results, which further demonstrates the importance of our proposed model for balancing risk cost and service benefit. Furthermore, the proposed path search rules with heuristic factors outperform the quality of results in traditional algorithms in complex environments. It is well known that other customer demands and risk areas also exist. For instance, convective weather also has a significant influence on the integrated risk model. In addition, the customer demand model could also consider some more conditions, such as the time window for acceptable service, customer location movement, etc. Therefore, the present work would be further investigated in subsequence research to build a more realistic logistics drone path planning model driven by more customer demands and risk areas.

Author Contributions

Conceptualization, J.L. and Q.S.; methodology, J.L. and Q.S.; formal analysis, J.L. and R.L.; writing—original draft preparation, J.L., R.L. and X.G.; writing—review and editing, J.Z.; supervision, Q.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the National Natural Science Foundation of China (Grant no. 71874081), the Natural Science Foundation of Jiangsu Province (Grant no. BK20201296), the Fundamental Research Funds for Nanjing University of Aeronautics and Astronautics (Grant no. NS2022065), and the Qing Lan Project of the Jiangsu Province.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The author declares no conflict of interest.

References

  1. Placek, M. Global Parcel Shipping Volume between 2013 and 2027. Available online: https://www.statista.com/statistics/1139910/parcel-shipping-volume-worldwide/ (accessed on 2 October 2022).
  2. Ranathunga, M.I.D.; Wijayanayake, A.N.; Niwunhella, D.H.H. Simulation-Based Efficiency Assessment of Integrated First-Mile Pickup and Last-Mile Delivery in an E-Commerce Logistics Network. In Proceedings of the 2022 International Research Conference on Smart Computing and Systems Engineering (SCSE), Colombo, Sri Lanka, 1 September 2022; pp. 246–253. [Google Scholar]
  3. Borghetti, F.; Caballini, C.; Carboni, A.; Grossato, G.; Maja, R.; Barabino, B. The Use of Drones for Last-Mile Delivery: A Numerical Case Study in Milan, Italy. Sustainability 2022, 14, 1766. [Google Scholar] [CrossRef]
  4. Kim, J.J.; Kim, I.; Hwang, J. A change of perceived innovativeness for contactless food delivery services using drones after the outbreak of COVID-19. Int. J. Hosp. Manag. 2021, 93, 102758. [Google Scholar] [CrossRef]
  5. Eun, J.; Song, B.D.; Lee, S.; Lim, D.-E. Mathematical Investigation on the Sustainability of UAV Logistics. Sustainability 2019, 11, 5932. [Google Scholar] [CrossRef] [Green Version]
  6. Aurambout, J.-P.; Gkoumas, K.; Ciuffo, B. Last mile delivery by drones: An estimation of viable market potential and access to citizens across European cities. Eur. Transp. Res. Rev. 2019, 11, 30. [Google Scholar] [CrossRef] [Green Version]
  7. Bányai, T. Impact of the Integration of First-Mile and Last-Mile Drone-Based Operations from Trucks on Energy Efficiency and the Environment. Drones 2022, 6, 249. [Google Scholar] [CrossRef]
  8. Levasseur, B.; Bertrand, S.; Raballand, N.; Viguier, F.; Goussu, G. Accurate Ground Impact Footprints and Probabilistic Maps for Risk Analysis of UAV Missions. In Proceedings of the 2019 IEEE Aerospace Conference, Big Sky, MT, USA, 2–9 March 2019. [Google Scholar]
  9. Yin, C.; Xiao, Z.Y.; Cao, X.B.; Xi, X.; Yang, P.; Wu, D.P. Offline and Online Search: UAV Multiobjective Path Planning Under Dynamic Urban Environment. IEEE Internet Things J. 2018, 5, 546–558. [Google Scholar] [CrossRef]
  10. Nikodem, F.; Bierig, A.; Dittrich, J. The New Specific Operations Risk Assessment Approach for UAS Regulation Compared to Common Civil Aviation Risk Assessment. In Proceedings of the DLRK 2018, Friedrichshafen, Deutschland, 4–6 September 2018. [Google Scholar]
  11. Shi, K.X.; Zhang, H.W.; Zhang, Z.Z.; Zhou, X.G. The Algorithm of Terminal Logistics Path Planning Based on TSP Problem. In Proceedings of the International Conference on Artificial Intelligence and Computer Engineering (ICAICE), Beijing, China, 23–25 October 2020; pp. 130–133. [Google Scholar]
  12. Murray, C.C.; Chu, A.G. The flying sidekick traveling salesman problem: Optimization of drone-assisted parcel delivery. Transp. Res. Part C Emerg. Technol. 2015, 54, 86–109. [Google Scholar] [CrossRef]
  13. Agatz, N.; Bouman, P.; Schmidt, M. Optimization Approaches for the Traveling Salesman Problem with Drone. Transp. Sci. 2018, 52, 965–981. [Google Scholar] [CrossRef]
  14. de Freitas, J.C.; Vaz Penna, P.H. A variable neighborhood search for flying sidekick traveling salesman problem. Int. Trans. Oper. Res. 2020, 27, 267–290. [Google Scholar] [CrossRef]
  15. Schermer, D.; Moeini, M.; Wendt, O. A Variable Neighborhood Search Algorithm for Solving the Vehicle Routing Problem with Drones; Technical Report BISOR-02/2018; Technical University of Kaiserslautern: Kaiserslautern, Germany, 2018. [Google Scholar]
  16. Mitici, M.; Blom, H.A.P. Mathematical Models for Air Traffic Conflict and Collision Probability Estimation. IEEE Trans. Intell. Transp. Syst. 2019, 20, 1052–1068. [Google Scholar] [CrossRef]
  17. Bertrand, S.; Raballand, N.; Viguier, F. Evaluating Ground Risk for Road Networks Induced by UAV Operations. In Proceedings of the 2018 International Conference on Unmanned Aircraft Systems (ICUAS), Dallas, TX, USA, 12–15 June 2018. [Google Scholar]
  18. Koh, C.H.; Low, K.H.; Li, L.; Zhao, Y.; Deng, C.; Tan, S.K.; Chen, Y.; Yeap, R.C.; Li, X. Weight threshold estimation of falling UAVs (Unmanned Aerial Vehicles) based on impact energy. Transp. Res. Part C Emerg. Technol. 2018, 93, 228–255. [Google Scholar] [CrossRef]
  19. Clothier, R.A.; Williams, B.P.; Hayhurst, K.J. Modelling the risks remotely piloted aircraft pose to people on the ground. Saf. Sci. 2018, 101, 33–47. [Google Scholar] [CrossRef] [PubMed]
  20. Zhang, J.; Yang, S.; Li, Y.; Wu, X. A flight conflict detection model for UAV based on four-dimensional coordinates. Int. J. Comput. Appl. Technol. 2019, 60, 51–56. [Google Scholar] [CrossRef]
  21. Liu, Z. Collision risk of crossing airlines at the same altitude based on REICH model. J. Shenzhen University. Sci. Eng. 2020, 37, 136–142. [Google Scholar] [CrossRef]
  22. Brooker, P. Airborne Separation Assurance Systems: Towards a work programme to prove safety. Saf. Sci. 2004, 42, 723–754. [Google Scholar] [CrossRef] [Green Version]
  23. Zhang, Z.; Shi, R. Research on Collision Risk Model in Free Flight Based on Position Error. In Geo-Informatics in Resource Management and Sustainable Ecosystem, GRMSE 2015: Communications in Computer and Information Science; Springer: Berlin/Heidelberg, 2016; Volume 569, pp. 795–803. [Google Scholar]
  24. Bauer, P.; Hiba, A.; Bokor, J.; Zarándy, Á. Three Dimensional Intruder Closest Point of Approach Estimation Based-on Monocular Image Parameters in Aircraft Sense and Avoid. J. Intell. Robot. Syst. 2019, 93, 261–276. [Google Scholar] [CrossRef] [Green Version]
  25. Chakravarthy, A.; Ghose, D. Generalization of the collision cone approach for motion safety in 3-D environments. Auton. Robot. 2012, 32, 243–266. [Google Scholar] [CrossRef]
  26. Fan, S.; Wu, G.; Wang, L.; Liu, Y.; Li, L.; Qi, Q. Path Planning for Flight Vehicle by Using Modified Artificial Potential Field Method. Aerosp. Control 2018, 36, 50–54. [Google Scholar]
  27. Tang, J.; Pan, R.; Zhou, S.; Wang, W.; Zou, R. An Improved Artificial Potential Field Method Integrating Simulated Electric Potential Field. Electron. Opt. Control 2020, 27, 69–73. [Google Scholar]
  28. Ma, N.; Cao, Y.; Wang, X.; Wang, Z.; Sun, H. A Fast path re-planning method for UAV based on improved A* algorithm. In Proceedings of the 3rd International Conference on Unmanned Systems (ICUS), Harbin, China, 27–28 November 2020; pp. 462–467. [Google Scholar]
  29. Koenig, S.; Likhachev, M. Improved fast replanning for robot navigation in unknown terrain. In Proceedings of the 2002 IEEE International Conference on Robotics and Automation (Cat. No.02CH37292), Washington, DC, USA, 11–15 May 2002; Volume 1, pp. 968–975. [Google Scholar]
  30. De Filippis, L.; Guglieri, G.; Quagliotti, F. Path Planning Strategies for UAVS in 3D Environments. J. Intell. Robot. Syst. 2012, 65, 247–264. [Google Scholar] [CrossRef]
  31. Nash, A.; Koenig, S.; Tovey, C. Lazy Theta*: Any-Angle Path Planning and Path Length Analysis in 3D. Proc. AAAI Conf. Artif. Intell. 2010, 24, 147–154. [Google Scholar] [CrossRef]
  32. Hrabar, S. 3D Path Planning and Stereo-based Obstacle Avoidance for Rotorcraft UAVs. In Proceedings of the 2008 IEEE/RSJ International Conference on Intelligent Robots and Systems, Nice, France, 22–26 September 2008; pp. 807–814. [Google Scholar]
  33. Geem, Z.W.; Kim, J.; Loganathan, G.V. A New Heuristic Optimization Algorithm: Harmony Search. Simulation 2001, 76, 60–68. [Google Scholar] [CrossRef]
  34. Wang, X.; Meng, X. UAV Online Path Planning Based on Improved Genetic Algorithm. In Proceedings of the 38th Chinese Control Conference (CCC), Guangzhou, China, 27–30 July 2019; pp. 4101–4106. [Google Scholar]
  35. Shahidi, N.; Esmaeilzadeh, H.; Abdollahi, M.; Lucas, C. Memetic Algorithm Based Path Planning for a Mobile Robot. Int. J. Inf. Technol. 2004, 1, 56–59. [Google Scholar]
  36. Foo, J.; Knutzon, J.; Kalivarapu, V.; Oliver, J.; Winer, E. Path Planning of Unmanned Aerial Vehicles Using B-Splines and Particle Swarm Optimization. J. Aerosp. Comput. Inf. Commun. 2009, 6, 271–290. [Google Scholar] [CrossRef]
  37. Huan, L.; Ning, Z.; Qiang, L. UAV Path Planning Based on an Improved Ant Colony Algorithm. In Proceedings of the 4th International Conference on Intelligent Autonomous Systems (ICoIAS), Wuhan, China, 14–16 May 2021; pp. 357–360. [Google Scholar]
  38. Hassanzadeh, I.; Madani, K.; Badamchizadeh, M.A. Mobile robot path planning based on shuffled frog leaping optimization algorithm. In Proceedings of the 2010 IEEE International Conference on Automation Science and Engineering, Toronto, ON, Canada, 21–24 August 2010; pp. 680–685. [Google Scholar]
  39. Guan-Ting, T.; Jih-Gau, J. Path Planning and Obstacle Avoidance Based on Reinforcement Learning for UAV Application. In Proceedings of the 2021 International Conference on System Science and Engineering (ICSSE), Ho Chi Minh City, Vietnam, 26–28 August 2021; pp. 352–355. [Google Scholar]
  40. Ju-Shan, L.; Hsiao-Ting, C.; Rung-Hung, G. Decentralized Planning-Assisted Deep Reinforcement Learning for Collision and Obstacle Avoidance in UAV Networks. In Proceedings of the 2021 IEEE 93rd Vehicular Technology Conference (VTC2021-Spring), Helsinki, Finland, 25–28 April 2021; pp. 1–7. [Google Scholar]
  41. Park, J.; Jang, S.; Shin, Y. Indoor Path Planning for an Unmanned Aerial Vehicle via Curriculum Learning. In Proceedings of the 2021 21st International Conference on Control, Automation and Systems (ICCAS), Jeju, Republic of Korea, 12–15 October 2021; pp. 529–533. [Google Scholar]
  42. Ghasri, M.; Maghrebi, M. Factors affecting unmanned aerial vehicles’ safety: A post-occurrence exploratory data analysis of drones’ accidents and incidents in Australia. Saf. Sci. 2021, 139, 105273. [Google Scholar] [CrossRef]
  43. Neogi, N.A.; Quach, C.C.; Dill, E. A Risk Based Assessment of a small UAS Cargo Delivery Operation in Proximity to Urban Areas. In Proceedings of the IEEE/AIAA 37th Digital Avionics Systems Conference (DASC), London, UK, 23–27 September 2018; pp. 111–119. [Google Scholar]
  44. Enayati, S.; Goeckel, D.L.; Houmansadr, A.; Pishro-nik, H. Privacy-Preserving Path-Planning for UAVs. In Proceedings of the 2022 International Symposium on Networks, Computers and Communications (ISNCC), Shenzhen, China, 19–22 July 2022; pp. 1–6. [Google Scholar]
  45. Bertrand, S.; Raballand, N.; Viguier, F.; Muller, F. Ground Risk Assessment for Long-Range Inspection Missions of Railways by UAVs. In Proceedings of the 2017 International Conference on Unmanned Aircraft Systems (ICUAS), Miami, FL, USA, 13–16 June 2017. [Google Scholar]
  46. Hu, X.; Pang, B.; Dai, F.; Low, K.H. Risk Assessment Model for UAV Cost-Effective Path Planning in Urban Environments. IEEE Access 2020, 8, 150162–150173. [Google Scholar] [CrossRef]
  47. 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]
  48. Rappaport, J. Consumption Amenities and City Population Density. Reg. Sci. Urban Econ. 2008, 38, 533–552. [Google Scholar] [CrossRef]
  49. Yao, Y.; Liu, X.; Li, X.; Zhang, J.; Zhaotang, L.; Mai, K.; Zhang, Y. Mapping fine-scale population distributions at the building level by integrating multi-source geospatial big data. Int. J. Geogr. Inf. Sci. 2017, 31, 1220–1244. [Google Scholar] [CrossRef]
  50. Zhang, N.; Zhang, M.; Low, K. 3D path planning and real-time collision resolution of multirotor drone operations in complex urban low-altitude airspace. Transp. Res. Part C Emerg. Technol. 2021, 129, 103123. [Google Scholar] [CrossRef]
  51. Usui, H. Statistical distribution of building lot depth: Theoretical and empirical investigation of downtown districts in Tokyo. Environ. Plan. B Urban Anal. City Sci. 2019, 46, 1499–1516. [Google Scholar] [CrossRef]
  52. Liu, C.; Yang, S.; Cui, Y.; Yang, Y. An improved risk assessment method based on a comprehensive weighting algorithm in railway signaling safety analysis. Saf. Sci. 2020, 128, 104768. [Google Scholar] [CrossRef]
  53. Choudhry, A.; Moon, B.; Patrikar, J.; Samaras, C.; Scherer, S. CVaR-based Flight Energy Risk Assessment for Multirotor UAVs using a Deep Energy Model. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021. [Google Scholar]
  54. Di Franco, C.; Buttazzo, G. Energy-aware Coverage Path Planning of UAVs. In Proceedings of the 2015 IEEE International Conference on Autonomous Robot Systems and Competitions, Vila Real, Portugal, 8–10 April 2015. [Google Scholar]
  55. Sharma, K.; Swarup, C.; Pandey, S.K.; Kumar, A.; Doriya, R.; Singh, K.; Singh, T. Early Detection of Obstacle to Optimize the Robot Path Planning. Drones 2022, 6, 265. [Google Scholar] [CrossRef]
  56. Wikipedia. List of Cities Proper by Population. Available online: https://en.wikipedia.org/wiki/List_of_cities_proper_by_population_density (accessed on 11 October 2022).
Figure 1. The technology framework of the proposed work.
Figure 1. The technology framework of the proposed work.
Drones 06 00418 g001
Figure 2. Risk cost mitigation affects path planning results.
Figure 2. Risk cost mitigation affects path planning results.
Drones 06 00418 g002
Figure 3. Drones and pedestrians.
Figure 3. Drones and pedestrians.
Drones 06 00418 g003
Figure 4. Drones and vehicles.
Figure 4. Drones and vehicles.
Drones 06 00418 g004
Figure 5. Gravity model for pedestrian distribution.
Figure 5. Gravity model for pedestrian distribution.
Drones 06 00418 g005
Figure 6. Drones and buildings.
Figure 6. Drones and buildings.
Drones 06 00418 g006
Figure 7. The path planning based on risk and customer.
Figure 7. The path planning based on risk and customer.
Drones 06 00418 g007
Figure 8. Environment modelling and path planning.
Figure 8. Environment modelling and path planning.
Drones 06 00418 g008
Figure 9. Impact of different risk combinations in the environment on path planning.
Figure 9. Impact of different risk combinations in the environment on path planning.
Drones 06 00418 g009
Figure 10. Path replanning due to new risk zones.
Figure 10. Path replanning due to new risk zones.
Drones 06 00418 g010
Figure 11. Path replanning due to new risk zones.
Figure 11. Path replanning due to new risk zones.
Drones 06 00418 g011
Figure 12. Sensitivity analysis of the parameter M b e n e f i t ( M r i s k = 5 ).
Figure 12. Sensitivity analysis of the parameter M b e n e f i t ( M r i s k = 5 ).
Drones 06 00418 g012
Figure 13. Sensitivity analysis of the parameter M r i s k ( M b e n e f i t = 0.5 ).
Figure 13. Sensitivity analysis of the parameter M r i s k ( M b e n e f i t = 0.5 ).
Drones 06 00418 g013
Figure 14. Mitigation effects of path risk in 100 urban environments.
Figure 14. Mitigation effects of path risk in 100 urban environments.
Drones 06 00418 g014
Table 1. Sheltering coefficients [47].
Table 1. Sheltering coefficients [47].
S f Type of Shelters
0None
0.25Trees
0.50Low-rise buildings
0.75High-rise buildings
1Industrial buildings
Table 2. Simulation parameters.
Table 2. Simulation parameters.
ParametersValueParametersValue
l min / m 2 ρ V / v e h i c l e m - 1 7.12 × 10 3
P c r a s h 6.04 × 10 5 N V 0.25
ρ A / k g m - 3 1.23 α i , α j , α k 0.50, 0.25, 0.25
f d 0.30 χ , ψ 2, 8
S d / m 2 0.02 R / m 200
ν / k g m 2 s 2 232 M r i s k , M b e n e f i t 20, 1
μ / k g m 2 s 2 106 C / A s 1/144
ρ p / p e o p l e m - 2 0.007 V n / k g m 2 A 1 s 3 22.80
S V ¯ / m 2 9.68 W / k g 20
D r o a d / m 20n6
η 0.70 ε 0.50
Table 3. Comparison of path planning results.
Table 3. Comparison of path planning results.
Path GroupAverage Path Length/kmCompletion RatioAverage Risk Cost
Cost-effective path1.241.006.20
No risk considered path1.111.0033.07
No customer considered path1.190.433.01
Table 4. Split comparison of path risk costs.
Table 4. Split comparison of path risk costs.
Risk CostGroup AGroup BGroup CGroup DGroup E
Total Risk Cost6.2018.4019.879.5533.07
Pedestrian Risk Cost R13.353.5615.485.6416.62
Vehicle Risk Cost R22.6614.473.112.8615.11
Building Risk Cost R30.190.371.281.051.33
Table 5. Results of path replanning.
Table 5. Results of path replanning.
Drone 1Path Length/kmCompletion RatioPath Risk Cost
Original Path1.6215.20
Replanning Path1.6915.22
Table 6. Sensitivity analysis of the parameter R .
Table 6. Sensitivity analysis of the parameter R .
R /m M r i s k Completion RatioAverage Risk CostUnserved Customers
2002016.20None
150200.906.57Customer 2
100200.435.44Customers 2, 4, 5, and 6
10050.9011.35Customer 2
Table 7. Comparison of the planning results of the two algorithms by varying M b e n e f i t .
Table 7. Comparison of the planning results of the two algorithms by varying M b e n e f i t .
M b e n e f i t
( M r i s k = 5 )
Proposed AlgorithmA* AlgorithmGenetic Algorithm
CompletionRatioPath LengthRisk CostCompletionRatioPath LengthRisk CostCompletionRatioPath LengthRisk Cost
0.010.661.081.410.451.100.500.651.101.50
0.050.691.141.570.491.140.510.691.151.64
0.10.731.141.600.541.130.550.741.151.70
0.150.741.171.790.541.150.550.741.171.84
0.21.001.171.830.611.150.5411.181.91
0.251.001.171.830.611.160.5411.181.91
0.51.001.212.420.611.190.5411.222.50
11.001.213.620.611.190.5411.233.81
21.001.213.630.611.190.5411.233.81
51.001.213.630.611.190.5411.233.81
Table 8. Comparing the planning results of the two algorithms by varying M r i s k .
Table 8. Comparing the planning results of the two algorithms by varying M r i s k .
M r i s k
( M b e n e f i t = 0.5 )
Proposed AlgorithmA* AlgorithmGenetic Algorithm
CompletionRatioPath LengthRisk CostCompletionRatioPath LengthRisk CostCompletionRatioPath LengthRisk Cost
11.001.092.860.581.100.7311.122.99
21.001.162.720.581.150.6211.182.90
31.001.182.500.591.160.6111.132.83
41.001.202.450.601.190.6111.212.69
51.001.212.420.611.190.5411.252.56
101.001.231.65 11.271.87
200.751.240.600.761.280.73
500.601.260.590.581.290.71
750.601.260.590.571.290.70
1000.601.260.580.571.290.70
Table 9. Statistical analysis parameters of the risk-mitigated group and the risk-unmitigated group.
Table 9. Statistical analysis parameters of the risk-mitigated group and the risk-unmitigated group.
Group 1Group 2
Sample Size n 1 = 100 n 2 = 100
Sample Means x 1 ¯ = 10.02 x 2 ¯ = 34.99
Sample Variances s 1 2 = 8.14 s 2 2 = 31.13
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Shao, Q.; Li, J.; Li, R.; Zhang, J.; Gao, X. Study of Urban Logistics Drone Path Planning Model Incorporating Service Benefit and Risk Cost. Drones 2022, 6, 418. https://doi.org/10.3390/drones6120418

AMA Style

Shao Q, Li J, Li R, Zhang J, Gao X. Study of Urban Logistics Drone Path Planning Model Incorporating Service Benefit and Risk Cost. Drones. 2022; 6(12):418. https://doi.org/10.3390/drones6120418

Chicago/Turabian Style

Shao, Quan, Jiaming Li, Ruoheng Li, Jiangao Zhang, and Xiaobo Gao. 2022. "Study of Urban Logistics Drone Path Planning Model Incorporating Service Benefit and Risk Cost" Drones 6, no. 12: 418. https://doi.org/10.3390/drones6120418

Article Metrics

Back to TopTop