Next Article in Journal
Task Travel Time Prediction Method Based on IMA-SURBF for Task Dispatching of Heterogeneous AGV System
Previous Article in Journal
Design and Implementation of a Biomimetic Underwater Robot Propulsion System Inspired by Bullfrog Hind Leg Movements
Previous Article in Special Issue
White Shark Optimization for Solving Workshop Layout Optimization Problem
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

EAB-BES: A Global Optimization Approach for Efficient UAV Path Planning in High-Density Urban Environments

1
School of Internet, Jiaxing Vocational and Technical College, Jiaxing 314036, China
2
Jiaxing Key Laboratory of Industrial Internet Security, Jiaxing Vocational and Technical College, Jiaxing 314036, China
3
School of Automation, Nanjing University of Science and Technology, Nanjing 210094, China
*
Authors to whom correspondence should be addressed.
Biomimetics 2025, 10(8), 499; https://doi.org/10.3390/biomimetics10080499 (registering DOI)
Submission received: 12 June 2025 / Revised: 18 July 2025 / Accepted: 30 July 2025 / Published: 31 July 2025
(This article belongs to the Special Issue Biomimicry for Optimization, Control, and Automation: 3rd Edition)

Abstract

This paper presents a multi-strategy enhanced bald eagle search algorithm (EAB-BES) for 3D UAV path planning in urban environments. EAB-BES addresses key limitations of the traditional bald eagle search (BES) algorithm, including slow convergence, susceptibility to local optima, and poor adaptability in complex urban scenarios. The algorithm enhances solution space exploration through elite opposition-based learning, balances global search and local exploitation via an adaptive weight mechanism, and refines local search directions using block-based elite-guided differential mutation. These innovations significantly improve BES’s convergence speed, path accuracy, and adaptability to urban constraints. To validate its effectiveness, six high-density urban environments with varied obstacles were used for comparative experiments against nine advanced algorithms. The results demonstrate that EAB-BES achieves the fastest convergence speed and lowest stable fitness values and generates the shortest, smoothest collision-free 3D paths. Statistical tests and box plot analysis further confirm its superior performance in multiple performance metrics. EAB-BES has greater competitiveness compared with the comparative algorithms and can provide an efficient, reliable and robust solution for UAV autonomous navigation in complex urban environments.

1. Introduction

In recent years, unmanned aerial vehicles (UAVs) have proliferated in various fields, including aerial photography [1], surveillance [2,3], delivery services [4] and disaster relief operations [5,6]. Their capability to operate in three-dimensional (3D) spaces provides unique advantages in scenarios where traditional ground-based or two-dimensional (2D) systems are insufficient.
However, UAV navigation in complex environments faces significant challenges due to obstacles such as mountains, buildings, and power lines [7,8], posing risks and restricting UAV operations. UAV path planning aims to determine optimal or near-optimal trajectories that avoid obstacles and satisfy constraints. The complexity of path planning significantly increases in 3D environments compared to 2D scenarios [9].
Many existing UAV path planning algorithms, such as A* [10], rapidly exploring random trees (RRT) [11,12], and probabilistic roadmaps (PRM) [13], heavily rely on pre-generated global environment maps [14]. This dependency makes real-time path planning difficult, especially in dynamic and large-scale environments [15,16]. Furthermore, the computational complexity increases exponentially with search space expansion, limiting real-time applicability [17].
Nature-inspired swarm intelligence algorithms offer promising alternatives due to their adaptability, distribution, and self-organization characteristics [18,19,20,21]. Among these, the Bald Eagle Search (BES) algorithm [22], inspired by bald eagle foraging behavior, has gained attention for its simplicity and powerful global search capability. BES balances exploration and exploitation through selection, search, and swooping stages. Despite its strengths, BES still suffers from slow convergence and susceptibility to local optima, limiting its effectiveness in complex urban environments. Nature-inspired swarm intelligence algorithms offer promising alternatives due to their adaptability, distribution, and self-organization characteristics [18,19,20,21]. Among these, the Bald Eagle Search (BES) algorithm [22], inspired by bald eagle foraging behavior, has gained attention for its simplicity and powerful global search capability. BES balances exploration and exploitation through selection, search, and swooping stages. Despite its strengths, BES still suffers from slow convergence and susceptibility to local optima, limiting its effectiveness in complex urban environments. Inspired by biological behaviors, BES belongs to the family of biomimetic algorithms that model animal foraging and survival strategies to solve complex computational problems. This study builds on this biomimetic foundation by enhancing BES with biologically plausible strategies that mimic elite guidance, adaptive response, and localized mutation, thereby improving its performance in challenging UAV path planning scenarios.
In this work, we propose an enhanced version of BES named EAB-BES, which incorporates three strategies: elite opposition-based learning, adaptive weight mechanism, and block-based elite-guided differential mutation. And apply the EAB-BES algorithm to the three-dimensional path planning problem of unmanned aerial vehicles in urban environments. The innovation of this work lies in the strategic integration and architectural synergy of these mechanisms within the BES algorithm framework to overcome its specific limitations. The three-stage structure of BES itself is more suitable for urban hierarchical path modeling. This significantly improves the performance of complex 3D UAV path planning. By introducing these strategies, EAB-BES significantly improves convergence speed, path accuracy, and obstacle avoidance capabilities in urban settings. Traditional BES is prone to getting stuck in local solutions during the swooping phase, especially in the synthesis strategy, where the block-based elite-guided differential mutation strategy generates directional perturbation vectors through subgroup competition, making it easy to escape from local optima. The key contributions of this paper are as follows:
  • Developed a specialized 3D UAV path planning model addressing collision avoidance and navigation efficiency among mixed-height urban obstacles.
  • Proposed the EAB-BES algorithm, integrating elite opposition-based learning, adaptive weighting, and block-based elite-guided differential mutation to enhance BES’s convergence speed, accuracy, and adaptability.
  • Introduced a novel block-based elite-guided differential mutation strategy for dynamically refining population subgroups, improving local optima escape ability and path robustness.
  • Validated the performance of EAB-BES through comparative experiments with 9 state-of-the-art algorithms in six high-density urban scenarios.
The rest of the paper is organized as follows: Section 2 introduces the related work. Section 3 describes preliminary concepts, including the UAV path planning problem and the basic BES algorithm. Section 4 details the proposed EAB-BES algorithm. Section 5 presents experimental results and discussions. Section 6 provides conclusions and future research directions.

2. Related Work

Research in UAV path planning has gained considerable attention due to increasing applications and complexity. Zeng et al. [23] proposed an energy-efficient communication strategy between UAVs and ground terminals. Kim et al. [24] developed a real-time UAV path planning algorithm using compensated Voronoi diagrams suitable for challenging environments like disaster areas and battlefields. Ergezer et al. [25] introduced a novel evolutionary operator for single UAV path planning, and Jayaweera et al. [26] adopted an artificial potential field (APF) method ensuring stable tracking of moving ground targets under windy conditions. Ikram et al. [27] proposed sequential block path planning (SBPP), while Fahmani et al. [28] developed a trajectory optimization method combined with UAV-based transmission line detection. Pamarthi et al. [29] designed a UAV motion planning framework for dynamic environments. Chan et al. [30] proposed an energy-efficient path planning model for UAVs navigating urban terrain influenced by wind.
Recently, numerous swarm intelligence algorithms have been applied to UAV path planning. For example, Roberge et al. [31] used genetic algorithm (GA) and particle swarm optimization (PSO) to generate feasible trajectories for fixed-wing UAVs in complex 3D scenarios. Liu et al. [32] presented a modified sparrow search algorithm (CASSA) for high-dimensional UAV route optimization. Zhao et al. [33] integrated the selfish herd optimizer (SHO) with PSO (SHOPSO) for UAV path planning, whereas Wang et al. [34] developed a modified mayfly algorithm (modMA) aimed at reducing path costs. Aslan et al. [35] designed a fast, real-time autonomous path planning approach for UAVs in large-scale environments. Yin et al. [36] proposed adaptive differential evolution with dynamic Thompson sampling (DE-DYTS) for collaborative multi-UAV path planning. Wang et al. [37] introduced an enhanced red-tailed hawk algorithm (IRTH) for practical UAV applications. Zhong et al. [38] extended reinforcement learning (RL) to cross-regional UAV path planning using improved Q-learning (QL). Zhang et al. [39] developed a multi-strategy ensemble wind-driven optimization (MEWDO) algorithm integrating cubic spline interpolation into robot path planning. Wang et al. [40] proposed an improved human evolutionary optimization algorithm (IHEOA) for UAV route optimization, and Yin et al. [41] developed a collaborative path planning strategy for unmanned surface vehicles in complex water environments with multi-stage constraints.
The Bald Eagle Search (BES) algorithm, inspired by the foraging behavior of bald eagles, has attracted significant attention due to its simplicity and strong global search capability. As a recently developed swarm intelligence algorithm [42], BES effectively balances exploration and exploitation through three stages: selection, search, and swooping. Its versatility has led to applications in diverse fields, such as engineering optimization [43,44], geometric approximation [45], biomedicine [46], mobile edge computing [47], energy storage [48], forest fire detection [49], face recognition [50], autonomous driving [51], path planning [52], water resource management [53], and IoT security [54]. However, BES still has limitations, such as slow convergence speed and susceptibility to local optima, which restrict its performance in complex urban UAV path planning tasks.
Despite the advantages of BES and other swarm intelligence algorithms, limitations remain regarding convergence speed, computational efficiency, and the ability to escape local optima. These challenges become particularly prominent in complex 3D urban environments. Therefore, further research into enhancing algorithmic performance through multi-strategy integration is essential to address these gaps.

3. Preliminary

3.1. Path Planning for UAV

UAVs are playing an increasingly crucial role in our daily lives. They have been widely used in mountainous environments, with preliminary research results achieved. However, in complex urban environments, the demands for urban logistics distribution, emergency rescue, and infrastructure inspection are growing rapidly. Given the numerous tall buildings, complex terrains, and abundant electromagnetic interference sources in cities, traditional path planning methods face difficulties. Thus, conducting UAV path planning becomes highly necessary. This paper focuses on researching UAV path planning in urban environments, aiming to enable UAVs to find safe and efficient flight paths in complex urban settings, enhance their application efficiency in urban scenarios, and ensure the smooth progress of urban-related operations.
In the context of urban-based UAV path planning, high-rise buildings and low-squat buildings are regarded as the primary obstacles to UAV flight. In a 3D urban environment, cylinders are employed to simulate high-rise buildings, while hemispheres are utilized to represent low-squat buildings.
The top-view schematic diagram of the UAV’s navigation path is shown in Figure 1. P and Q are marked as the starting and goal positions, respectively. In complex urban environments, high-rise and low-rise buildings are the main obstacles, represented by circular projections with different radii and threat levels. If a part of the UAV’s flight path enters a circular threat area, the UAV will be threatened. When the flight path does not pass through the circular projection, the path is safe. Therefore, the goal of this UAV is to obtain the optimal path from P to Q while minimizing costs as much as possible.
Our fitness function aims to comprehensively consider factors such as path length, flight altitude, and building threats to evaluate the quality of UAV paths. The fitness function in this article mainly consists of three parts: path length cost, flight height cost, and threat cost.
(1)
Path Length Cost ( F l e n g t h C o s t )
Suppose the coordinate sequence of the interpolation points is ( x 1 ( i ) , y 1 ( i ) , z 1 ( i ) ) , where i = 1 , 2 , , n , and n is the number of interpolation points. The path length cost is obtained by calculating the sum of the Euclidean distances between adjacent interpolation points, and the formula is
F l e n g h t C o s t = i = 1 n 1 ( x 1 ( i + 1 ) x 1 ( i ) ) 2 + ( y 1 ( i + 1 ) y 1 ( i ) ) 2 + ( z 1 ( i + 1 ) z 1 ( i ) ) 2 .
(2)
Flight Height Cost ( F h e i g h t C o s t )
The flight height cost consists of two parts:
Height deviation cost of intermediate navigation nodes ( F h e i g h t C o s t 1 ): Suppose the coordinate sequence of the navigation nodes is ( X s ( i ) , Y s ( i ) , Z s ( i ) ) , where i = 1 , 2 , , m , and m is the number of navigation nodes. The optimal flight height B e s t F l i H i is obtained based on terrain interpolation, and the calculation formula is
B e s t F l i H ( i ) = interp 2 ( X , Y , Z , X s ( i ) , Y s ( i ) ) + O p t i m a l _ h ,
where O p t i m a l _ h = 500 is the offset of the optimal flight height relative to the ground. Then the height deviation cost of intermediate navigation nodes is
F h e i g h t C o s t 1 = i = 2 m 1 Z s ( i ) B e s t F l i H ( i ) B e s t F l i H ( i ) .
Flight height constraint penalty cost ( F h e i g h t C o s t 2 ): The minimum flight height M i n F l i H i is obtained based on terrain interpolation, and the calculation formula is
M i n F l i H ( i ) = interp 2 ( X , Y , Z , x 1 ( i ) , y 1 ( i ) ) + M i n _ h ,
where M i n _ h = 10 is the offset of the minimum flight height relative to the ground. When z 1 ( i ) < M i n F l i H i or isnan ( M i n F l i H i ) , a penalty value P e n a l t y f = 1 × 10 6 is applied; otherwise, it is 0. Then the flight height constraint penalty cost is
F h e i g h t C o s t 2 = P e n a l t y f ,   if   z 1 ( i ) < M i n F l i H ( i )   or   isnan ( M i n F l i H ( i ) ) 0 , otherwise .
Therefore, the total flight height cost is
F h e i g h t C o s t = F h e i g h t Cos t 1 + F h e i g h t Cos t 2 .
(3)
Threat Cost ( F t h r e a t C o s t )
Let T h r e a t A ( i ) represent the threat value of the i-th interpolation point from high-rise buildings, and T h r e a t R ( i ) represent the threat value of the i-th interpolation point from low-rise buildings. P e n a l t y t = 1 × 10 3 is the threat penalty factor. Then the calculation formula for the threat cost is
F t h r e a t C o s t = P e n a l t y t i = 1 n ( T h r e a t A ( i ) + T h r e a t R ( i ) ) .
Threat value from high-rise buildings ( T h r e a t A ( i ) ): Suppose the number of high-rise buildings is p . For the j-th high-rise building, define its base center coordinates as ( x j , y j , z j ) , its base radius as r j and its height as h j . The threat value for the i-th path point is computed if the conditions below are satisfied.
Horizontal distance constraint: The horizontal projection distance from the path point to the building base must be less than the radius r j :
( x 1 ( i ) x j ) 2 + ( y 1 ( i ) y j ) 2 r j .
Vertical height constraint: The vertical coordinate of the path point must lie within the building’s height range:
z 1 ( i ) [ z j , z j + h j ] .
The threat value is formulated as follows:
T h r e a t A ( i ) = j = 1 p max r j ( x 1 ( i ) x j ) 2 + ( y 1 ( i ) y j ) 2 , 0 , if   z 1 ( i ) [ z j , z j + h j ] 0 , o t h e r w i s e .
Threat value from low-rise buildings ( T h r e a t R ( i ) ): Suppose the number of low-rise buildings is l . For the j-th high-rise building, define the center coordinates of the hemisphere as ( x j , y j , z j ) , with radius r j . The threat value for the i-th path point is computed if the conditions below are satisfied.
Three-dimensional distance constraint: The Euclidean distance from the path point to the hemisphere center must be less than the radius r j :
( x 1 ( i ) x j ) 2 + ( y 1 ( i ) y j ) 2 + ( z 1 ( i ) z j ) 2 r j .
Vertical height constraint: The path point must lie within the upper half-space covered by the hemisphere:
z 1 ( i ) z j .
The threat value is formulated as follows:
T h r e a t R ( i ) = j = 1 l max r j ( x 1 ( i ) x j ) 2 + ( y 1 ( i ) y j ) 2 + ( z 1 ( i ) z j ) 2 , 0 , if   z 1 ( i ) z j 0 , otherwise .
In order to balance the above three parts, allocation weights λ 1 ,   λ 2 ,   λ 3 are set, each being 1 / 3 . The fitness function is
F i t n e s s = λ 1 F l e n g t h C o s t + λ 2 F h e i g h t C o s t + λ 3 F t h r e a t C o s t .

3.2. Bald Eagle Search Algorithm

During the selection phase, the bald eagle accurately locates and selects the most advantageous position within the specified search space. This choice is based on the amount of food available in each region. The mathematical expression is
X i , n e w = X best + ε r ( X mean X i ) ,
where X i , n e w refers to the updated position of the i-th bald eagle. X best indicates the current optimal position of the bald eagle. The position change parameter ε has a value in the range ( 1.5 ,   2 ) , and r is a random number in the open interval ( 0 ,   1 ) . Meanwhile, X mean represents the average position of the bald eagle, and X i denotes the i-th position of a bald eagle.
After the selection phase is completed, BES enters the search phase. The algorithm systematically searches for prey within a previously determined area by mimicking the hunting actions of bald eagles. The eagle moves in a circle and gradually expands its search range in a spiral pattern. The mathematical description is
X i , n e w = X i + y ( i ) ( X i X i + 1 ) + x ( i ) ( X i X mean )
x ( i ) = x r ( i ) max ( x r ) y ( i ) = y r ( i ) max ( y r )
x r ( i ) = r ( i ) sin θ ( i ) y r ( i ) = r ( i ) cos θ ( i )
θ ( i ) = a π r a n d r ( i ) = θ ( i ) + R r a n d .
In polar space, x ( i ) and y ( i ) represent the position of the i-th bald eagle. Both values are restricted to the interval between −1 and 1. X i + 1 is the subsequent updated position of the i-th bald eagle. θ ( i ) and r ( i ) are the polar angle and polar diameter, respectively. The spiral parameters a and R fall within the intervals (5, 10) and (0.5, 2), respectively. Additionally, r a n d is a random number with a value ranging from 0 to 1.
During the swooping phase, the bald eagle will dive to catch prey locked in search space. Equation (20) describes this behavior.
X i , n e w = r a n d X best + x 1 ( i ) ( X i c 1 X mean ) + y 1 ( i ) ( X i c 2 X best )
x 1 ( i ) = x r ( i ) max ( x r ) y 1 ( i ) = y r ( i ) max ( y r )
x r ( i ) = r ( i ) sinh θ ( i ) y r ( i ) = r ( i ) cosh θ ( i )
θ ( i ) = a π r a n d r ( i ) = θ ( i ) .
The BES algorithm incorporates enhancement coefficients c 1 and c 2 , with each coefficient having a value within the range of 1 to 2. To gain a more thorough understanding of the BES algorithm, the pseudocode is presented in Algorithm 1.
Algorithm 1: The pseudo-code of BES
Input: N (population size), D (dimension), Maxiter (Maximum number of iterations),
up, lb (upper and lower bounds)
1. Randomly generated initial point X i
2. Evaluate the fitness values
3. while (t < Max_iter)
4.     for i = 1 to N
        Select stage
5.       Update individual position X i by Equation (15)
        Search stage
6.       Update individual position X i by Equation (16)
        Swooping stage
7.       Update individual position X i by Equation (20)
8.     end for
9. end while
10. Output: the optimal solution

4. Proposed EAB-BES Algorithm

This paper proposes a multi-strategy enhanced bald eagle search algorithm (EAB-BES) that integrates three critical innovations to address optimization limitations. First, an elite opposition-based learning mechanism is used for population initialization, employing bidirectional search to enhance diversity and accelerate convergence. Second, an adaptive weight factor is introduced into the iterative framework, dynamically balancing global exploration and local exploitation. Third, a block-based elite-guided differential mutation strategy partitions the population into competitive subpopulations, generating directional perturbation vectors. These vectors are modulated by a nonlinear convergence factor to balance exploration–exploitation trade-offs. By incorporating elite guidance into mutation, the strategy preserves diversity while refining the best solution, helping to avoid local optima and improving solution accuracy during fine-tuning.

4.1. Elite Opposition-Based Learning Strategy

Before the iterative optimization begins, the bald eagle population’s positions are randomly initialized. However, this randomness may expand the feasible solution range and increase search time, as the optimal solution’s location remains unknown. Population initialization significantly impacts search performance. To address this, an elite opposition-based learning (EOBL) strategy [55] is introduced. The inverse solutions (candidate solutions) are generated within the elite group’s range, and the population is updated by selecting the better solutions. This approach enhances search space exploration, improves diversity, and accelerates convergence.
EOBL introduces the dynamic information of elite individuals on the basis of basic opposition-based learning (OBL) and expands the generation interval of opposition solutions from a fixed range to a dynamic interval based on the elite group. The specific steps are as follows:
(1)
Selection of the elite group: Select the top 10% of individuals with the optimal fitness from the current population as the elite group.
(2)
Definition of the dynamic interval: Determine the dynamic boundaries according to the distribution of the elite group in the j-th dimension. a j ( t ) is the minimum value of the elite group in the j-th dimension, and b j ( t ) is the maximum value of the elite group in the j-th dimension.
(3)
Generation of opposition solutions: Combined with the random scaling coefficient k [ 0 ,   1 ] , the mathematical expression of the opposition solution x i j ( t ) is
x i j ( t ) = k ( a j ( t ) + b j ( t ) ) x i j ( t ) ,
where x i j ( t ) is the value of the current individual in the j-th dimension. Figure 2 is the schematic diagram of this strategy.
After the EOBL strategy, the fitness function value of the corresponding individual is computed. By contrasting the fitness function values between the current individual and the optimized individual, the one with a better fitness value is selected as the initial population individual. The following formula is used to optimize randomly initialized individuals:
X i = X ¯ i , f ( X ¯ i ) < f ( X i ) X i , else .

4.2. Adaptive Weight Mechanism

To balance global and local search, enhance BES convergence speed and accuracy, and prevent premature convergence, an adaptive nonlinear weighting mechanism based on exponential power attenuation is introduced [56]. Additionally, the fixed parameter controlling the spiral trajectory is modified. This mechanism dynamically adjusts the weight factor: maintaining a high value initially for stronger global exploration, accelerating decay in the middle phase to balance exploration and exploitation, and gradually slowing decay in the final stage to refine local search accuracy. The specific formula is as follows:
ω ( t ) = ω min + ( ω max ω min ) exp ( ( η t T ) μ ) ,
where t represents the current number of iterations, and T is the maximum number of iterations. ω max and ω min are the maximum and minimum values of the weight, respectively, with values of 2 and 0.2, respectively. η controls the decay rate, with a value of 4. μ adjusts the shape of the decay curve, and its value is 2. The curve of the adaptive nonlinear weight is shown in Figure 3.
Thus, the formula for the latest selection phase of the algorithm is
X i , n e w = X best + ω ( t ) r ( X mean X i ) .

4.3. Block-Based Elite-Guided Differential Mutation Strategy

In this paper, a block-based elite-guided differential mutation strategy (BEDMS) is designed. Its core objective is to balance the global exploration and local exploitation capabilities of the algorithm through the collaborative mechanism of dynamic block competition and elite guidance, effectively addressing issues such as the tendency of the traditional bald eagle search algorithm to get trapped in local optima and its insufficient convergence speed in high-dimensional nonlinear scenarios like path planning. This strategy includes the following three crucial stages [57]:
(1)
Dynamic blocking mechanism
Let the population size be N . In the t-th iteration, the population is divided into two competitive subgroups through the index permutation function i d x = randperm ( N ) :
X 1 = X i d x ( k ) |   k = 1 , ,   N / 2 X 2 = X i d x ( k ) |   k = N / 2 + 1 , , 2   N / 2 .
(2)
Generation of differential perturbation
Construct a directional mutation vector by utilizing the differences between the subgroups, and introduce the convergence factor F for nonlinear modulation:
Δ = F ( X 1 X 2 ) .
This formula ensures that the perturbation maintains high-intensity exploration in the early stage of the iteration t T and shifts to fine exploitation in the later stage t T .
(3)
Elite-guided mutation injection
Inject the perturbation into the first half of the population while retaining the information of the current optimal solution X best :
X n e w ( 1 : N / 2 ) = X best + 0.5 ( X ( 1 : N / 2 ) + Δ ) .
This operation is equivalent to constructing a dynamically shrinking search hypercube in the neighborhood of the elite solution. Its volume is controlled by the convergence factor F , and the mathematical description is as follows:
X mutant = X best + 0.5 ( X + F ( X 1 X 2 ) ) , if   r a n d < q X , otherwise .
The principle of this strategy is shown in Figure 4.
In order to demonstrate the working mechanism of the EAB-BES algorithm more clearly, a flowchart of the EAB-BES algorithm integrating these strategies and mechanisms was drawn, as shown in Figure 5. The pseudocode of the EAB-BES algorithm is shown in Algorithm 2.
Algorithm 2: The pseudo-code of EAB-BES
Input: N (population size), D (dimension), Max_iter (max iterations), up, lb (bounds)
1. Initialize population X i randomly and calculate fitness f ( X i )
2. Apply elite opposition-based learning on individual population by Equation (24)
  and calculate new f ( X i )
3. Update X i with better individuals Compare the fitness values before and
  after optimization, select the individual position X b e s t with the best fitness
  value as the optimal position.
4. while (t ≤ Max_iter)
5.  Update adaptive weight ω ( t ) by Equation (26)
6.     for i = 1 to N
        Select stage
7.        Update individual position X i by Equation (27)
        Search stage
8.        Update individual position X i by Equation (16)
        Swooping stage
9.        Update individual position X i by Equation (20)
10.     Apply a block-based elite-guided differential mutation strategy
        to the current optimal solution.
11.        if f ( X n e w ) < f ( X i )
12.           X i = X n e w
13.        end if
14.        if  f ( X n e w ) < f ( X b e s t )
15.           X b e s t = X n e w
16.        end if
17.      end for
18.      t = t + 1
19. end while
20. Output  X best

4.4. Computational Complexity Analysis

The BES exhibits a time complexity of O ( T N F D ) (where N , D , T and F represent population size, dimensionality, iterations, and fitness evaluation cost) and space complexity O ( N D ) . The EAB-BES integrates three strategies: elite opposition-based learning (doubling fitness evaluations per iteration to O ( 2 N F D ) ), difference mutation (adding O ( N D ) step-size calculations), and adaptive weighting ( O ( N ) per iteration). While preserving the asymptotic time complexity O ( T N F D ) and space complexity O ( N D ) (storing population and opposition solutions). Although the time complexity of EAB-BES is still O ( T N F D ) , the number of fitness assessments has increased, and the cost of location updates and parameter calculations has slightly increased. The spatial complexity remains unchanged, with only a small amount of parameter storage added without changing the size. EAB-BES improves performance but also increases some computational costs.

5. Experimental Results and Discussion

5.1. Experimental Setup

This study compared nine algorithms with EAB-BES, including the classic particle swarm optimization algorithm [58] (PSO), differential evolution [59] (DE), teaching-learning-based optimization [60] (TLBO), the emerging excellent algorithms—slime mold algorithm [61] (SMA) and sparrow search algorithm [62] (SSA)—and the improved high-performance algorithms—teaching learning slime mold algorithm [63] (TLSMA), chaotic sparrow search algorithm (CSSA) [64], bald eagle search algorithm [22] (BES), and modified bald eagle search algorithm (mBES) [65]. To test the performance and effectiveness of EAB-BES, these algorithms were applied to solve the path planning problem of 3D UAVs in complex urban scenes. In each experiment, each algorithm was configured to perform 200 iterations with a population size of 100, and the entire process was independently run and repeated 20 times. The dimension is set to 30. The experiment was conducted in the MATLAB R2019(a) environment. The desktop computer adopted an Intel (R) Core (TM) i7-97000 CPU, featuring a 3.00 GHz main frequency, 64-bit operating system, and 16 GB RAM. Table 1 presents the parameter settings for various algorithms.

5.2. UAV Flight Environment Description

To evaluate the performance, effectiveness, and feasibility of the EAB-BES algorithm, this paper applies it along with other comparative algorithms to solve the 3D path planning problem for UAVs in urban environments. In this study, six types of urban environments are designed, where cylinders and hemispheres are used to represent high-rise buildings and low-rise structures, respectively. The complexity of the obstacles, including their number, height, and breadth, increases progressively, leading to a corresponding rise in the difficulty level.
In Environment 1 and Environment 2, the coordinates of the starting and goal points are identical. These environments are relatively simple, characterized by a small number of buildings and smaller radii. And these tests are the flight conditions of different algorithms in low spaces. The primary difference is that Environment 2 features an increased number of buildings and larger radii. The heights of high-rise buildings remain consistent across Environment 1 to Environment 3, whereas only the heights of low-rise buildings vary. The difficulty level rises sharply from Environment 4 to Environment 6, with significant increases in the number, height, radius, and density of both high-rise and low-rise buildings. Among these, the tallest building exceeds 9000 m in height, while the largest radius reaches 2000 m. The building positions vary across the six environments from Environment 1 to Environment 6.
In Environment 1 to Environment 4, the UAV’s path primarily follows a diagonal trajectory. In Environment 1 and Environment 2, the starting and ending points share the same altitude, enabling parallel flight. In Environment 3, the ending point is at a lower altitude than the starting point, resulting in a descending flight path. In Environment 4, the ending point is at a higher altitude than the starting point, resulting in an ascending flight path. In Environment 5 and Environment 6, the UAV’s path primarily follows the coordinate axes, with a descending flight in Environment 5 and an ascending flight in Environment 6.
In the 3D flight diagram, the start is marked with a red dot, and the goal with a five-pointed star. Altitude is encoded using a color gradient: dark blue for low altitudes, transitioning from cyan–green–yellow to red for high altitudes. This design visually emphasizes altitude variations and terrain undulations in the study area. The detailed configurations of the six 3D test environments are presented in Table 2.

5.3. Analysis of Experimental Results

Figure 6 shows the convergence curves of the best fitness values for the 3D path planning of the UAV in six environments. After 200 iterations, each algorithm can converge normally. However, in all environments, the EAB-BES algorithm has a faster convergence speed and can achieve the minimum precision value. It can timely escape from local optimal traps, has strong convergence stability, can find the optimal solution to the problem, and search for the shortest planned path.
Figure 6a,b illustrates the convergence situations of different algorithms in Environments 1 and 2. Since the first two environments are relatively simple and do not impose high requirements on the algorithm performance, all algorithms can converge to a relatively good value. At the initial stage of iteration, the fitness values obtained by the algorithms are relatively large, while the convergence values are relatively small, resulting in a significant data gap. In the later stage, it is difficult to distinguish the differences in the convergence values of different algorithms. Therefore, a small window was intentionally opened in the convergence graph. Although in some individual scenarios, the fitness values of UAV path planning did not differ significantly, it can be clearly observed in the small window that the EAB-BES still achieved the minimum fitness convergence value, with faster convergence speed and the strongest performance.
In Environments 3–6, corresponding to Figure 6c–f, it can be more intuitively seen that compared with the comparison algorithms, within the same number of iterations, the EAB-BES algorithm shows a faster trend of approaching the optimal solution. The fitness value fluctuates minimally during the convergence process, indicating good stability. The EAB-BES algorithm has extremely high curve smoothness. In contrast, the fluctuations of the DE and TLSMA algorithms are relatively large. Under the same test environment, the difference in the final convergence fitness values between the EAB-BES algorithm and other algorithms is obvious. The fitness value of the EAB-BES algorithm is significantly the lowest. The performance of BES is also good. Other comparison algorithms, such as PSO, TLBO, and SSA, may fall into local optima and exhibit premature convergence.
In Figure 6e, after the fitness value of the EAB-BES algorithm reaches a certain level at the initial stage of iteration, it successfully decreases to near the minimum value after 50 more generations of further search, effectively avoiding the premature convergence phenomenon and ensuring the acquisition of the global optimal solution. Relying on its unique differential mutation strategy based on block-based elite guidance, it successfully escapes from the local optimal region in subsequent iterations, and the fitness value continues to decline and finally converges near the global optimum. This characteristic enables the algorithm to have stronger robustness in complex solution spaces and greatly improves the probability of finding the true optimal solution. The comparison of the convergence curves proves the superiority of the EAB-BES in solving the UAV path planning problem, which can obtain better results and demonstrate better performance.
Table 3 presents a detailed numerical comparison of all algorithms across different urban environments, including the best value, worst value, mean value, and standard deviation. From the table, it can be observed that EAB-BES outperforms other algorithms in most numerical comparisons. It achieves significantly lower values in terms of the best value, worst value, and mean value. In terms of standard deviation, EAB-BES is less volatile than other algorithms in most scenarios, highlighting the reliable performance of this algorithm under different operating conditions. DE also shows certain advantages in the standard deviation index. Similarly to the results shown in the convergence curves, the advantage of EAB-BES in Environment 1 and Environment 2 is not as pronounced but still superior to other algorithms, which is attributed to the simplicity of the building structures in these environments.
In Environment 3 to Environment 6, due to the increased density, height, and radius of both high-rise and low-rise buildings in the urban environment, as well as the adjustment of the UAV’s starting and goal point altitudes, the UAV’s flight path involves both descending and ascending trajectories. As a result, the shortcomings of the comparative algorithms become evident, as they tend to fall into premature convergence, experience reduced accuracy, and fail to meet the requirements for optimal path planning. TLSMA, CSSA, and mBES, these excellent improved algorithms, also perform well in terms of optimal values and can generally find suboptimal solutions.
In contrast, the EAB-BES algorithm, enhanced by elite opposition-based learning, adaptive weighting, and a block-based elite-guided differential mutation strategy, overcomes the tendency to fall into local optima. It significantly improves accuracy and convergence speed, effectively balancing local and global search capabilities. Therefore, EAB-BES can find superior solutions compared to other algorithms, plan the shortest routes, and efficiently solve the 3D UAV path planning problem in urban environments.
Figure 7, Figure 8, Figure 9, Figure 10, Figure 11 and Figure 12 present the 3D stereograms and top views of different algorithms for addressing the UAV path planning problem in urban environments. In these figures, the EAB-BES algorithm exhibits remarkable advantages compared with comparative algorithms such as PSO, DE, and TLBO. In Environments 1 and 2, although the complexity of obstacles is low, EAB-BES still plans shorter and smoother paths. As the complexity of the environment increases, for example, in Environments 3–6, the obstacle avoidance ability and path optimization advantages of EAB-BES become more apparent as the density, height, and distribution complexity of high-rise and low-rise buildings increase. Under constraint compliance, its planned path accurately avoids various obstacles, including high-rise buildings (columnar) and low-rise buildings (hemispherical), eliminating redundant detouring. Compared with algorithms like PSO and SSA, it features shorter path length and better continuity. This performance benefits from the elite opposition-based learning, adaptive weights, and block-based elite-guided differential mutation strategies integrated into EAB-BES, enabling effective balance between local and global search capabilities in complex urban 3D environments. It thus effectively verifies the algorithm’s excellent performance, as well as its efficiency and reliability in solving the 3D UAV path planning problem across diverse and complex scenarios. In high-difficulty and high-density scenarios such as Environment 4, 5, and 6, the CSSA and mBES algorithms can also plan shorter collision-free paths, which is due to the advanced strategies within the improved algorithms.
In Table 4, we conducted an ablation experiment on the four key parameters ( η , ω max , ω min , μ ) of the EAB-BES algorithm to verify their impact on performance. The ablation experiment was conducted in the most challenging Environment 6 to verify the generalization of the proposed algorithm, and the Mean, Best, Worst, and Std were reported. The results show that the original parameter configuration ( η = 4, ω max = 2, ω min = 0.2, μ = 2) achieved the best performance in all indicators, indicating that this configuration achieved a good balance between accuracy and stability.
From the comparison, it can be observed that increasing the η value (such as η = 5) or adjusting ω max (such as setting it to 1.5 or 2.5) will cause a slight decrease in the average fitness and the best value. At the same time, reducing or increasing the ω min and μ values will also weaken the convergence effect and robustness of the algorithm to a certain extent. This result further verifies that the parameter configuration proposed in this paper has good adaptability and adjustment ability, which can not only accelerate convergence but also effectively prevent falling into local optimality.
As illustrated in Figure 13, the CPU time of the EAB-BES algorithm is moderately higher than that of simpler algorithms such as DE, PSO, and TLBO, particularly in complex urban environments like Environments 4, 5, and 6. For instance, in Environment 6, EAB-BES requires approximately 877.9 s, compared to 840.4 s for DE—an increase of about 4.5%. This additional computational cost is primarily attributed to the integration of multiple strategies in EAB-BES, which significantly enhance global search capability and path accuracy.
Nevertheless, this trade-off proves to be well justified. Despite the increased runtime, EAB-BES achieves substantial improvements in overall performance metrics. In the same environment, the best path cost is reduced by 23.2%, and the standard deviation is lowered by 30.2%, indicating improved robustness and consistency. Among advanced algorithms like BES and mBES, EAB-BES also attains the shortest CPU time, reflecting its enhanced search efficiency.
Furthermore, the average CPU time of EAB-BES across six environments remains under 950 s, which is acceptable for offline preflight planning or near real-time route updates in practical UAV missions. In mission-critical scenarios where navigation precision, obstacle avoidance, and environmental adaptability are essential, the performance gains of EAB-BES outweigh the moderate increase in computational load.
Therefore, EAB-BES strikes a favorable balance between optimization performance and computational efficiency, making it a reliable and scalable solution for 3D UAV path planning tasks in complex urban environments.

5.4. Statistical Hypothesis Test

To validate the scientific validity and credibility of the proposed algorithm and analyze its performance advantages, statistical hypothesis tests were performed. The Wilcoxon rank-sum test quantifies significant differences between paired algorithms using p-values [66]. The Friedman test compares performance rankings across multiple environments to assess macro-level algorithmic superiority [67].
From the statistical test results, Table 5 presents the p-values from the Wilcoxon rank-sum test. The analysis reveals that in the vast majority of environments, the p-values for comparisons between EAB-BES and algorithms such as PSO, DE, and TLBO are significantly lower than the conventional significance level of 0.05. This strongly demonstrates that the performance differences between EAB-BES and the comparative algorithms are statistically significant. Although a few pairwise comparisons do not reach significance, the overall test results robustly support the conclusion that EAB-BES exhibits more reliable performance advantages in UAV path planning tasks compared to other algorithms, validating its effectiveness and superiority.
Table 6 shows the results of the Friedman test. The data indicate that the EAB-BES algorithm ranks first from Environment 1 to Environment 6, with significantly lower average scores than comparative algorithms. This demonstrates its superior comprehensive performance across multiple urban environments.
To enrich statistical tests, we calculated Cohen’s d effect sizes to assess the practical significance of the observed differences. Unlike p-values, which indicate statistical significance, Cohen’s d quantifies the magnitude of the difference between two groups in standardized units. Typically, values of d > 0.2, 0.5, and 0.8 are interpreted as small, medium, and large effects, respectively.
As shown in Table 7, EAB-BES demonstrates moderate to large effect sizes (d > 0.8) in most scenarios, especially against PSO, SMA, and mBES. For example, in Environment 5, EAB-BES exhibits a very large effect (2.22) when compared with PSO, confirming its substantial improvement. These results indicate that the performance advantage of EAB-BES is not only statistically significant but also practically meaningful in real-world UAV path planning applications.
Box plots visualize performance distributions of algorithms in 3D UAV path planning for urban environments. The median represents average planning accuracy, the interquartile range (IQR) measures fitness value dispersion (stability), and outliers indicate abnormal fluctuations during execution [68]. Figure 14 presents box plots that compare the performance of algorithms across six urban environments in terms of planning accuracy (median), stability (IQR), and robustness (outliers). EAB-BES consistently achieves lower medians, smaller box heights, and fewer outliers than most comparative algorithms.
In Environments 1 to 6, EAB-BES demonstrates superior fitness values, reduced variability, and minimal abnormal fluctuations. Notably, its box plots are markedly compact and positioned lower than others, reflecting high accuracy and strong stability. For example, in Environments 1, 2 and 3, EAB-BES exhibits almost no outliers, while PSO and DE show pronounced fluctuations. EAB-BES achieves a favorable balance of precision, stability, and reliability in repeated runs, confirming its effectiveness for robust 3D UAV path planning in complex urban scenarios.

5.5. Discussion

The experimental results across six heterogeneous environments demonstrate the superior performance of the EAB-BES algorithm in 3D UAV path planning. Compared to the BES, EAB-BES achieved significant improvements in core metrics: a 5.2% reduction in Best (path length), a 3.8% optimization in Mean performance, and a 41.2% enhancement in robustness (Std) on average. In Environment 5 with stringent dynamic constraints, EAB-BES reduced the best value by 10.03% and optimized Std by 31.6%, highlighting its adaptability to complex scenarios.
When compared to mainstream algorithms, EAB-BES consistently outperformed competitors in multiple dimensions. For instance, it achieved 20.8% lower best values than PSO in Environment 6 and a 14.6% improvement over TLSMA in Environment 5. In terms of convergence stability, EAB-BES maintained the lowest Mean values across all environments, with a 10.0% optimization over PSO in Environment 4. While TLBO exhibited the lowest Std (195.30) in Environment 1 and DE achieved minimal Std (1705.75) in Environment 6, EAB-BES demonstrated balanced robustness, particularly excelling in dynamic environments (e.g., 344.93 Std in Environment 2, 80.2% lower than DE).
Statistical analyses further validate these findings. The Wilcoxon rank-sum test showed that the majority of p-values were significantly below 0.05, confirming the statistical significance of EAB-BES’s improvements. The Friedman test ranked EAB-BES first overall, underscoring its comprehensive superiority. These results can be attributed to the algorithm’s integration of elite opposition-based learning, adaptive weighting mechanisms, and block-based elite-guided differential mutation, which collectively enhance exploration–exploitation balance and adaptability to high-density urban environments.
These results underscore the effectiveness of EAB-BES in harmonizing exploration–exploitation trade-offs, especially under strict constraints. The EAB-BES’s ability to minimize path length while ensuring stability positions it as a robust solution for real-world UAV applications, particularly in complex urban landscapes requiring high precision and adaptability.

6. Conclusions

This study introduces a multi-strategy enhanced bald eagle search algorithm (EAB-BES) to address critical challenges in 3D UAV path planning within complex urban environments. By integrating elite opposition-based learning to broaden solution space exploration, adaptive weight mechanisms to dynamically balance global–local search trade-offs, and block-based elite-guided differential mutation to refine local optimization precision, EAB-BES systematically enhances the capabilities of the conventional BES algorithm across three key dimensions. Extensive experiments conducted in six high-density scenarios with mixed high-rise and low-altitude obstacles validate its superiority in generating collision-free paths, achieving the shortest path length, highest smoothness, and fastest convergence speed among comparative algorithms. Statistical analyses, including the Wilcoxon rank-sum, Friedman test, box plot evaluations, and Cohen’s d effect size analysis, further confirm its robustness in avoiding local optima, the practical significance of performance gains, and its stable behavior under stringent spatial constraints. An ablation study further verifies the robustness of key parameter settings, demonstrating balanced convergence and generalization ability under varying configurations. Computational efficiency analysis reveals that the marginal increase in CPU time is well compensated by notable gains in path quality and robustness, making EAB-BES suitable for near real-time or offline mission planning scenarios. These comparative results demonstrate that EAB-BES consistently identifies superior solutions, efficiently resolving 3D path planning challenges in urban environments and offering practical benefits for urban surveillance, emergency response, and logistics applications.
Future research will focus on integrating EAB-BES with reinforcement learning for real-time dynamic obstacle avoidance [69,70,71] and extending the framework to multi-UAV collaborative systems in ultra-high-density cities for decentralized path coordination [72,73]. Practical planning of low-cost UAVs in real scenarios can also be explored to improve adaptability across heterogeneous environments, especially in enhancing model deployment and data transmission efficiency within communication-constrained UAV clusters [74,75,76,77].

Author Contributions

Y.Z., methodology, software, formal analysis, investigation, visualization, and writing—original draft preparation; W.X., conceptualization, resources, supervision, project administration, and writing—review and editing; S.Y., validation, data curation, supervision, and funding acquisition. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Public Welfare Research Project of Jiaxing City (Government-funded, Grant No. 2024AY10030), the General Scientific Research Project of the Zhejiang Provincial Department of Education (Grant No. Y202351454), and the Jiaxing Vocational and Technical College 2025 school-level scientific research project (Grant No. jzyy202522).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Data will be made available on request.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Wang, X.; He, N.; Hong, C.; Wang, Q.; Chen, M. Improved YOLOX-X based UAV aerial photography object detection algorithm. Image Vis. Comput. 2023, 135, 104697. [Google Scholar] [CrossRef]
  2. Fang, Z.; Savkin, A.V. Strategies for Optimized UAV Surveillance in Various Tasks and Scenarios: A Review. Drones 2024, 8, 193. [Google Scholar] [CrossRef]
  3. Semsch, E.; Jakob, M.; Pavlicek, D.; Pechoucek, M. Autonomous UAV surveillance in complex urban environments. In Proceedings of the 2009 IEEE/WIC/ACM International Joint Conference on Web Intelligence and Intelligent Agent Technology, Milan, Italy, 15–18 September 2009; Volume 2, pp. 82–85. [Google Scholar]
  4. Kirschstein, T. Comparison of energy demands of drone-based and ground-based parcel delivery services. Transp. Res. Part D Transp. Environ. 2020, 78, 102209. [Google Scholar] [CrossRef]
  5. Niyazi, M.; Behnamian, J. Application of Emerging Digital Technologies in Disaster Relief Operations: A Systematic Review. Arch. Comput. Methods Eng. 2023, 30, 1579–1599. [Google Scholar] [CrossRef]
  6. Khan, A.; Gupta, S.; Gupta, S.K. Emerging UAV technology for disaster detection, mitigation, response, and preparedness. J. Field Robot. 2022, 39, 905–955. [Google Scholar] [CrossRef]
  7. Zeng, Y.; Zhang, R.; Lim, T.J. Wireless communications with unmanned aerial vehicles: Opportunities and challenges. IEEE Commun. Mag. 2016, 54, 36–42. [Google Scholar] [CrossRef]
  8. Shakhatreh, H.; Sawalmeh, A.H.; Al-Fuqaha, A.; Dou, Z.; Almaita, E.; Khalil, I.; Othman, N.S.; Khreishah, A.; Guizani, M. Unmanned aerial vehicles (UAVs): A survey on civil applications and key research challenges. IEEE Access 2019, 7, 48572–48634. [Google Scholar] [CrossRef]
  9. Nex, F.; Remondino, F. UAV for 3D mapping applications: A review. Appl. Geomat. 2014, 6, 1–15. [Google Scholar] [CrossRef]
  10. Chen, J.; Li, M.; Yuan, Z.; Gu, Q. An Improved A* Algorithm for UAV Path Planning Problems. In Proceedings of the 2020 IEEE 4th Information Technology, Networking, Electronic and Automation Control Conference (ITNEC), Chongqing, China, 12–14 June 2020; Volume 1, pp. 958–962. [Google Scholar]
  11. Kothari, M.; Postlethwaite, I. A Probabilistically Robust Path Planning Algorithm for UAVs Using Rapidly-Exploring Random Trees. J. Intell. Robot. Syst. 2013, 71, 231–253. [Google Scholar] [CrossRef]
  12. Li, B.; Chen, B. An Adaptive Rapidly-Exploring Random Tree. IEEE/CAA J. Autom. Sin. 2022, 9, 283–294. [Google Scholar] [CrossRef]
  13. Hsu, D.; Latombe, J.-C.; Kurniawati, H. On the Probabilistic Foundations of Probabilistic Roadmap Planning. Int. J. Robot. Res. 2006, 25, 627–643. [Google Scholar] [CrossRef]
  14. Gasparetto, A.; Boscariol, P.; Lanzutti, A.; Vidoni, R. Path Planning and Trajectory Planning Algorithms: A General Overview. In Motion and Operation Planning of Robotic Systems; Carbone, G., Gomez-Bravo, F., Eds.; Springer International Publishing: Cham, Switzerland, 2015; Volume 29, pp. 3–27. ISBN 978-3-319-14704-8. [Google Scholar]
  15. Yang, L.; Qi, J.; Song, D.; Xiao, J.; Han, J.; Xia, Y. Survey of Robot 3D Path Planning Algorithms. J. Control Sci. Eng. 2016, 2016, 1–22. [Google Scholar] [CrossRef]
  16. Raj, A.; Ahuja, K.; Busnel, Y. AI algorithm for predicting and optimizing trajectory of massive UAV swarm. Robot. Auton. Syst. 2025, 186, 104910. [Google Scholar] [CrossRef]
  17. Niu, Y.; Yan, X.; Wang, Y.; Niu, Y. Three-dimensional UCAV path planning using a novel modified artificial ecosystem optimizer. Expert Syst. Appl. 2023, 217, 119499. [Google Scholar] [CrossRef]
  18. Yahia, H.S.; Mohammed, A.S. Path planning optimization in unmanned aerial vehicles using meta-heuristic algorithms: A systematic review. Environ. Monit. Assess. 2023, 195, 30. [Google Scholar] [CrossRef]
  19. Zhu, D.; Wang, S.; Zhou, C.; Yan, S.; Xue, J. Human memory optimization algorithm: A memory-inspired optimizer for global optimization problems. Expert Syst. Appl. 2024, 237, 121597. [Google Scholar] [CrossRef]
  20. Yin, S.; Xiang, Z. A hyper-heuristic algorithm via proximal policy optimization for multi-objective truss problems. Expert Syst. Appl. 2024, 256, 124929. [Google Scholar] [CrossRef]
  21. Yang, X.-S. Nature-Inspired Optimization Algorithms; Academic Press: Cambridge, MA, USA, 2020; ISBN 0-12-821989-0. [Google Scholar]
  22. Alsattar, H.A.; Zaidan, A.A.; Zaidan, B.B. Novel meta-heuristic bald eagle search optimisation algorithm. Artif. Intell. Rev. 2020, 53, 2237–2264. [Google Scholar] [CrossRef]
  23. Zeng, Y.; Zhang, R. Energy-efficient UAV communication with trajectory optimization. IEEE Trans. Wirel. Commun. 2017, 16, 3747–3760. [Google Scholar] [CrossRef]
  24. Kim, M.-J.; Kang, T.Y.; Ryoo, C.-K. Real-Time Path Planning for Unmanned Aerial Vehicles Based on Compensated Voronoi Diagram. Int. J. Aeronaut. Space Sci. 2025, 26, 235–244. [Google Scholar] [CrossRef]
  25. Ergezer, H.; Leblebicioglu, K. Path Planning for UAVs for Maximum Information Collection. IEEE Trans. Aerosp. Electron. Syst. 2013, 49, 502–520. [Google Scholar] [CrossRef]
  26. Jayaweera, H.M.P.C.; Hanoun, S. Path Planning of Unmanned Aerial Vehicles (UAVs) in Windy Environments. Drones 2022, 6, 101. [Google Scholar] [CrossRef]
  27. Ikram, M.; Sroufe, R. A novel sequential block path planning method for 3D unmanned aerial vehicle routing in sustainable supply chains. Supply Chain. Anal. 2025, 9, 100094. [Google Scholar] [CrossRef]
  28. Fahmani, L.; Benhadou, S. Optimizing 2D path planning for unmanned aerial vehicle inspection of electric transmission lines. Sci. Afr. 2024, 24, e02203. [Google Scholar] [CrossRef]
  29. Pamarthi, V.; Agrawal, R. Unmanned aerial vehicle path planning with hybrid motion algorithm for obstacle avoidance. Meas. Sens. 2024, 36, 101195. [Google Scholar] [CrossRef]
  30. Chan, Y.Y.; Ng, K.K.H.; Lee, C.K.M.; Hsu, L.-T.; Keung, K.L. Wind dynamic and energy-efficiency path planning for unmanned aerial vehicles in the lower-level airspace and urban air mobility context. Sustain. Energy Technol. Assess. 2023, 57, 103202. [Google Scholar] [CrossRef]
  31. Roberge, V.; Tarbouchi, M.; Labonte, G. Comparison of Parallel Genetic Algorithm and Particle Swarm Optimization for Real-Time UAV Path Planning. IEEE Trans. Ind. Inform. 2013, 9, 132–141. [Google Scholar] [CrossRef]
  32. Liu, G.; Shu, C.; Liang, Z.; Peng, B.; Cheng, L. A Modified Sparrow Search Algorithm with Application in 3d Route Planning for UAV. Sensors 2021, 21, 1224. [Google Scholar] [CrossRef]
  33. Zhao, R.; Wang, Y.; Xiao, G.; Liu, C.; Hu, P.; Li, H. A method of path planning for unmanned aerial vehicle based on the hybrid of selfish herd optimizer and particle swarm optimizer. Appl. Intell. 2022, 52, 16775–16798. [Google Scholar] [CrossRef]
  34. Wang, X.; Pan, J.-S.; Yang, Q.; Kong, L.; Snášel, V.; Chu, S.-C. Modified Mayfly Algorithm for UAV Path Planning. Drones 2022, 6, 134. [Google Scholar] [CrossRef]
  35. Aslan, M.F.; Durdu, A.; Sabanci, K. Goal distance-based UAV path planning approach, path optimization and learning-based path estimation: GDRRT*, PSO-GDRRT* and BiLSTM-PSO-GDRRT*. Appl. Soft Comput. 2023, 137, 110156. [Google Scholar] [CrossRef]
  36. Yin, S.; Wang, R.; Xiang, Y.; Xiang, Z. Adaptive differential evolution for collaborative path planning of multiple unmanned aerial vehicles. In Proceedings of the 2024 36th Chinese Control and Decision Conference (CCDC), Xi’an, China, 25–27 May 2024; pp. 1521–1526. [Google Scholar]
  37. Wang, M.; Yuan, P.; Hu, P.; Yang, Z.; Ke, S.; Huang, L.; Zhang, P. Multi-Strategy Improved Red-Tailed Hawk Algorithm for Real-Environment Unmanned Aerial Vehicle Path Planning. Biomimetics 2025, 10, 31. [Google Scholar] [CrossRef] [PubMed]
  38. Zhong, Y.; Wang, Y. Cross-regional path planning based on improved Q-learning with dynamic exploration factor and heuristic reward value. Expert Syst. Appl. 2025, 260, 125388. [Google Scholar] [CrossRef]
  39. Zhang, C.; Yang, Y.; Chen, W. Multi-strategy ensemble wind driven optimization algorithm for robot path planning. Math. Comput. Simul. 2025, 231, 144–159. [Google Scholar] [CrossRef]
  40. Wang, X.; Zhou, S.; Wang, Z.; Xia, X.; Duan, Y. An Improved Human Evolution Optimization Algorithm for Unmanned Aerial Vehicle 3D Trajectory Planning. Biomimetics 2025, 10, 23. [Google Scholar] [CrossRef]
  41. Yin, S.; Xu, N.; Shi, Z.; Xiang, Z. Collaborative path planning of multi-unmanned surface vehicles via multi-stage constrained multi-objective optimization. Adv. Eng. Inform. 2025, 65, 103115. [Google Scholar] [CrossRef]
  42. Zhang, Y.; Zhou, Y.; Zhou, G.; Luo, Q. An effective multi-objective bald eagle search algorithm for solving engineering design problems. Appl. Soft Comput. 2023, 145, 110585. [Google Scholar] [CrossRef]
  43. Zheng, R.; Li, R.; Hussien, A.G.; Hamad, Q.S.; Al-Betar, M.A.; Che, Y.; Wen, H. A multi-strategy boosted bald eagle search algorithm for global optimization and constrained engineering problems: Case study on MLP classification problems. Artif. Intell. Rev. 2024, 58, 18. [Google Scholar] [CrossRef]
  44. Zhang, D.; Liang, X.; Cao, Y.; Zhang, M.; Xiao, D. Adaptive bald eagle search algorithm with elite swarm guiding and population memory crossover. Int. J. Bio-Inspired Comput. 2024, 24, 133–149. [Google Scholar] [CrossRef]
  45. Zhang, Y.; Zhou, Y.; Zhou, G.; Luo, Q.; Zhu, B. A Curve Approximation Approach Using Bio-inspired Polar Coordinate Bald Eagle Search Algorithm. Int. J. Comput. Intell. Syst. 2022, 15, 30. [Google Scholar] [CrossRef]
  46. Sayed, G.I.; Soliman, M.M.; Hassanien, A.E. A novel melanoma prediction model for imbalanced data using optimized SqueezeNet by bald eagle search optimization. Comput. Biol. Med. 2021, 136, 104712. [Google Scholar] [CrossRef]
  47. Almashhadani, H.A.; Deng, X.; Latif, S.N.A.; Ibrahim, M.M.; AL-hwaidi, O.H.R. Deploying an efficient and reliable scheduling for mobile edge computing for IoT applications. Mater. Today Proc. 2023, 80, 2850–2857. [Google Scholar] [CrossRef]
  48. Nassef, A.M.; Fathy, A.; Rezk, H.; Yousri, D. Optimal parameter identification of supercapacitor model using bald eagle search optimization algorithm. J. Energy Storage 2022, 50, 104603. [Google Scholar] [CrossRef]
  49. Algarni, A.D.; Alturki, N.; Soliman, N.F.; Abdel-Khalek, S.; Mousa, A.A.A. An Improved Bald Eagle Search Algorithm with Deep Learning Model for Forest Fire Detection Using Hyperspectral Remote Sensing Images. Can. J. Remote Sens. 2022, 48, 609–620. [Google Scholar] [CrossRef]
  50. Alsubai, S.; Hamdi, M.; Abdel-Khalek, S.; Alqahtani, A.; Binbusayyis, A.; Mansour, R.F. Bald eagle search optimization with deep transfer learning enabled age-invariant face recognition model. Image Vis. Comput. 2022, 126, 104545. [Google Scholar] [CrossRef]
  51. Elsisi, M.; Essa, M.E.-S.M. Improved bald eagle search algorithm with dimension learning-based hunting for autonomous vehicle including vision dynamics. Appl. Intell. 2023, 53, 11997–12014. [Google Scholar] [CrossRef]
  52. Dian, S.; Zhong, J.; Guo, B.; Liu, J.; Guo, R. A smooth path planning method for mobile robot using a BES-incorporated modified QPSO algorithm. Expert Syst. Appl. 2022, 208, 118256. [Google Scholar] [CrossRef]
  53. Wang, W.-C.; Tian, W.-C.; Chau, K.-W.; Zang, H. MSBES: An improved bald eagle search algorithm with multi- strategy fusion for engineering design and water management problems. J. Supercomput. 2025, 81, 251. [Google Scholar] [CrossRef]
  54. Alabdan, R.; Alabduallah, B.; Alruwais, N.; Arasi, M.A.; Asklany, S.A.; Alghushairy, O.; Alallah, F.S.; Alshareef, A. Blockchain-assisted improved interval type-2 fuzzy deep learning-based attack detection on internet of things driven consumer electronics. Alex. Eng. J. 2025, 110, 153–167. [Google Scholar] [CrossRef]
  55. Yildiz, B.S.; Pholdee, N.; Bureerat, S.; Yildiz, A.R.; Sait, S.M. Enhanced grasshopper optimization algorithm using elite opposition-based learning for solving real-world engineering problems. Eng. Comput. 2022, 38, 4207–4219. [Google Scholar] [CrossRef]
  56. Zhu, D.; Shen, J.; Zhang, Y.; Li, W.; Zhu, X.; Zhou, C.; Cheng, S.; Yao, Y. Multi-strategy particle swarm optimization with adaptive forgetting for base station layout. Swarm Evol. Comput. 2024, 91, 101737. [Google Scholar] [CrossRef]
  57. Yang, Q.; Yan, J.-Q.; Gao, X.-D.; Xu, D.-D.; Lu, Z.-Y.; Zhang, J. Random neighbor elite guided differential evolution for global numerical optimization. Inf. Sci. 2022, 607, 1408–1438. [Google Scholar] [CrossRef]
  58. Kennedy, J.; Eberhart, R. Particle swarm optimization. In Proceedings of the Proceedings of ICNN’95—International Conference on Neural Networks, Perth, Australia, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar]
  59. Das, S.; Suganthan, P.N. Differential Evolution: A Survey of the State-of-the-Art. IEEE Trans. Evol. Comput. 2011, 15, 4–31. [Google Scholar] [CrossRef]
  60. Rao, R.V.; Savsani, V.J.; Vakharia, D.P. Teaching–learning-based optimization: A novel method for constrained mechanical design optimization problems. Comput. Aided Des. 2011, 43, 303–315. [Google Scholar] [CrossRef]
  61. Li, S.; Chen, H.; Wang, M.; Heidari, A.A.; Mirjalili, S. Slime mould algorithm: A new method for stochastic optimization. Future Gener. Comput. Syst. 2020, 111, 300–323. [Google Scholar] [CrossRef]
  62. Xue, J.; Shen, B. A novel swarm intelligence optimization approach: Sparrow search algorithm. Syst. Sci. Control Eng. 2020, 8, 22–34. [Google Scholar] [CrossRef]
  63. Zhong, C.; Li, G.; Meng, Z. A hybrid teaching–learning slime mould algorithm for global optimization and reliability-based design optimization problems. Neural Comput. Appl. 2022, 34, 16617–16642. [Google Scholar] [CrossRef]
  64. Zhang, C.; Ding, S. A stochastic configuration network based on chaotic sparrow search algorithm. Knowl.-Based Syst. 2021, 220, 106924. [Google Scholar] [CrossRef]
  65. Chhabra, A.; Hussien, A.G.; Hashim, F.A. Improved bald eagle search algorithm for global optimization and feature selection. Alex. Eng. J. 2023, 68, 141–180. [Google Scholar] [CrossRef]
  66. Niu, Y.; Yan, X.; Wang, Y.; Niu, Y. An adaptive neighborhood-based search enhanced artificial ecosystem optimizer for UCAV path planning. Expert Syst. Appl. 2022, 208, 118047. [Google Scholar] [CrossRef]
  67. Yin, S.; Xiang, Z. Adaptive operator selection with dueling deep Q-network for evolutionary multi-objective optimization. Neurocomputing 2024, 581, 127491. [Google Scholar] [CrossRef]
  68. Zhu, D.; Wang, S.; Zhou, C.; Yan, S. Manta ray foraging optimization based on mechanics game and progressive learning for multiple optimization problems. Appl. Soft Comput. 2023, 145, 110561. [Google Scholar] [CrossRef]
  69. Xu, N.; Shi, Z.; Yin, S.; Xiang, Z. A hyper-heuristic with deep Q-network for the multi-objective unmanned surface vehicles scheduling problem. Neurocomputing 2024, 596, 127943. [Google Scholar] [CrossRef]
  70. Xu, Z.; Zhan, X.; Chen, B.; Xiu, Y.; Yang, C.; Shimada, K. A real-time dynamic obstacle tracking and mapping system for UAV navigation and collision avoidance with an RGB-D camera. In Proceedings of the 2023 IEEE International Conference on Robotics and Automation (ICRA), London, UK, 29 May–2 June 2023; pp. 10645–10651. [Google Scholar]
  71. Hau, B.M.; You, S.-S.; Bao Long, L.N.; Kim, H.-S. Efficient routing for multiple AGVs in container terminals using hybrid deep learning and metaheuristic algorithm. Ain Shams Eng. J. 2025, 16, 103468. [Google Scholar] [CrossRef]
  72. Krůček, M.; Král, K.; Cushman, K.C.; Missarov, A.; Kellner, J.R. Supervised Segmentation of Ultra-High-Density Drone Lidar for Large-Area Mapping of Individual Trees. Remote Sens. 2020, 12, 3260. [Google Scholar] [CrossRef]
  73. Guo, H.; Wang, Y.; Liu, J.; Liu, C. Multi-UAV Cooperative Task Offloading and Resource Allocation in 5G Advanced and Beyond. IEEE Trans. Wirel. Commun. 2024, 23, 347–359. [Google Scholar] [CrossRef]
  74. Bayraktar, E.; Yigit, C.B.; Boyraz, P. A hybrid image dataset toward bridging the gap between real and simulation environments for robotics. Mach. Vis. Appl. 2019, 30, 23–40. [Google Scholar] [CrossRef]
  75. Bayraktar, E.; Korkmaz, B.N.; Erarslan, A.U.; Celebi, N. Traffic congestion-aware graph-based vehicle rerouting framework from aerial imagery. Eng. Appl. Artif. Intell. 2023, 119, 105769. [Google Scholar] [CrossRef]
  76. Bayraktar, E.; Basarkan, M.E.; Celebi, N. A low-cost UAV framework towards ornamental plant detection and counting in the wild. ISPRS J. Photogramm. Remote Sens. 2020, 167, 1–11. [Google Scholar] [CrossRef]
  77. Bayraktar, E.; Yigit, C.B. Conditional-pooling for improved data transmission. Pattern Recognit. 2024, 145, 109978. [Google Scholar] [CrossRef]
Figure 1. Top view of UAV path planning.
Figure 1. Top view of UAV path planning.
Biomimetics 10 00499 g001
Figure 2. Elite opposition-based learning.
Figure 2. Elite opposition-based learning.
Biomimetics 10 00499 g002
Figure 3. The nonlinear variation curve of the adaptive weight.
Figure 3. The nonlinear variation curve of the adaptive weight.
Biomimetics 10 00499 g003
Figure 4. Block-based elite-guided differential mutation.
Figure 4. Block-based elite-guided differential mutation.
Biomimetics 10 00499 g004
Figure 5. The flowchart of the EAB-BES algorithm.
Figure 5. The flowchart of the EAB-BES algorithm.
Biomimetics 10 00499 g005
Figure 6. The convergence curves of comparative algorithms for all environments.
Figure 6. The convergence curves of comparative algorithms for all environments.
Biomimetics 10 00499 g006
Figure 7. 3D path stereogram and top view of Environment 1.
Figure 7. 3D path stereogram and top view of Environment 1.
Biomimetics 10 00499 g007
Figure 8. 3D path stereogram and top view of Environment 2.
Figure 8. 3D path stereogram and top view of Environment 2.
Biomimetics 10 00499 g008
Figure 9. 3D path stereogram and top view of Environment 3.
Figure 9. 3D path stereogram and top view of Environment 3.
Biomimetics 10 00499 g009
Figure 10. 3D path stereogram and top view of Environment 4.
Figure 10. 3D path stereogram and top view of Environment 4.
Biomimetics 10 00499 g010
Figure 11. 3D path stereogram and top view of Environment 5.
Figure 11. 3D path stereogram and top view of Environment 5.
Biomimetics 10 00499 g011
Figure 12. 3D path stereogram and top view of Environment 6.
Figure 12. 3D path stereogram and top view of Environment 6.
Biomimetics 10 00499 g012
Figure 13. Comparison of CPU running time for different algorithms.
Figure 13. Comparison of CPU running time for different algorithms.
Biomimetics 10 00499 g013
Figure 14. Box plot comparison of different algorithms in all environments.
Figure 14. Box plot comparison of different algorithms in all environments.
Biomimetics 10 00499 g014
Table 1. The parameter settings of algorithms.
Table 1. The parameter settings of algorithms.
AlgorithmsParameter Settings
PSO w = 0.9 , C 1 = C 2 = 2
DE F = 0.5 , C r = 0.9
TLBO T F { 1 , 2 } , r i [ 0 , 1 ]
SMA z = 0.03
SSA P D = 0.2 P o p S i z e , S D = 0.1 P o p S i z e , S T = 0.8
TLSMA T F { 1 , 2 } , r i [ 0 , 1 ] , z = 0.03
CSSA P D = 0.2 , S D [ 0.1 ,   0.2 ] , S T = 0.8 , μ l o g = 3.99 , w 0 = 0.9 , c = 0.9
BES α = 2 , a = 10 , R = 1.5 , c 1 = c 2 = 2 , r [ 0 ,   1 ]
mBES α = 2 , a = 10 , R = 1.5 , c 1 = c 2 = 2 , r [ 0 ,   1 ]
EAB-BES α = 2 ,   a = 10 ,   R = 1.5 ,   c 1 = c 2 = 2 ,   r [ 0 ,   1 ] ,   k [ 0 ,   1 ] , ω m a x = 2 ,   ω m i n = 0.2 ,   η = 4 ,   μ = 2 ,   β = 1.5
Table 2. Details of different 3D test environments.
Table 2. Details of different 3D test environments.
EnvironmentsStart PointGoal PointPosition of High-Rise BuildingsPosition of Low-Rise Buildings
Projection CoordinateHeight, RadiusProjection CoordinateRadius
Environment 1(0, 20000, 100)(20000, 0, 100)(15845, 13757, 0)5000, 1300(7283, 10186, 0)1300
(11655, 12328, 0)5000, 1400(5794, 6991, 0)1400
(3683, 17649, 0)5000, 1500(17063, 3049, 0)1500
(10083, 6039, 0)5000, 1600(10034, 15375, 0)1600
(5567, 14937, 0)5000, 1700(13216, 7566, 0)1700
Environment 2(0, 20000, 100)(20000, 0, 100)(14269, 5484, 0)5000, 1300(18038, 13163, 0)1300
(15174, 13534, 0)5000, 1400(7064, 15587, 0)1400
(2667, 17685, 0)5000, 1500(3823, 12278, 0)1500
(9284, 2633, 0)5000, 1600(15831, 9895, 0)1600
(4422, 4209, 0)5000, 1700(11449, 13609, 0)1700
(7810, 11614, 0)5000, 1300(15061, 17010, 0)1300
(9561, 17000, 0)5000, 1400(10435, 8614, 0)1400
(17766, 6717, 0)5000, 1500(6732, 8174, 0)1500
Environment 3(0, 20000, 2000)(20000, 0, 100)(10312, 1963, 0)5000, 1300(10874, 7195, 0)1300
(6500, 8040, 0)5000, 1400(11371, 17484, 0)1400
(13832, 14768, 0)5000, 1500(9714, 14344, 0)1500
(8948, 11361, 0)5000, 1600(3164, 12413, 0)1600
(2002, 16532, 0)5000, 1700(16851, 6353, 0)1700
(17122, 13444, 0)5000, 1500(15003, 10659, 0)1500
(14002, 4327, 0)5000, 1600(5727, 3857, 0)1600
(1757, 8175, 0)5000, 1700(5818, 15221, 0)1700
Environment 4(0, 20000, 100)(20000, 0, 3000)(9415, 7258, 0)6000, 1700(5301, 5310, 0)1300
(7590, 3590, 0)5000, 1400(6504, 14073, 0)1400
(6869, 10045, 0)5000, 1500(8681, 17245, 0)1500
(13617, 5224, 0)6000, 1600(16878, 3426, 0)1600
(17634, 12447, 0)5000, 1900(17673, 17059, 0)1700
(17522, 7928, 0)4000, 1300(2560, 10564, 0)1800
(2479, 6642, 0)5000, 1400(3405, 17190, 0)1900
(10672, 10981, 0)5000, 1500(13778, 10590, 0)2000
(1957, 13903, 0)5000, 1300(3204, 2153, 0)1600
(11870, 15626, 0)3000, 1700(14819, 14020, 0)1300
Environment 5(0, 10000, 4000)(20000, 10000, 500)(12307, 16887, 0)5000, 2000(18011, 3362, 0)1600
(13862, 12235, 0)3000, 1600(12346, 2149, 0)1400
(7236, 7024, 0)5000, 1500(11007, 5410, 0)1400
(8325, 13398, 0)6000, 1900(5412, 10606, 0)1800
(16720, 9031, 0)5000, 1700(8362, 3073, 0)1500
(4259, 17214, 0)7000, 1300(11286, 11556, 0)1600
(13161, 6781, 0)5000, 1400(2859, 7427, 0)1600
(1705, 11170, 0)3000, 1500(9344, 15785, 0)1900
(10107, 8725, 0)4000, 1800(16204, 5497, 0)2000
(2487, 3581, 0)5000, 1300(16424, 13188, 0)1300
Environment 6(0, 10000, 500)(20000, 10000, 5000)(18380, 15991, 0)6000, 1300(13683, 7254, 0)1700
(6808, 7803, 0)7000, 1400(11402, 3462, 0)1900
(1808, 17415, 0)8000, 1500(16021, 14619, 0)1500
(14600, 3189, 0)6000, 1600(9434, 15827, 0)1600
(3376, 11338, 0)5000, 1700(17182, 5046, 0)1700
(9536, 9027, 0)9000, 1800(4004, 7203, 0)1300
(4807, 2406, 0)7000, 1300(4586, 15201, 0)1400
(16451, 11611, 0)7000, 1400(6609, 11204, 0)2000
(14932, 17467, 0)6000, 2000(10002, 12396, 0)1600
(17894, 8620, 0)8000, 1500(13238, 10476, 0)1300
(5580, 16794, 0)7000, 1300(13236, 14589, 0)2000
(1817, 4687, 0)6000, 1800(8378, 4910, 0)1800
Table 3. Experimental results in different environments.
Table 3. Experimental results in different environments.
EnvironmentsIndicatorsPSODETLBOSMASSATLSMACSSABESmBESEAB-BES
Environment 1Best28869.1128949.1430123.4728883.3028795.4528800.0529118.2929159.9328850.0828770.17
Worst30469.1330654.3930634.8630655.9130563.5830406.9930225.8830557.6030406.7930132.65
Mean29710.2929982.0930261.9729808.3630022.4229742.0929899.7329755.6229911.2829700.06
Std817.64776.74195.30640.50746.99610.83377.84594.27455.77352.08
Environment 2Best29743.1928974.4529595.9929170.6529150.5028994.9629133.7629074.8729143.4728894.00
Worst36292.5433049.1730575.8933467.2335039.1235133.7435300.7734852.1834411.8130263.82
Mean30521.5329978.6229986.9829787.0231219.7829757.1930015.9530771.3630536.5029627.45
Std2883.921738.53364.181407.493001.441627.212605.282511.772041.02344.93
Environment 3Best29235.8628839.4529092.1528875.6428845.1928859.3428840.6128813.9428806.8828655.60
Worst35241.5334209.9340172.2031693.2534665.9334177.8232800.1831893.6034526.5431591.01
Mean31509.1931131.9831508.2029733.1930574.5730232.4430634.0130103.9431125.3729656.72
Std2558.712631.293676.531366.882724.412611.791724.711197.912106.371153.68
Environment 4Best32104.0429687.3229976.2430000.6729744.9529877.2929733.2329959.9429505.6229290.53
Worst38424.6235745.3736158.3537890.7736782.1437978.7138111.9737146.9437416.6934313.32
Mean35056.7232253.0831881.7132401.2033685.8232358.5832321.6634237.6033229.8231549.43
Std2364.482178.092780.873644.212842.432996.203200.112381.972637.402525.59
Environment 5Best30082.3427732.1827809.3428026.7028238.9827665.3724809.3826264.9225616.9723637.72
Worst35473.5030815.4730577.2730203.6333814.2431021.2731224.7332572.9031914.3130146.74
Mean31241.2427911.5628178.7728937.2031909.5128714.5127684.4328937.9229964.8427746.38
Std2335.512058.331620.601506.933360.332425.742491.362123.463271.771451.82
Environment 6Best29602.3627573.9629819.9628069.5928173.1727515.3524501.4826667.5228998.6323445.14
Worst34345.6732744.8633811.1136694.0632948.5835868.6632601.1235241.6935104.2630529.16
Mean30828.0829352.2730905.7429277.9229135.1130683.4528758.6630077.5131314.0127643.72
Std3336.111705.752899.163713.672967.113680.633215.223834.743401.452376.33
The optimal results are shown in bold.
Table 4. Comparison of EAB-BES parameter ablation experiments on Environment 6.
Table 4. Comparison of EAB-BES parameter ablation experiments on Environment 6.
No. η ω m a x ω m i n μ MeanBestWorstStd
1320.2224501.4832601.1228758.663215.22
2420.2223445.1430529.1627643.722376.33
3520.2224611.3033012.0528910.543412.09
441.50.2223733.5831115.8828124.882945.87
542.50.2223889.4131901.6728257.423080.25
6420.1224123.6531774.3328511.423001.89
7420.3224345.5631345.9928402.662966.72
8420.21.524089.2231805.7428683.913033.15
9420.22.523492.3630777.2127665.282452.68
The optimal results are shown in bold.
Table 5. Wilcoxon rank-sum test results (p-values) in different environments.
Table 5. Wilcoxon rank-sum test results (p-values) in different environments.
EnvironmentsEAB-BES VS
PSODETLBOSMASSATLSMACSSABESmBES
Environment 14.78 × 10−48.89 × 10−57.10 × 10−51.06 × 10−34.38 × 10−133.85 × 10−41.18 × 10−71.99 × 10−28.60 × 10−1
Environment 23.87 × 10−112.42 × 10−35.99 × 10−51.32 × 10−13.85 × 10−72.43 × 10−61.34 × 10−98.24 × 10−46.32 × 10−3
Environment 31.33 × 10−11.09 × 10−22.28 × 10−64.57 × 10−31.12 × 10−23.87 × 10−21.00 × 10−81.97 × 10−42.27 × 10−4
Environment 42.07 × 10−61.68 × 10−96.68 × 10−33.29 × 10−43.28 × 10−67.86 × 10−54.44 × 10−34.98 × 10−101.10 × 10−8
Environment 51.44 × 10−144.28 × 10−122.25 × 10−129.05 × 10−141.12 × 10−128.30 × 10−133.21 × 10−141.67 × 10−93.83 × 10−10
Environment 62.14 × 10−96.18 × 10−91.78 × 10−133.61 × 10−24.37 × 10−22.62 × 10−34.01 × 10−24.12 × 10−22.23 × 10−5
No significant differences are shown in bold.
Table 6. Friedman test results in different environments.
Table 6. Friedman test results in different environments.
EnvironmentsIndicatorsPSODETLBOSMASSATLSMACSSABESmBESEAB-BES
Environment 1Mean score4.84.78.05.45.55.15.36.25.03.9
Rank32107856941
Environment 2Mean score8.05.76.13.76.84.06.76.85.51.7
Rank10562837841
Environment 3Mean score5.84.75.65.95.95.35.47.85.53.0
Rank72688341051
Environment 4Mean score7.75.24.35.06.55.65.05.96.43.4
Rank10523963781
Environment 5Mean score8.14.24.83.98.15.24.06.86.13.8
Rank9452963871
Environment 6Mean score6.44.76.65.15.45.66.07.64.82.8
Rank82945671031
Table 7. Cohen’s d effect size between EAB-BES and other comparative algorithms across six environments.
Table 7. Cohen’s d effect size between EAB-BES and other comparative algorithms across six environments.
EnvironmentsEAB-BES VS
PSODETLBOSMASSATLSMACSSABESmBES
Environment 10.210.261.060.100.210.110.520.160.62
Environment 21.400.931.340.421.150.701.191.060.82
Environment 30.970.730.700.800.900.680.670.780.86
Environment 41.460.770.430.611.050.690.281.090.91
Environment 52.220.590.840.291.560.880.111.141.41
Environment 61.711.331.230.840.921.110.810.981.14
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

Zhang, Y.; Xiao, W.; Yin, S. EAB-BES: A Global Optimization Approach for Efficient UAV Path Planning in High-Density Urban Environments. Biomimetics 2025, 10, 499. https://doi.org/10.3390/biomimetics10080499

AMA Style

Zhang Y, Xiao W, Yin S. EAB-BES: A Global Optimization Approach for Efficient UAV Path Planning in High-Density Urban Environments. Biomimetics. 2025; 10(8):499. https://doi.org/10.3390/biomimetics10080499

Chicago/Turabian Style

Zhang, Yunhui, Wenhong Xiao, and Shihong Yin. 2025. "EAB-BES: A Global Optimization Approach for Efficient UAV Path Planning in High-Density Urban Environments" Biomimetics 10, no. 8: 499. https://doi.org/10.3390/biomimetics10080499

APA Style

Zhang, Y., Xiao, W., & Yin, S. (2025). EAB-BES: A Global Optimization Approach for Efficient UAV Path Planning in High-Density Urban Environments. Biomimetics, 10(8), 499. https://doi.org/10.3390/biomimetics10080499

Article Metrics

Back to TopTop