Next Article in Journal
Research on Swarm Control Based on Complementary Collaboration of Unmanned Aerial Vehicle Swarms Under Complex Conditions
Next Article in Special Issue
A Hierarchical Control Algorithm for a Pursuit–Evasion Game Based on Fuzzy Actor–Critic Learning and Model Predictive Control
Previous Article in Journal
Fixed/Mobile Collaborative Traffic Flow Detection Study Based on Wireless Charging of UAVs
Previous Article in Special Issue
Assignment Technology Based on Improved Great Wall Construction Algorithm
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Multi-Objective Black-Winged Kite Algorithm for Multi-UAV Cooperative Path Planning

1
Department of Aeronautics and Astronautics, Fudan University, NO. 220 Handan Road, Yangpu District, Shanghai 200433, China
2
Technology and Engineering Center for Space Utilization, China Academy of Science, No. 9 Dengzhuang South Road, Haidian District, Beijing 100094, China
3
Qian Xuesen Laboratory of Space Technology, China Academy of Space Technology, No. 104 Youyi Road, Haidian District, Beijing 100094, China
*
Author to whom correspondence should be addressed.
Drones 2025, 9(2), 118; https://doi.org/10.3390/drones9020118
Submission received: 30 December 2024 / Revised: 31 January 2025 / Accepted: 1 February 2025 / Published: 5 February 2025

Abstract

:
In UAV path-planning research, it is often difficult to achieve optimal performance for conflicting objectives. Therefore, the more promising approach is to find a balanced solution that mitigates the effects of subjective weighting, utilizing a multi-objective optimization algorithm to address the complex planning issues that involve multiple machines. Here, we introduce an advanced mathematical model for cooperative path planning among multiple UAVs in urban logistics scenarios, employing the non-dominated sorting black-winged kite algorithm (NSBKA) to address this multi-objective optimization challenge. To evaluate the efficacy of NSBKA, it was benchmarked against other algorithms using the Zitzler, Deb, and Thiele (ZDT) test problems, Deb, Thiele, Laumanns, and Zitzler (DTLZ) test problems, and test functions from the conference on evolutionary computation 2009 (CEC2009) for three types of multi-objective problems. Comparative analyses and statistical results indicate that the proposed algorithm outperforms on all 22 test functions. To verify the capability of NSBKA in addressing the multi-UAV cooperative problem model, the algorithm is applied to solve the problem. Simulation experiments for three UAVs and five UAVs show that the proposed algorithm can obtain a more reasonable collaborative path solution set for UAVs. Moreover, path planning based on NSBKA is generally superior to other algorithms in terms of energy saving, safety, and computing efficiency during planning. This affirms the effectiveness of the meta-heuristic algorithm in dealing with multiple objective multi-UAV cooperation problems and further enhances the robustness and competitiveness of NSBKA.

1. Introduction

The low-altitude domain is increasingly becoming a fresh frontier for economic activities [1]. The development of a low-altitude economy is closely tied to the rapid advancements in UAV technology and the expansion of its application fields [2]. Meanwhile, UAVs have been extensively deployed across various fields, including digital twin technology [3], agricultural production [4], medical services [5], power inspections [6], and other areas. In most of these fields, the development of efficient UAV path planning remains one of the most important research issues [7,8]. The key problem of path planning lies in determining the safe and efficient routes from the starting point to the destination. Despite consistent advancements in path-planning research over recent decades, it still presents significant challenges in complex scenarios, such as contingency task planning [9], infrastructure inspection [10], and environments with restricted communication capabilities [11].
The challenge of UAV path planning is usually formulated as an optimization problem, with numerous single-objective and multi-objective optimization strategies having been proposed over recent years to address a range of UAV applications [12,13,14]. As research into multi-UAV systems progresses, there has been a significant rise in the number of UAVs collaborating simultaneously, and the complexity of mission scenarios that must be addressed increases. Using single-objective optimization methods to address multi-UAV path planning is becoming increasingly challenging due to the complex planning requirements. For example, in the study of UAVs equipped with sensors for area exploration, monitoring, and data collection, İslam et al. [15] proposed to optimize objectives like coverage duration and the connectivity of a group of UAVs through a framework that combines a single-weighted approach with multi-objective optimization. The results indicate that solutions derived from a single weighted objective are less diverse and do not balance the weights of objectives as effectively as those obtained through multi-objective optimization techniques. In multi-UAV applications, planning an appropriate flight path is a common requirement. However, in the task of highly complex UAV mission scenarios, it is necessary to evaluate the quality of the obtained flight path based on multiple objectives for further optimization.
At present, the prevalent approaches to UAV path planning include artificial potential fields [16], graph-based search algorithms [17,18,19,20], sampling-based approaches [21,22,23], and meta-heuristic intelligent algorithms [24,25,26]. However, these methods mainly focus on a single objective: aiming for the shortest path to obtaining the optimal solution. Generally, minimizing path length aims to shorten the path as much as possible, so as to ensure the mission efficiency of the UAV at a constant flight speed. For example, Wu et al. proposed an improved 3D artificial potential field method to solve the problem of maintaining UAV formation and avoiding spatial obstacles in the pursuit of the shortest path for UAV formation in path planning [27]. However, this method emphasizes formation control of the whole UAV group, which results in a lack of individual autonomy for each UAV. While path length is a commonly used criterion in UAV path planning, additional objectives must be considered when planning for multiple UAVs. For example, for the task of locating defects in a multi-UAV inspection pipeline network, path length, energy consumption, and flight height should be considered as the major objectives for high-quality trajectory planning. Inspired by booby behavior, Aljalaud et al. proposed a specific heuristic algorithm for the task to minimize the UAVs’ total travel length and energy cost and prevent collisions [28]. Clearly, these objectives suggest that the complexity of multi-UAV path planning extends beyond simply minimizing path length. In planning the paths for indoor UAV inspections, objectives like the number of UAVs assigned to each inspection point, their flight speed, and the inspection time should also be considered. Zhang et al. addressed this challenge by developing a search algorithm called CFSSA, which integrates chaotic cube mapping initialization, firefly algorithm disturbance search, and tent chaos mapping perturbation search [29]. While they treated these factors as constraints to simplify computations, further optimizations involving these potential objectives should be conducted for multi-UAV cooperative path planning. Typically, energy loss can be evaluated by examining path smoothness, as more frequent and sharper turns lead to higher energy consumption in UAV flights [30]. Nonetheless, for practical tasks involving multi-UAV cooperation, it is insufficient to only consider energy consumption, the number of UAVs, and potential airframe collisions as additional constraints. Instead, they should be regarded as essential objectives regarding energy saving, task efficiency, as well as path safety.
Considering that the problem’s computational complexity is manageable, the weighted sum method is a primary approach in multi-objective path planning [31,32]. Essentially, it transforms the multi-objective optimization problem into a single-objective one by applying different weights and finally obtains a single optimal solution. However, the method’s limitation lies in its inability to recognize the relative importance of various objectives. For example, Wang et al. treated the path-planning issue as a mathematical optimization problem combining the objectives of path length and smoothness [33]. Here, achieving a balance between path length and smoothness is challenging, since finding a suitable weight depends on the experiments, which do not always ensure the identification of the optimal weight values. By considering the threat cost, flight height cost, and the distance from the endpoint when encountering obstacles, Deng et al. used the weighted sum method to formulate the UAV path-planning model’s objective function, and it is rather challenging to choose the appropriate weights due to the multiple objectives to be evaluated [34]. It is noteworthy that the effectiveness of path planning cannot be guaranteed by considering only a single objective or by weighting multiple objectives into a single one. With the increasing number of conflicting objectives, relying solely on weights becomes insufficient to yield the desired range of alternative solutions.
Indeed, some studies even indicate potential conflicts among these aforementioned objectives [35,36]. For conflicting goals, a set of alternative solutions is often preferred over an optimal solution. Therefore, our work addresses the application challenge of multi-UAV cooperative delivery in urban environments by framing a multi-UAV cooperative path-planning model. We classify conflicting optimization goals into two types: minimizing energy consumption and maximizing safety. Furthermore, a novel multi-objective optimization algorithm based on the non-dominated sorting technique and black-winged kite algorithm (NSBKA) is proposed to solve this intricate issue. Building upon the BKA approach, our approach initially sorts the population by dominance levels, followed by calculating the crowding distance to assess the distribution density of each individual. An external archive is then established to store non-dominated individuals with high crowding distances, ensuring a diverse and well-distributed set of solutions. This strategy effectively addresses multi-objective optimization problems by promoting both convergence and diversity in the Pareto front approximation.
The main contributions of this study are summarized below:
  • A mathematical model for urban UAV logistics delivery is formulated, with a thorough analysis of the constraints and objectives for multi-UAV cooperative path planning, and the threat distribution under urban logistics delivery is also considered. The multi-objective optimization method is proposed to evaluate each independent cost function;
  • The NSBKA algorithm has been introduced based on the BKA. The improved algorithm is now capable of addressing multi-objective optimization problems by integrating the non-dominated sorting technique and the crowding-distance calculation method;
  • The NSBKA algorithm is rigorously tested across 22 test functions that are commonly used in multi-objective optimization. The IGD (indicator of generational distance), HV (hypervolume), and CPU running time are selected as metrics for performance assessment. Additionally, the NSBKA’s multi-objective optimization capabilities are compared with the multi-objective grey wolf optimizer (MOGWO), the multi-objective sparrow optimization algorithm (MOSSA), the multi-objective stochastic paint optimizer (MOSPO), and multi-objective generalized normal distribution optimization (MOGNDO) to verify its efficacy;
  • Simulation experiments have been conducted by applying the NSBKA and other algorithms to solve the multi-UAV cooperative path-planning problem, with a comparative analysis of the simulation results for scenarios involving three and five UAVs with identical parameters to ascertain the method’s efficacy in tackling such cooperative path-planning issues.
The remainder of this article is organized as follows. Section 2 introduces the basic concepts of the multi-objective optimization problem and the BKA algorithm. Section 3 provides an overview of the problem description and mathematical model for multi-machine cooperative path planning. Section 4 focuses on detailing the specific improvements made to the NSBKA algorithm and outlines the experimental setup designed to validate the optimality of the algorithm. Section 5 summarizes and analyzes the results of the experiment. Section 6 concludes the paper with future perspectives and potential directions for research.

2. Related Work

To investigate the mathematical models of the multi-UAV cooperation problem and their solution methodologies, it is imperative to acquire a foundational understanding of the relevant theoretical knowledge, which includes the fundamental definitions of multi-objective optimization and the core principles of the black-winged kite algorithm (BKA). Such prerequisite knowledge furnishes the essential theoretical underpinnings for the subsequent construction of models and the resolution of problems.

2.1. Multi-Objective Optimization Problem

In this study, cooperative path planning for multi-UAVs is regarded as a multi-objective optimization problem, and the multi-objective optimization method is designed to address the multiple conflicting objectives. As a constraint optimization problem, it is essential to simultaneously satisfy both the performance and cooperative constraints of the UAVs. This ensures that the collective flight paths of the UAVs are optimized for minimal length (with the lowest energy consumption) and maximal safety along those paths.
The mathematical model of the multi-objective optimization problem is illustrated as follows [37],
minimize :   F x = f 1 x , f 2 x , f 3 x , , f m x
subject   to :   g i x 0 ,   i = 1 , 2 , 3 , , p
h j x = 0 ,   j = 1 , 2 , 3 , , k
L q x q U q ,   q = 1 , 2 , 3 , , n
where x is the decision vector, f1(x), f2(x), …, fm(x) are the different objective functions, and m represents the number of objective functions. In Equation (1), F(x) represents a whole function, consisting of multiple objective functions f1(x), f2(x), …, fm(x) that should be optimized simultaneously. In Equation (2), gi(x) ≥ 0 denotes the i-th inequality constraint, and p is the number of inequality constraints. In Equation (3), hj(x) = 0 is the j-th equality constraint, with k being the number of constraints. Equation (4) is the value range of the q-th variable xq. Uq and Lq are the upper and lower bounds of the corresponding variable, and n is the number of variables, respectively.
The multi-objective problem usually does not have a single optimal solution like the single-objective problem. So, Pareto optimal solution is used to express the definition of formula 1’s solution, and the related concepts are described in Definitions 1 and 2. In Equation (1), the objectives of multi-objective optimization are independent of each other, and they represent different aspects of the problem. In the optimization process, the optimization direction of the targets and the physical or usage properties on which they are based determine that their units do not need to be unified.
Definition 1. 
Pareto Dominance.
Pareto dominance is a criterion used to compare solutions in a multi-objective optimization problem. Suppose that there are two solutions x = (x1, x2, …, xn) and y = (y1, y2, …, yn). Vector x is said to dominate vector y (defined as x < y) if and only if the following two conditions are satisfied:
(1)
x is no worse than y in all objectives;
(2)
x is strictly better than y in at least one objective.
Mathematically, for a minimization problem with m objectives, x < y if:
u { 1 , 2 , , m } ,   f u x f u y v { 1 , 2 , , m } ,   f v x < f v y
If neither solution dominates the other, they are considered non-dominated.
Definition 2. 
Pareto Optimality.
Solution x is said to be Pareto optimal (or non-dominated) if it is not dominated by any other feasible solution in the search space. In other words, there exists no other solution that can improve one objective without degrading at least one other objective. Pareto optimality represents the best possible trade-off between conflicting objectives.
Figure 1 intuitively illustrates the dominant relationships among the solutions through the distribution of bi-objective optimization solutions. It can be clearly seen that x2 dominates x3, and {x1, x2, x4, …, xc} constitutes a set of Pareto-optimal solutions.
Definition 3. 
Pareto Optimal Set.
The Pareto optimal set (also known as the Pareto set) P is the collection of all Pareto optimal solutions in the decision space. Formally, it is defined as:
P * = x * Θ | x Θ , x x *
where Θ represents the feasible decision space. Each solution x* in the Pareto optimal set is a candidate for the optimal trade-off between objectives.
Definition 4. 
Pareto Optimal Front (PF).
The Pareto optimal front (also known as the Pareto front) is the set of objective function values corresponding to the Pareto optimal set. It represents the optimal trade-offs between objectives in the objective space. Formally, it is defined as:
P F * = F x * | x * P *
where F(x*) = (f2(x*), f2(x*), …, fm(x*)) is the vector of objective values for a Pareto optimal solution x*. The Pareto front provides a visual and analytical representation of the best achievable performance for the multi-objective problem.

2.2. Black-Winged Kite Algorithm

2.2.1. Description of BKA

BKA is a population-based metaheuristic optimization algorithm inspired by the migration and foraging behaviors of black-winged kite birds [38]. Similar to other metaheuristic methods, the initialization of BKA requires the generation of a random set of solutions:
X Initial = X 1 , 1 X 1 , 2 X 1 , dim X N , 2 X N , 2 X N , dim
where N is the number of potential solutions, dim is the dimension size of the given problem, and Xi,j is the j-th dimension of the i-th black-winged kite.
The positions of the individuals in the initial population are randomly generated within a given range, which makes the individuals in the population have a certain diversity and can better explore the solution space
X i = X l b + r a n d X u b X l b
where i is an integer between one and N, Xlb and Xub are the lower and upper bounds of i-th black-winged kite in the j-th dimension, respectively, and rand() is a value chosen at random between [0, 1].
After the initial solution is generated, the individual of the initial population is calculated, and the individual with the best fitness value, where the objective function value representing the scalar is minimized, is selected as the leader.
The optimization process of the BKA is divided into two parts. The first part focuses on the foraging behavior of the black-winged kite, and the second part simulates its migration behavior. Based on the aforementioned principles, the pseudocode of BKA is depicted in Algorithm 1.
Algorithm 1: Pseudocode of the BKA.
Input: The population size N, maximum number of iterations T, and variable dimension dim
Output: The best quasi-optimal solution obtained by BKA for a given optimization problem.
Initialization phase
Initialization of the position of black-winged kites and evaluation of the objective function.
Calculate the fitness value of each Black-winged kite
while (t < T) do
/* Attacking behavior */
if p < r
xi,j(t + 1) = xi,j(t) + n(1 + sin(r)) × xi,j(t)
end if
  xi,j(t + 1) = xi,j(t) + n(2r − 1) × xi,j(t)
end
/* Migration behavior */
if Fi < Fri
xi,j(t + 1) = xi,j(t) + C(0, 1) × [xi,j(t) − Lj(t)]
end if
  xi,j(t + 1) = xi,j(t) + C(0, 1) × [Lj(t) – m × xi,j(t)]
end
/* Select the best individual */
if f[xi,j(t + 1)] < f[Lj(t)]
  Xbest = xi,j(t + 1), Fbest = f[xi,j(t + 1)]
end if
  Xbest = Lj(t), Fbest = f[Lj(t)]
end
end while
 Return Xbest and Fbest

2.2.2. Foraging Behavior

As a predator of small mammals and insects in grasslands, the black-winged kite often hovers in the air to find the attack opportunity and directly attacks, which inspires the foraging behavior to realize the global search and local search. To achieve a more effective balance between global and local search performance, the algorithm introduces a parameter p to control the individual selection behavior. Additionally, the non-linear reduction of the variable n with the increase in iterations enables the algorithm to avoid falling into the local optimal solution.
x t + 1 i , j = x t i , j + n 1 + sin r x t i , j , p < r x t i , j + n 2 r 1 x t i , j , e l s e
n = 0.05 e 2 t T 2
where xti,j is the position of the i-th black-winged kite in the j-th dimension in the t-th iteration steps, r is a random number that ranges from zero to one, p is a constant value of 0.9, T is the total number of iterations, and t is the number of iterations that have been completed so far.

2.2.3. Migration Behavior

The migration behavior of birds is to find more suitable favorable habitats and more survival resources, and this behavior is usually guided by leaders within the flock. In the case of the black-winged kite, Wang et al. made an assumption that individuals in the population would choose a way to migrate in a favorable direction according to the capabilities of the leader. The following presents the mathematical models of the two migration types:
x t + 1 i , j = x t i , j + C 0 , 1 x t i , j X L t j , F i < F r i x t i , j + C 0 , 1 X L t j m x t i , j , e l s e
m = 2 sin r + π / 2
where Fi represents the fitness value of the current position in the j-th dimension obtained by the i-th black-winged kite in the t iteration, Fri represents the fitness value of the random position in the j-th dimension obtained from any black-winged kites in the t-th iteration, and C(0, 1) represents the Cauchy mutation, which is the probability density function of the Cauchy distribution in standard form and is used to convert the uniform distribution to the Cauchy distribution in standard form.

3. Mathematical Model for Cooperative Path Planning of Multiple UAVs

This section systematically elucidates the mathematical model for multi-UAV cooperative path planning, with a particular focus on the formulation of safety and low-energy consumption objective functions. It also provides a detailed analysis of the constraints pertaining to flight altitude, velocity, angle, and trajectory length.

3.1. Problem Description

For the multi-UAV cooperative path-planning problem, multiple UAVs take off simultaneously from adjacent locations, navigating while avoiding all kinds of obstacles to reach their respective destinations, thereby fulfilling the task requirements. Therefore, this work focuses on flight energy consumption, path safety, and the spatiotemporal cooperation of UAVs and establishes the corresponding mathematical models. In practical operations, it is often necessary to consider the flight constraints of the individual UAV and the cooperative constraints between multiple UAVs. To simplify the calculation of multi-UAV trajectory experimental simulations within three-dimensional (3D) planning space, the following assumptions have been made:
(1)
the flight speed of the UAV is uniform and unchanged during the performance of the mission;
(2)
the path of each UAV is divided into a plurality of path segments, in which the UAV can be regarded as flying in a straight line;
(3)
all UAVs are isomorphic;
(4)
ignoring the influence of external weather and airflow on drone flight;
(5)
all UAV information interactions are assumed to be in an ideal state of communication, with no delays, interruptions, etc.

3.2. Differences Between Multi-Objective and Single-Objective Weighting Methods

Suppose that there is a single-objective optimization problem, where the objective is to minimize the function G = w1g1(ζ) + w2g2(ζ), where w1 and w2 both represent weight coefficients and ζ= {ζ1, ζ2, …, ζk} is the vector of decision variables. In the case of a single-objective optimization problem, if there are two solutions, ζ1 and ζ2, and the optimization objective is to minimize G, then ζ1 is superior to ζ2 if and only if G(ζ1) < G(ζ2).
In the context of multi-objective optimization, given two solutions a1 and a2, for the objective functions (g1(ζ), g2(ζ)), a1 dominates a2 if and only if Equation (14) is satisfied.
i { 1 , 2 , , k } ,   g i ζ 1 g 2 ζ 2 j { 1 , 2 , , k } ,   g j ζ 1 < g j ζ 2
If there is no dominant relationship between the two solutions, they are incomparable, and this situation generally does not occur in single-objective optimization.
The single-objective weighting method ultimately results in a single objective function, which combines multiple sub-factors through weighting. In contrast, the multi-objective method keeps multiple objective functions independent and focuses on the dominant relationships and trade-offs among these objective functions.
The single-objective weighting method obtains a solution that optimizes the weighted objective function. In the multi-objective method, a set of Pareto-optimal solutions is obtained. These solutions have different characteristics in terms of the trade-offs among various objectives, and no single solution is absolutely optimal for all objectives. For example, in a bi-objective (minimization) problem, the single-objective weighting method may find a solution ζw that minimizes w1g1(ζ) + w2g2(ζ), while the multi-objective method can find a set of solutions {a1, a2, …}, and these solutions have different trade-offs between g1(ζ) and g2(ζ), thus forming the Pareto front.

3.3. Multi-UAV Cooperative Cost Model

The objective functions in the mathematical model are the core part of UAV path planning, which represents the objectives to be accomplished by path planning. The assessment of UAV path quality usually involves multiple indicators. Traditional UAV path-planning research predominantly employs the technique of weighting objective functions, with the significance of each target dictating its weight. This approach essentially transforms the problem into a single-objective optimization task. While this method streamlines the problem and reduces computational load, it typically yields solutions that are satisfactory only in terms of the overall fitness value of the objective function. In fact, it is often the case that objectives are in conflict with one another, where enhancing one objective may result in a decline in the performance of other objectives. Given these inherent trade-offs, achieving optimal performance across all objectives simultaneously is typically unattainable. Therefore, the more promising approach is to find a balanced solution that effectively reconciles competing objectives aimed at optimizing overall system performance. This study avoids the influence of artificial weighting and uses the multi-objective optimization algorithm to solve the optimization problem of multi-machine cooperative path planning. For multi-objective optimization, the optimal solution is no longer the solution that minimizes the single objective function, but the Pareto solution set. In practical applications, the solution set must also be selected according to the preference of the decision maker.
In this study, we have chosen the alternative approach, which treats the multi-UAV cooperation model as a multi-objective optimization problem and proposes three representative objective functions for evaluation. In addition, given that the model is intended for application in urban logistics delivery, any obstacles that the UAV may encounter during the mission are regarded as threats.
(1)
Energy Consumption Objective
Energy consumption is one of the most important indicators of UAV mission planning, which can be intuitively expressed by the length of the flight path. Therefore, the sum of the flight ranges of all UAVs is used to represent the cost of this objective:
f 1 = i = 1 N u j = 0 N p i p j i p j + 1 i
where |pijpij+1| represents the length from the j-th track point of the i-th UAV to the (j + 1)-th track point, Nu represents the number of UAVs, and Npi represents the number of track points of the i-th UAV.
(2)
Safety Objective
The primary safety concern for UAV path planning is to avoid urban obstacles. As illustrated in Equation (16), if a certain path segment in the planning is inside or intersects with the obstacles, then that path is treated as an infeasible path. A larger penalty term is used to exclude it from optimization.
f 2 = A / a r g S ,   No   trajectory   segments   pass   through   the   obstacle M ,   Trajectory   segments   pass   through   the   obstacle
a r g S = i = 1 N u i = 1 N p i + 1 r i / N p i + 1
where M and A are both constants, representing the penalty for approaching the obstacle area, A = 100, M is larger, M = 10,000, and ri is the distance of each path segment from the nearest obstacle.

3.4. Constraints

As moving objects in three-dimensional space, the constraints influencing UAVs are mainly determined by the physical characteristics and mission requirements [39]. In addition, as a cooperative constraint, it is essential to ensure that each UAV in the formation can successfully complete the flight mission under the constraints of a single track.

3.4.1. Flight Height Constraints

Throughout the flight space, drones must maintain an altitude above the minimum required to prevent unnecessary collisions at low altitudes while also ensuring that they do not exceed a certain altitude to avoid inefficient mission execution caused by high altitudes. In addition, the flight altitude should also comply with the range allowed by low-altitude regulations.
h min h i h max
Among them, hi represents the vertical height of the i-th UAV in the planned space, hmin is the lowest allowable altitude, and hmax is the maximum flight altitude.

3.4.2. Flight Maximum Distance and Minimum Distance Constraints

Due to the limitations of energy consumption and mission efficiency, it is very necessary for UAVs to have a definite maximum range to ensure mission completion. Assuming that the maximum range of a single UAV is Lmax, then
j = 0 N p i + 1 p j p j + 1 L max
where |pjpj + 1| represents the distance between the j-th track point and the (j + 1)-th track point.
Since the drone needs to fly a certain distance as a buffer when changing course, the minimum distance at which its maneuverability can change course is limited:
p j p j + 1 L min
where Lmin denotes the shortest flight distance.

3.4.3. Flight Speed Constraints

Considering the local weather conditions and wind speed, it is necessary to limit the drone’s flight speed within a secure range to guarantee stable and safe operation.
v min v i v max
where vi indicates the flight speed of the i-th UAV, vmin and vmax indicate the minimum and maximum speed, respectively.

3.4.4. Flight Angle Constraints

Given the performance constraints of UAVs, executing sharp turns at constant speed is challenging. Therefore, the angle between successive segments of the flight path should be within a reasonable range. In addition, considering the maneuverability and the payload requirements for logistics missions, the ascent angle during flight should not be too large.
θ min θ θ max
φ min φ φ max
where q is the pitch angle, qmax and qmin are the maximum and minimum allowable values of the pitch angle, j is the yaw angle, and jmax and jmin are the maximum and minimum allowable yaw angles, respectively.

3.4.5. Spatiotemporal Cooperative Constraints

Spatial cooperation among UAVs is designed to minimize the potential for conflicts and prevent collisions among all agents. Temporal cooperation mandates that the time each UAV takes to reach its target must fall within acceptable error margins [40].
X i t X j t d s a f e ,   i j
T i min , T i max T j min , T j max
T i T i min , T i max = L i / V i max , L i / V i min , T j T j min , T j max = L j / V j max , L j / V j min
where Xi(t) is the position of the i-th UAV at time t, Xj(t) is the position of the j-th UAV at time t, and dsafe is the minimum distance between UAVs to maintain a safe flight.. Vi, Li, and Ti are the speed, path length, and arrival time of the i-th UAV, respectively. Vj, Lj, and Tj are the speed, path length, and arrival time of the j-th UAV, respectively.

4. Methodology

This section provides a comprehensive exposition of the NSBKA method proposed in this study, systematically configures the parameters of the test functions employed in the experiments, and introduces the criteria for evaluating the convergence and diversity of the test results.

4.1. Optimization Process of Non-Dominated Sorting Black-Winged Kite Algorithm (NSBKA)

4.1.1. Non-Dominated Sorting

In the non-dominated sorting process, each individual in the population has two parameters, N and S. N(i) represents the number of individuals whose solutions dominate the i-th individual in the population [41,42,43]. S(i) is the set of individuals whose solutions are dominated by i-th individual. According to the Pareto dominance relationship, the fewer times an individual is dominated, the better the individual is. The pseudocode for non-dominant sorting is shown in Algorithm 2.
Algorithm 2: Pseudocode of the non-dominated sorting
Input: The number of solutions in population P is M
Output: A list of non-dominant frontiers with different ranks F = {F1, F2, F3, …, Fk}
Initialize phase:
Initializes the number representing the rank k = 1
for i = 1 to M do
  Initialize S(i) as an empty set, N(i) = 0
 for q = 1 to M do
  if i dominates q
   add q to S(i)
  else
   N(i) = N(i) + 1
  end if
  end for
  if N(i) = 0
   set irank = 1
   add i to F1
  end if
end for
while Fk is not empty
  initialize an empty set Q
  for each solution i in Fk
  for each solution q in S(i)
   N(q) = N(q) − 1
   if N(q) = 0
  qrank = k + 1
  add q to Q
  end if
  end for
  end for
  k = k + 1
  set Fk = Q
while
return F

4.1.2. External Archive

Unlike BKA, the fitness in multi-objective optimization algorithms is represented by objective vectors rather than scalars, which makes it impossible to conduct direct comparisons. Therefore, NSBKA sets up an external archive outside the population and continuously updates the external archive by utilizing the non-dominated solutions generated in each iteration of the algorithm [44]. To manage these solutions and maintain the archive, several rules have been formulated for updating or modifying the archive, and the details are as follows:
(1)
If there exists a solution in the external archive that dominates the new individual generated in each iteration of the algorithm, the new individual will not be added to the external archive;
(2)
If the new individual dominates one or more individuals in the external archive, then the new individual will replace the dominated individuals in the external archive;
(3)
If the new individual and all the individuals in the external archive do not dominate each other, then the new individual will be added to the external archive;
(4)
Set an upper limit for the external archive. If the newly added non-dominated solutions meet the above conditions but the archive is full, then individuals with a high crowding distance will be taken into consideration.

4.1.3. Crowding Distance

To ensure that the number of individuals in the external archive population does not exceed the upper limit and maintain the population diversity at the same time, a method of removing similar individuals according to the magnitude of the crowding degree of solutions is adopted to prune the population. The calculation method regarding the crowding degree is shown as follows:
(1)
the objective function values F(f1, f2, …, fi, …, fN) of each individual in the external archive population are calculated;
(2)
all of the objectives of the current individual need to be traversed and calculated to find the extreme values of fimax and fimin of each objective;
(3)
the crowding distance of each individual is computed in accordance with Equation (27).
D c j = i = 1 N f i j + 1 f i j 1 f i max f i min
where fi(j − 1) and fi(j + 1) are the fitness values of the two individuals adjacent to individual (j − 1)-th and (j + 1)-th in the i-th objective function, Dc(j) is the crowding distance of the j-th individual, and N is the number of objective functions.
When the number of individuals in the external archive population exceeds the upper limit, those individuals with a higher crowding degree, that is, the individuals with a smaller value of Dc(j), will be preferentially selected and removed from the external archive population. This is conducted to maintain the upper limit of the number of individuals in the population and simultaneously preserve the population diversity.

4.1.4. Non-Dominated Sorting Method

In this section, we propose the NSBKA algorithm, which is designed to address multi-objective optimization problems. This multi-objective optimization algorithm employs a well-diversified population to achieve an evenly distributed set of Pareto solutions within the target space, thereby avoiding the local optimal search. We adopt the same non-dominated hierarchical sorting strategy as NSGA-II and compare the crowding degree among individuals in the same non-dominated rank. To prevent the loss of Pareto solutions, we also introduce external archives to store non-dominated solutions and individuals with better crowding. The pseudo-code for the NSBKA algorithm is shown in Algorithm 3.
Algorithm 3: Pseudocode of the NSBKA
Input: The population size N, maximum number of iterations T, external archive size M, attacking parameters r = rand() and p = 0.9, and variable dimension dim
Output: The Pareto optimal solution obtained by NSBKA for a given optimization problem
Initialize phase:
Calculate the initial solution X and update the external archive.
while (t < T)
/* Attacking behavior */
 Calculate n by Equation (11)
if p < r
Xi,new(t) = X i(t) + n(1 + sin(r))Xi(t)
else
Xi,new(t) = Xi(t) + n(2r − 1)Xi(t)
end if
if Xi,new(t) < Xi(t) (Xi,new(t) dominates Xi(t))
 Update the Xi(t + 1) = Xi,new(t)
end if
/* Migration behavior */
 ∀Xi,L(t)∈Archive()
ifkN, F(Xi,L(t)) ≦ F(Xk(t))
Xi,new(t) = X i(t) + C(0, 1)[X i(t) − Xi,L(t)]
else
Xi,new(t) = X i(t) + C(0, 1)[Xi,L(t) − m×X i(t)]
end if
if Xi,new(t) < X i(t)
 Update the X i(t + 1) = Xi,new(t)
end if
/* Update the archive*/
 Calculate according to the strategiesin Section 4.1 and Equation (27), and then select the solutions that meet the requirements and put them into the archive.
t = t + 1
end while
Return

4.2. Performance Analysis on Benchmark Test Functions

In this section, three widely used benchmark test set functions ZDT, DTLZ [45], and 10 standard multi-objective test problems from CEC2009 [46,47] are employed to examine the efficacy of NSBKA. The ZDT functions are tailored to check the performance of algorithms designed for bi-objective problems, whereas the DTLZ benchmark problem suite proposed by Deb et al. differs from ZDT, in that it offers scalability to any number of objectives. CEC2009 includes both dual-objective and triple-objective testing functions. To test the algorithm, we selected five bi-objective test functions from the ZDT suite, seven three-objective test functions from DTLZ, and ten test functions from CEC2009 to compare the approximate PF of the NSBKA and other algorithms [48]. Table 1 shows the number of objective functions, the description of PF distribution characteristics, and the number of samples of real PF for various test problems.
According to Table 1, we used ZDT1 to ZDT6 to test the bi-objective problem set, and the variable dimension of ZDT1 to ZDT6 was 10. ZDT1 and ZDT4 present a continuous and uniformly distributed convex Pareto front. ZDT2 showcases a concave Pareto front. ZDT3 displays five non-convex discontinuous fronts. ZDT6 presents a non-uniform Pareto front with an irregular mapping between the objective function space and decision variable space. At the same time, we used DTLZ1 to DTLZ7 to test the three-objective problem, and the variable dimensions are 12, except that the variable dimension of DTLZ1 is 7 and the variable dimension of DTLZ7 is 22. The variable dimensions of the UF function are all 10, and its PF combines the characteristics of ZDT and DTLZ.

4.3. Performance Metrics

In this section, since a single performance metric is not sufficient to adequately evaluate the performance of an algorithm, the hypervolume (HV) and inverted generational distance (IGD) have been selected to quantify the convergence and diversity of the test algorithm. Simultaneously, the computational efficiency of the algorithm was evaluated by the computing time of the test problem on the CPU.
The IGD index is a metric for gauging algorithm convergence, primarily evaluated by calculating the average distance from the uniform distribution solution of the approximate PF and the true PF obtained from the test algorithm to the nearest solution [49]. A smaller IGD value means better convergence [41]. An explanation of IGD is shown in Figure 2.
I G D = i = 1 n d i 2 n
where n is the number of true Pareto optimal solutions, and di is the Euclidean distance between the i-th obtained Pareto optimal solution in the reference solution set, the tested solution set, and the measured Pareto optimal solution.
The HV index is related to the convergence to the true PF and the diversity of the obtained solutions, with a larger HV implying higher convergence and coverage [50]. The algorithm is evaluated by computing the union collective product of all hypercubes, which yields a set of solutions that together form a larger hypercube with the reference point as the diagonal [48].
H V = δ a P A v a
where d represents the Lebesgue measure, which is used to calculate the volume of the hypercube. Va is a hypercube formed by solution A and the corresponding reference point in the non-dominant solution set. Meanwhile, when calculating the HV value, the first step is to normalize the target value of the non-dominant solution. This is obtained by using the ideal point and the lowest point of the true PF. An explanation of HV is shown in Figure 3.
In addition, to assess the computational efficiency, we compared the average computation times of all the algorithms across multiple runs on a given test problem, using this as a metric to validate the algorithm’s performance.

4.4. Experimental Setup

The experimental environment for this research is the Windows 11 operating system, using an AMD Ryzeen7 5800H CPU @ 3.20 GHz. To ensure optimal performance in the algorithm comparison, we adhered to the parameters specified in the original sources. In addition, to maintain the fairness of comparison, the number of populations and iterations of all test algorithms are set to the same number. Specifically, we set the population size to 100 for two-objective problems and 300 for three-objective problems. All algorithms were independently executed 10 times on the MATLAB R2022a platform to ensure that the conclusions were statistically robust.

5. Results and Discussion

In this section, we have designed two sets of experiments, namely benchmark function tests and path simulation experiments, to validate the enhanced performance and efficacy of the refined NABKA algorithm.

5.1. Comparison Between Algorithms

In assessing the performance of our novel new algorithm in multi-UAV path planning, we compared it with MOSSA [51], MOGWO [44], MOSPO [52], and MOGNDO [53] through optimization experiments. Table 2 shows the mean and standard deviation of the IGD metric for the five algorithms across the ZDT, DTLZ, and UF problem sets. When analyzing the results of the test experiment, the symbol “(+)” means better than NSBKA, while “(-)” means that the metric is worse than NSBKA. The last row of Table 2 confirms the superior optimization capability of NSBKA. The NSBKA algorithm outperforms the other four algorithms overall, showing superior optimization performance in 13 of the test cases. Compared with other multi-objective optimization algorithms, NSBKA’s excellent performance can be attributed primarily to its powerful global and local search capabilities. Through its search and update mechanisms for agent positions, NSBKA is able to yield Pareto solutions that exhibit high convergence and diversity. However, it does not dominate in every scenario. For example, in the DTLZ suite, the NSBKA records a lower IGD metric than the MOSSA on DTLZ1, DTLZ2, DTLZ4, and DTLZ7. Additionally, it also shows a lower IGD value on DTLZ7 than MOGWO, MOSPO, and MOGNDO. In the CEC2009 suite, its IGD values underperform in comparison to MOSSA on UF5, UF9, and UF10, and it also underperforms against MOGNDO and MOSPO on UF3 and UF5. While other algorithms might show excellence in certain test cases, NSBKA stands out for its consistently strong performance across the vast majority of test problems examined in this study.
Table 3 presents a comparative analysis of the NSBKA algorithm against MOSSA, MOGWO, MOSPO, and MOGNDO using the HV metric. The proposed approach demonstrates better performance in 12 of the 22 test cases. The NSBKA algorithm exhibits significant superior performance in the DTLZ benchmark tests. Within the DTLZ problem set, NSBKA, with the exception of DTLZ7, achieves HV values that surpass all other algorithms except for MOSSA. When compared to MOSSA, NSBKA demonstrates advantages solely in DTLZ6 and DTLZ7, with the HV value differences between the two algorithms being insignificant. Moreover, the standard deviation of NSBKA on DTLZ2 and DTLZ5 is more stable than that of MOSSA. In the CEC2009 suite, NSBKA’s HV index on UF3 is lower than the other four algorithms. In addition, its HV value on UF5 and UF9 is lower than MOSSA, and its value on UF5, UF8, and UF10 is lower than MOSPO. In summary, NSBKA outperforms other algorithms in terms of HV indicators for a range of test problems.
Table 4 illustrates the comparison of NSBKA with other algorithms regarding CPU runtime, with the bolded numbers representing the most expeditious CPU times required to resolve the problems. It is observed that the NSBKA algorithm demonstrates considerable computational efficiency in addressing bi-objective optimization problems involving ZDT test functions. While the NSBKA algorithm is not the fastest for the ZDT3 function, it is only 2.917 s slower than the leading competitors, a gap that still allows it to outperform algorithms such as MOGWO and MOSPO. In the case of DTLZ test functions, the NSBKA algorithm’s performance in optimizing DTLZ2, 4, and 5 is surpassed only by MOSSA, with negligible differences from the top results. For DTLZ6 and 7, NSBKA achieved the fastest optimization speeds. However, when optimizing UF1-10 test functions, NSBKA shows lower computational efficiency. Except for subpar performances on UF1, 5, 6, and 7, its performance on other functions is moderate compared to other algorithms. The main reason that NSBKA does not markedly outperform other algorithms in CPU computation time is its emphasis on convergence and diversity at the expense of computational efficiency during optimization. Overall, although there is potential for enhancing the computational efficiency of the NSBKA algorithm in multi-objective problem-solving, its optimization outcomes are exceptional.
Figure 4 and Figure 5 illustrates the visualization of the final solutions for NSBKA and the comparative algorithms. A striking superior performance of NSBKA is observed on the CEC2009 test suite. It is also evident that, for the UF1, UF4, and UF8 functions within the CEC2009 test suite, NSBKA yields a broader range of Pareto optimal solutions compared to MOGWO, MOSSA, MOSPO, and MOGNDO. Moreover, the solutions achieved by NSBKA are in the closest proximity to the actual Pareto Front. Such results are ultimately due to differences in local and global search performance between algorithms. In addition, it can be clearly seen from Figure 4 and Figure 5 and Table 2 that both NSBKA and the other algorithms have poor convergence and coverage when computing Pareto optimal sets with discontinuities, such as UF6. This may be due to the large number of discontinuous regions in the search space of UF5 and UF6, which makes the algorithm unable to improve the accurate results on this problem. Finally, the metrics in Table 2 and Table 3 show that the performance of NSBKA in solving the unique three-objective optimization problems of the Pareto real front, such as UF9 and UF10, is not optimal. Therefore, the algorithm has the potential to be improved for solving this kind of problem.

5.2. Cooperative Path-Planning Experiments

This section details the application of NSBKA for addressing the multi-UAV path-planning problem. In the logistics delivery of UAVs, the urban environment plays a primary role in the path planning of UAVs.
Within intricate and congested urban landscapes, UAV flight encounters a multitude of obstacles that constrict the available flight space. For UAV logistics delivery, navigating around the obstacles within the urban landscape enroute to the respective destinations plays a key role in the UAV’s path planning. In this work, a 3D environment is established to simulate UAV logistics delivery, designating various objects such as trees, signal towers, and buildings as obstacles. To simplify the calculation, all obstacles in the simulation environment are represented by cuboids, as shown in Figure 6. The planning environment dimensions are configured at 1000 × 1000 × 50 m3, with experiments conducted for UAV groups consisting of three and five UAVs each. Table 5 shows the size and distribution of each obstacle in the environment. And the position is represented by the point closest to the origin.
The flowchart of the proposed algorithm for path optimization is shown in Figure 7. First, the algorithm parameters, including the population size N and the maximum number of iterations Tmax, are initialized. Subsequently, the performance constraints for the UAV trajectory, as well as the parameters for the starting and target points, are defined. Then, an iterative process is executed: the objective function for each individual is evaluated, and the feasibility of all UAV waypoints is verified against the predefined constraints. The position equations of the individuals are updated in accordance with Equations (10)–(13), and any waypoints violating the constraints are adjusted. The external archive is then updated using non-dominated sorting and crowding-distance computation methods. Upon completion of the iterations, the optimized Pareto solution set, which satisfies the path-planning constraints, is generated as the final output.
Table 6 demonstrates the range of performance constraint parameters for the UAVs. The initial and goal points of the UAV are provided in Table 7, while Table 8 and Table 9 present the parameters for evaluating path quality. The control parameters of the algorithm are consistent with those used in the optimization function tests. The simulation experiments are executed using Matlab2022a within the previously described environment.
To verify the algorithm’s enhanced planning efficacy within an identical urban setting and across varying mission specifications, we designed two experiments. In Experiment 1, the starting points and target points for each UAV are provided, as shown in Table 7. Each UAV departs from its respective initial point, navigates through various obstacles while satisfying its performance constraints, and ultimately reaches its goal target point. In Experiment 2, the performance constraints remain identical to those in Experiment 1. The sole distinction lies in the fact that Experiment 2 involves path planning for two additional UAVs compared to Experiment 1, and the initial point and goal point of each UAV are shown in the table. All algorithms performed 1000 iterations. The population size was set to 30, and the performance constraint parameters refer to the data in Table 7.

5.2.1. Experiment 1

The number of waypoints for each UAV is set to 24, and 30 Pareto solutions are obtained through algorithm optimization. The visual path represented by each solution is shown in Figure 8. The representativeness of these solutions is then judged by the safety factor and the energy consumption factor. The safety coefficient corresponds to the value of objective function f2, while the energy consumption coefficient corresponds to the value of objective function f1. We select the most representative solution among these Pareto solutions, representing the solution with the path with less energy consumption and the path with high security, as shown in Figure 9 and Table 8.
The simulation results in Figure 9 and Table 8 show that the solution obtained by NSBKA optimizes the mathematical model of multi-UAV collaborative path planning more effectively. As illustrated in Figure 8, the safety-prioritized paths maintain a safe distance from surrounding obstacles. With the exception of UAV2, which has some trajectory segments that approach the obstacles, the other drones’ paths consistently remain at a sufficient distance from the obstacles. This ensures that, during actual flight, the drones minimize the need for emergency obstacle avoidance, thereby enhancing flight safety. In contrast, the energy-efficient paths focus on minimizing length while ensuring obstacle avoidance. The bold numbers in Table 8 are the best of the comparison objects. As a result, all three UAVs adopt a strategy of tight obstacle avoidance to shorten their flight paths. Based on the data in Table 8, the CPU running time for the NSBKA algorithm is 1150.66 s. This result is 41.56 s slower than that of MOGND, but it is significantly faster than MOSSA by 67.17 s, MOGWO by 705.08 s, and MOSPO by 618.10 s, respectively. If the path with the highest safety level from the obtained Pareto solution set is chosen as the representative solution, the safety coefficient for the UAV swarm using the NSBKA algorithm is 3.40. Although this is 0.08 higher than MOSPO, it is lower than that of MOSSA by 0.24, MOGWO by 0.08, and MOGNDO by 0.59, respectively. If the path with the lowest energy consumption from the obtained Pareto solution set is selected as the representative solution, the energy consumption coefficient for the UAV swarm based on the NSBKA algorithm is 3321.64. This result is lower than that of MOSSA by 79.18, MOGWO by 75.43, MOSPO by 110.54, and MOGNDO by 99.52, respectively. It can also be concluded from Table 8 that the energy consumption of the solution with better safety will increase, while the safety of the solution with better energy savings will decrease.

5.2.2. Experiment 2

The number of flight points for each UAV is set to 21, and the most representative solution is selected from the Pareto solutions optimized by the algorithm. That is, the path with the least energy consumption and the path with high safety, as shown in Figure 10 and Table 9.
The simulation results, illustrated in Figure 10 and Table 9, show that the NSBKA-derived solution effectively optimizes the mathematical model for multi-UAV collaborative path planning. Figure 9 further reveals that the paths designed with safety as a priority consistently maintain a secure distance from obstacles. This design feature significantly reduces the likelihood of drones requiring sudden evasive maneuvers during practical operations, thereby bolstering overall flight safety. Conversely, the energy-conserving paths are designed to minimize travel distance while maintaining obstacle avoidance. As a result, all five UAVs employ close-proximity obstacle avoidance to achieve shorter flight paths. The bold numbers in Table 9 are the best of the comparison objects. Based on the data in Table 9, the CPU running time for the NSBKA algorithm is 1894.02 s. This result is 195.93 s slower than that of MOGND, but it is significantly faster than MOSSA by 116.11 seconds, MOGWO by 522.49 s, and MOSPO by 275.76 s, respectively. If the path with the highest safety level from the obtained Pareto solution set is chosen as the representative solution, the safety coefficient for the UAV swarm using the NSBKA algorithm is 9.53. While this result is 1.03 higher than MOSSA and 1.06 higher than MOSPO, it is 0.37 lower than MOGWO and 0.41 lower than MOGNDO. If the path with the lowest energy consumption from the obtained Pareto solution set is selected as the representative solution, the energy consumption coefficient for the UAV swarm based on the NSBKA algorithm is 4909.34. Compared to other methods, the result is 4.71 lower than MOSSA, 110.85 lower than MOSPO, and 71.22 lower than MOGNDO, but it is 94.72 higher than MOGWO. It can also be concluded from Table 9 that the energy consumption of the solution with better safety will increase, while the safety of the solution with better energy savings will decrease. This conclusion is the same as when the three UAVs were planned.
In terms of obtaining multiple representative types of solutions (e.g., safety and energy efficiency) and CPU processing time, the NSBKA method is able to achieve near-optimal solutions with notable benchmarks, though it may not excel in specific metrics. Nevertheless, it consistently delivers near-optimal solutions with stable performance. This indicates that NSBKA can provide a reliable set of solutions in practical applications, particularly in scenarios where high-quality solutions are required but absolute optimality is not essential. NSBKA exhibits strong robustness across tasks of varying scales and complexities. Whether planning for three or five UAVs, NSBKA is capable of delivering relatively stable solutions without significant performance degradation as task complexity increases. Furthermore, the framework of NSBKA is relatively flexible and offers substantial room for improvement. It can be easily integrated with other optimization techniques or enhanced, such as by incorporating additional local search strategies or parallel computing, to further boost its performance.

6. Conclusions

In this study, we have established a mathematical model of multi-UAV cooperative path planning for delivering tasks in urban logistics scenarios and introduced the NSBKA algorithm to solve the model. To enhance the BKA algorithm, we have incorporated non-dominated sorting, crowding-distance calculation, and external archiving, transforming it into an effective approach for multi-objective optimization. This upgrade aims to boost the algorithm’s optimization speed and search efficiency while maintaining solution diversity and convergence.
We assessed the NSBKA’s performance against MOSSA, MOGWO, MOSPO, and MOGNDO on ZDT, DTLZ, and CEC2009 multi-objective benchmarks under equitable conditions. The comparison and statistical results showed that the NSBKA achieved the best results on 22 test functions. In terms of average IGD values, the NSBKA performed better in 13 out of 22 functions compared to the aggregate performance of the other four algorithms. Regarding the average HV values, the NSBKA scored higher in 13 functions compared to the collective results of the other four algorithms. Then, these five algorithms were used to solve the path-planning problem for the UAVs. The experiments showed that all algorithms could find the path of the UAV, which shows the effectiveness of the metaheuristic algorithm. Regardless of whether planning for three or five drones, the NSBKA completed path planning with shorter CPU times compared to MOSSA, MOGWO, and MOSPO. Furthermore, the representative solutions derived from the NSBKA for both the three- and five-drone scenarios exhibited advantages over at least two of the other algorithms.
While this study provides an innovative method for multi-UAV cooperative path planning, certain limitations still exist. As the number of UAVs increases, the runtime of the algorithm in overall path planning increases, which poses a challenge to the planning of a massive number of drones. Future studies could develop more suitable mathematical models to address such challenges, and the NSBKA could also be refined to improve its capability to solve multi-objective optimization problems.

Author Contributions

Conceptualization, L.L. and Y.L.; methodology, X.L.; validation, X.L. and F.W.; formal analysis, X.L.; investigation, X.L. and L.L.; data curation, X.L.; writing—original draft preparation, X.L.; writing—review and editing, L.L., Y.L. and F.W.; visualization, X.L.; supervision, L.L.; funding acquisition, L.L. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Fund of Fudan University under JIH2126018Y.

Data Availability Statement

The datasets used in this study are not publicly available due to confidentiality restrictions. Researchers are welcome to contact the corresponding author for further inquiries, and partial datasets or guidance may be provided upon reasonable request.

Acknowledgments

We thank Haitao Zhang for the fruitful discussion and help in the model development.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Cheng, G.Y.; Song, X.X.; Lyu, Z.H.; Xu, J. Networked ISAC for Low-Altitude Economy: Transmit Beamforming and UAV Trajectory Design. In Proceedings of the IEEE/CIC International Conference on Communications in China (ICCC), Hangzhou, China, 7–9 August 2024. [Google Scholar]
  2. Huang, C.Q.; Fang, S.F.; Wu, H.; Wang, Y.; Yang, Y.C. Low-altitude intelligent transportation: System architecture, infrastructure, and key technologies. J. Ind. Inf. Integr. 2024, 42, 100694. [Google Scholar] [CrossRef]
  3. Van, C.L.; Cao, C.X.; Nguyen, A.N.; Pham, C.V.; Nguyen, L.Q. Building 3D CityGML models of mining industrial structures using integrated UAV and TLS point clouds. Int. J. Coal Sci. Technol. 2023, 10, 69. [Google Scholar] [CrossRef]
  4. Ju, C.; Son, H.I. Multiple UAV Systems for Agricultural Applications: Control, Implementation, and Evaluation. Electronics 2018, 7, 162. [Google Scholar] [CrossRef]
  5. Kotlinski, M.; Calkowska, J.K. U-Space and UTM Deployment as an Opportunity for More Complex UAV Operations Including UAV Medical Transport. J. Intell. Robot. Syst. 2022, 106, 12. [Google Scholar] [CrossRef] [PubMed]
  6. Li, K.; Yan, X.X.; Han, Y. Multi-mechanism swarm optimization for multi-UAV task assignment and path planning in transmission line inspection under multi-wind field. Appl. Soft Comput. 2024, 150, 111033. [Google Scholar] [CrossRef]
  7. Qadir, Z.; Ullah, F.; Munawar, H.S.; Al-Turjman, F. Addressing disasters in smart cities through UAVs path planning and 5G communications: A systematic review. Comput. Commun. 2021, 168, 114–135. [Google Scholar] [CrossRef]
  8. Merei, A.; McHeick, H.; Ghaddar, A. Survey on Path Planning for UAVs in Healthcare Missions. J. Med. Syst. 2023, 47, 79. [Google Scholar] [CrossRef]
  9. Xu, Y.; Xie, Y.; Yu, R.; Hou, L.; Wang, K.; Xu, L. Integrated perception-communication-logistics multi-objective oriented path planning for emergency UAVs. J. Commun. 2024, 45, 1–12. [Google Scholar]
  10. Gao, C.X.; Wang, X.Y.; Chen, X.; Chen, B.M. A hierarchical multi-UAV cooperative framework for infrastructure inspection and reconstruction. Control Theory Technol. 2024, 22, 394–405. [Google Scholar] [CrossRef]
  11. Xu, Y.H.; Wei, Y.R.; Wang, D.; Jiang, K.Y.; Deng, H.B. Multi-UAV Path Planning in GPS and Communication Denial Environment. Sensors 2023, 23, 2997. [Google Scholar] [CrossRef]
  12. Coutinho, W.P.; Battarra, M.; Fliege, J. The unmanned aerial vehicle routing and trajectory optimisation problem, a taxonomic review. Comput. Ind. Eng. 2018, 120, 116–128. [Google Scholar] [CrossRef]
  13. Xu, X.J.; Xie, C.Y.; Luo, Z.F.; Zhang, C.F.; Zhang, T. A multi-objective evolutionary algorithm based on dimension exploration and discrepancy evolution for UAV path planning problem. Inf. Sci. 2024, 657, 119977. [Google Scholar] [CrossRef]
  14. Peng, C.D.; Huang, X.M.; Wu, Y.; Kang, J.W. Constrained Multi-Objective Optimization for UAV-Enabled Mobile Edge Computing: Offloading Optimization and Path Planning. IEEE Wirel. Commun. Lett. 2022, 11, 861–865. [Google Scholar] [CrossRef]
  15. Güven, I.; Yanmaz, E. Multi-objective path planning for multi-UAV connectivity and area coverage. Ad. Hoc. Netw. 2024, 160, 103520. [Google Scholar] [CrossRef]
  16. Diao, Q.F.; Zhang, J.F.; Liu, M.; Yang, J.X. A Disaster Relief UAV Path Planning Based on APF-IRRT* Fusion Algorithm. Drones 2023, 7, 323. [Google Scholar] [CrossRef]
  17. Wang, S.; Li, A. Multi-adjacent-vertexes and Multi-shortest-paths Problem of Dijkstra Algorithm. Comput. Sci. 2014, 41, 217–224. [Google Scholar]
  18. Hong, Z.H.; Sun, P.F.; Tong, X.H.; Pan, H.Y.; Zhou, R.Y.; Zhang, Y.; Han, Y.L.; Wang, J.; Yang, S.H.; Xu, L.J. Improved A-Star Algorithm for Long-Distance Off-Road Path Planning Using Terrain Data Map. Isprs Int. J. Geo-Inf. 2021, 10, 785. [Google Scholar] [CrossRef]
  19. Zhang, Z.; Wu, J.; Dai, J.Y.; He, C. A Novel Real-Time Penetration Path Planning Algorithm for Stealth UAV in 3D Complex Dynamic Environment. IEEE Access 2020, 8, 122757–122771. [Google Scholar] [CrossRef]
  20. Ammar, A.; Bennaceur, H.; Châari, I.; Koubâa, A.; Alajlan, M. Relaxed Dijkstra and A* with linear complexity for robot path planning problems in large-scale grid environments. Soft Comput. 2016, 20, 4149–4171. [Google Scholar] [CrossRef]
  21. Zhang, J.C.; An, Y.Q.; Cao, J.N.; Ouyang, S.B.; Wang, L. UAV Trajectory Planning for Complex Open Storage Environments Based on an Improved RRT Algorithm. IEEE Access 2023, 11, 23189–23204. [Google Scholar] [CrossRef]
  22. Guo, Y.C.; Liu, X.X.; Liu, X.H.; Yang, Y.; Zhang, W.G. FC-RRT*: An Improved Path Planning Algorithm for UAV in 3D Complex Environment. Isprs Int. J. Geo-Inf. 2022, 11, 112. [Google Scholar] [CrossRef]
  23. Zhang, T.; Lu, Y.; Zhang, L.; Lu, Y. UAV Path Planning Based on Improved Voronoi Diagram and Dynamic Weights A~* Algorithm. Fire Control Command Control 2015, 40, 156–160. [Google Scholar]
  24. Cai, X.; Hu, Z.; Zhang, Z.; Wang, Q.; Cui, Z.; Zhang, W. Multi-UAV coordinated path planning based on many-objective optimization. Sci. Sin. Informationis 2021, 51, 985–996. [Google Scholar] [CrossRef]
  25. Hooshyar, M.; Huang, Y.M. Meta-heuristic Algorithms in UAV Path Planning Optimization: A Systematic Review (2018–2022). Drones 2023, 7, 687. [Google Scholar] [CrossRef]
  26. Ge, F.W.; Li, K.; Han, Y.; Xu, W.S.; Wang, Y.A. Path planning of UAV for oilfield inspections in a three-dimensional dynamic environment with moving obstacles based on an improved pigeon-inspired optimization algorithm. Appl. Intell. 2020, 50, 2800–2817. [Google Scholar] [CrossRef]
  27. Wu, Y.; Niu, K.; Li, L.; Chen, Z. Formation flight control of UAV based on 3D-APF and constraint dynamics. Syst. Eng. Electron. 2018, 40, 1104–1108. [Google Scholar]
  28. Aljalaud, F.; Kurdi, H.; Youcef-Toumi, K. Autonomous Multi-UAV Path Planning in Pipe Inspection Missions Based on Booby Behavior. Mathematics 2023, 11, 2092. [Google Scholar] [CrossRef]
  29. Zhang, J.W.; Zhu, X.J.; Li, J. Intelligent Path Planning with an Improved Sparrow Search Algorithm for Workshop UAV Inspection. Sensors 2024, 24, 1104. [Google Scholar] [CrossRef]
  30. Ji, X.; Meng, X.J.; Wang, A.W.; Hua, Q.Y.; Wang, F.W.; Chen, R.; Zhang, J.; Fang, D.Y. E2PP: An Energy-Efficient Path Planning Method for UAV-Assisted Data Collection. Secur. Commun. Netw. 2020, 2020, 1–13. [Google Scholar] [CrossRef]
  31. Xu, C.; Xu, M.; Yin, C.J. Optimized multi-UAV cooperative path planning under the complex confrontation environment. Comput. Commun. 2020, 162, 196–203. [Google Scholar] [CrossRef]
  32. Yang, L.Q.; Guo, J.; Liu, Y.B. THREE-DIMENSIONAL UAV COOPERATIVE PATH PLANNING BASED ON THE MP-CGWO ALGORITHM. Int. J. Innov. Comput. Inf. Control 2020, 16, 991–1006. [Google Scholar] [CrossRef]
  33. Wang, X.; Pan, J.S.; Yang, Q.Y.; Kong, L.P.; Snásel, V.; Chu, S.C. Modified Mayfly Algorithm for UAV Path Planning. Drones 2022, 6, 134. [Google Scholar] [CrossRef]
  34. Deng, M.Y.; Yang, Q.Q.; Peng, Y. A Real-Time Path Planning Method for Urban Low-Altitude Logistics UAVs. Sensors 2023, 23, 7472. [Google Scholar] [CrossRef]
  35. Zhou, D.; Wang, P.; Li, X.; Zhang, K. Cooperative path planning of multi-UAV based on multi-objective optimization algorithm. Syst. Eng. Electron. 2017, 39, 782–787. [Google Scholar]
  36. Tan, L.; Shi, J.Q.; Gao, J.; Wang, H.Y.; Zhang, H.T.; Zhang, Y. Multi-UAV path planning based on IB-ABC with restricted planned arrival sequence. Robotica 2023, 41, 1244–1257. [Google Scholar] [CrossRef]
  37. Li, W.H.; Zhang, T.; Wang, R.; Huang, S.J.; Liang, J. Multimodal multi-objective optimization: Comparative study of the state-of-the-art. Swarm Evol. Comput. 2023, 77, 101253. [Google Scholar] [CrossRef]
  38. Wang, J.; Wang, W.C.; Hu, X.X.; Qiu, L.; Zang, H.F. Black-winged kite algorithm: A nature-inspired meta-heuristic for solving benchmark functions and engineering problems. Artif. Intell. Rev. 2024, 57, 98. [Google Scholar] [CrossRef]
  39. Wu, Y.; Nie, M.T.; Ma, X.L.; Guo, Y.C.; Liu, X.X. Co-Evolutionary Algorithm-Based Multi-Unmanned Aerial Vehicle Cooperative Path Planning. Drones 2023, 7, 606. [Google Scholar] [CrossRef]
  40. Zhang, J.; Cui, Y.N.; Ren, J. Dynamic Mission Planning Algorithm for UAV Formation in Battlefield Environment. IEEE Trans. Aerosp. Electron. Syst. 2023, 59, 3750–3765. [Google Scholar] [CrossRef]
  41. Tian, Y.; Wang, H.D.; Zhang, X.Y.; Jin, Y.C. Effectiveness and efficiency of non-dominated sorting for evolutionary multi- and many-objective optimization. Complex Intell. Syst. 2017, 3, 247–263. [Google Scholar] [CrossRef]
  42. Niu, B.; Liu, J.; Tan, L.J. Multi-swarm cooperative multi-objective bacterial foraging optimisation. Int. J. Bio-Inspired Comput. 2019, 13, 21–31. [Google Scholar] [CrossRef]
  43. Deb, K.; Pratap, A.; Agarwal, S.; Meyarivan, T. A fast and elitist multiobjective genetic algorithm: NSGA-II. IEEE Trans. Evol. Comput. 2002, 6, 182–197. [Google Scholar] [CrossRef]
  44. Mirjalili, S.; Saremi, S.; Mirjalili, S.M.; Coelho, L.D. Multi-objective grey wolf optimizer: A novel algorithm for multi-criterion optimization. Expert Syst. Appl. 2016, 47, 106–119. [Google Scholar] [CrossRef]
  45. Huband, S.; Hingston, P.; Barone, L.; While, L. A review of multiobjective test problems and a scalable test problem toolkit. IEEE Trans. Evol. Comput. 2006, 10, 477–506. [Google Scholar] [CrossRef]
  46. Liu, T.Y.; Jiao, L.C.; Ma, W.P.; Ma, J.J.; Shang, R.H. A new quantum-behaved particle swarm optimization based on cultural evolution mechanism for multiobjective problems. Knowl.-Based Syst. 2016, 101, 90–99. [Google Scholar] [CrossRef]
  47. Zhang, Q.; Zhou, A.; Zhao, S.-Z.; Suganthan, P.N.; Liu, W.; Tiwari, S. Multiobjective Optimization Test Instances for the CEC 2009 Special Session and Competition; Technical Report CES-887; University of Essex and Nanyang Technological University: Singapore, 2009. [Google Scholar]
  48. Cui, Y.Y.; Meng, X.; Qiao, J.F. A multi-objective particle swarm optimization algorithm based on two-archive mechanism. Appl. Soft Comput. 2022, 119, 108532. [Google Scholar] [CrossRef]
  49. Wang, L.; Pan, X.; Shen, X.; Zhao, P.; Qiu, Q. Balancing convergence and diversity in resource allocation strategy for decomposition-based multi-objective evolutionary algorithm. Appl. Soft Comput. 2021, 100, 106968. [Google Scholar] [CrossRef]
  50. Chen, N.; Chen, W.N.; Gong, Y.J.; Zhan, Z.H.; Zhang, J.; Li, Y.; Tan, Y.S. An Evolutionary Algorithm with Double-Level Archives for Multiobjective Optimization. IEEE Trans. Cybern. 2015, 45, 1851–1863. [Google Scholar] [CrossRef]
  51. Wu, W.; Tian, L.; Wang, Z.; Zhang, Y.; Wu, J.; Gui, F. Novel multi-objective sparrow optimization algorithm with improved non-dominated sorting. Appl. Res. Comput. 2022, 39, 2012–2019. [Google Scholar]
  52. Khodadadi, N.; Abualigah, L.; Mirjalili, S. Multi-objective Stochastic Paint Optimizer (MOSPO). Neural Comput. Appl. 2022, 34, 18035–18058. [Google Scholar] [CrossRef]
  53. Khodadadi, N.; Khodadadi, E.; Abdollahzadeh, B.; Ei-Kenawy, E.S.M.; Mardanpour, P.; Zhao, W.G.; Gharehchopogh, F.S.; Mirjalili, S. Multi-objective generalized normal distribution optimization: A novel algorithm for multi-objective problems. Clust. Comput.-J. Netw. Softw. Tools Appl. 2024, 27, 10589–10631. [Google Scholar] [CrossRef]
Figure 1. Distribution of solutions in a bi-objective optimization problem.
Figure 1. Distribution of solutions in a bi-objective optimization problem.
Drones 09 00118 g001
Figure 2. Schematic view of the inversed generational distance (IGD) metric.
Figure 2. Schematic view of the inversed generational distance (IGD) metric.
Drones 09 00118 g002
Figure 3. Schematic view of the hyper-volume (HV) metric.
Figure 3. Schematic view of the hyper-volume (HV) metric.
Drones 09 00118 g003
Figure 4. The Pareto optimal front obtained by the NSBKA, MOSSA, and MOGWO for the UF1, UF4, UF6, and UF8 benchmark problems.
Figure 4. The Pareto optimal front obtained by the NSBKA, MOSSA, and MOGWO for the UF1, UF4, UF6, and UF8 benchmark problems.
Drones 09 00118 g004
Figure 5. The Pareto optimal front obtained by the NSBKA, MOSPO, and MOGNDO for the UF1, UF4, UF6, and UF8 benchmark problems.
Figure 5. The Pareto optimal front obtained by the NSBKA, MOSPO, and MOGNDO for the UF1, UF4, UF6, and UF8 benchmark problems.
Drones 09 00118 g005
Figure 6. The 3D models of the urban environment. The environmental model is constructed based on the typical urban buildings in Shanghai.
Figure 6. The 3D models of the urban environment. The environmental model is constructed based on the typical urban buildings in Shanghai.
Drones 09 00118 g006
Figure 7. Flowchart of the proposed algorithm for path optimization.
Figure 7. Flowchart of the proposed algorithm for path optimization.
Drones 09 00118 g007
Figure 8. NSBKA Pareto solution set for paths.
Figure 8. NSBKA Pareto solution set for paths.
Drones 09 00118 g008
Figure 9. Five Algorithms Visualized: Solution for Three UAVs. (a,b) and (c,d) are NSBKA solutions representing better safety and energy consumption, respectively. (e,f) and (g,h) are MOSSA solutions representing safety and energy consumption, respectively. (i,j) and (k,l) are MOGWO solutions representing safety and energy consumption, respectively. (m,n) and (o,p) are MOSPO solutions representing safety and energy consumption, respectively. (q,r) and (s,t) are MOGNDO solutions representing safety and energy consumption, respectively. (Green line frame: Algorithm type; Blue line frame: Solutions for Energy Consumption; Red line frame: Solutions for Safety; Cycle: Start; Star: End).
Figure 9. Five Algorithms Visualized: Solution for Three UAVs. (a,b) and (c,d) are NSBKA solutions representing better safety and energy consumption, respectively. (e,f) and (g,h) are MOSSA solutions representing safety and energy consumption, respectively. (i,j) and (k,l) are MOGWO solutions representing safety and energy consumption, respectively. (m,n) and (o,p) are MOSPO solutions representing safety and energy consumption, respectively. (q,r) and (s,t) are MOGNDO solutions representing safety and energy consumption, respectively. (Green line frame: Algorithm type; Blue line frame: Solutions for Energy Consumption; Red line frame: Solutions for Safety; Cycle: Start; Star: End).
Drones 09 00118 g009
Figure 10. Five Algorithms Visualized: solution for five UAVs. The subfigures are explained in the same way as in Figure 9.
Figure 10. Five Algorithms Visualized: solution for five UAVs. The subfigures are explained in the same way as in Figure 9.
Drones 09 00118 g010
Table 1. Different features and settings for the selected test functions.
Table 1. Different features and settings for the selected test functions.
ProblemDimension of VariablesDimension of ObjectivesFeatures of PFSample Size in PF
ZDT1102Convex1000
ZDT2102Concave1000
ZDT3102Discontinuous1000
ZDT4102Convex1000
ZDT6102Concave, Non-uniform1000
DTLZ173Continues990
DTLZ2123Concave, Continues990
DTLZ3123Concave990
DTLZ4123Concave, Non-uniform990
DTLZ5123Concave1000
DTLZ6123Concave1000
DTLZ7223Disconnected, Mixed1024
UF1102Convex1000
UF2102Convex1000
UF3102Convex1000
UF4102Concave1000
UF5102Discontinuous21
UF6102Discontinuous501
UF7102Linear1000
UF8103Concave990
UF9103Mixed522
UF10103Concave990
Table 2. Results of IGD metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Table 2. Results of IGD metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Test ProblemIGD MetricMOSSAMOGWOMOSPOMOGNDONSBKA
ZDT1Mean
std
2.226 × 10−3(−)
6.328 × 10−5
4.518 × 10−3(−)
8.161 × 10−4
6.725 × 10−3(−)
1.959 × 10−4
1.692 × 10−2(−)
3.656 × 10−3
2.087 × 10−3
2.730 × 10−5
ZDT2Mean
std
2.307 × 10−3(−)
6.440 × 10−5
5.109 × 10−3(−)
9.231 × 10−4
7.072 × 10−3(−)
1.102 × 10−4
1.960 × 10−2(−)
1.951 × 10−3
2.058 × 10−3
7.820 × 10−5
ZDT3Mean
std
2.498 × 10−3(−)
6.060 × 10−5
5.046 × 10−3(−)
7.153 × 10−4
8.425 × 10−3(−)
8.943 × 10−4
1.092 × 10−2(−)
3.902 × 10−3
2.292 × 10−3
1.894 × 10−4
ZDT4Mean
std
2.192 × 10−3(−)
4.342 × 10−5
1.096 × 100(−)
2.437 × 100
7.204 × 10−3(−)
2.013 × 10−4
4.358 × 100(−)
1.658 × 100
2.083 × 10−3
1.108 × 10−4
ZDT6Mean
std
1.814 × 10−3(−)
7.277 × 10−5
3.459 × 10−3(−)
5.349 × 10−4
1.153 × 10−2(−)
5.579 × 10−3
3.457 × 10−1(−)
7.963 × 10−2
1.691 × 10−3
9.870 × 10−5
DTLZ1Mean
std
2.702 × 10−2(+)
8.902 × 10−3
8.955 × 100(−)
3.484 × 100
1.036 × 101(−)
3.756 × 100
1.403 × 101(−)
2.439 × 100
5.586 × 10−2
2.381 × 10−2
DTLZ2Mean
std
5.965 × 10−2(+)
2.518 × 10−3
1.124 × 10−1(−)
1.234 × 10−2
1.091 × 10−1(−)
3.676 × 10−3
1.248 × 10−1(−)
2.961 × 10−2
6.661 × 10−2
4.167 × 10−3
DTLZ3Mean
std
1.577 × 10−1(+)
1.330 × 10−1
1.802 × 102(−)
2.572 × 101
1.759 × 102(−)
1.477 × 101
2.139 × 102(−)
1.152 × 101
2.161 × 10−1
2.058 × 10−1
DTLZ4Mean
std
4.936 × 10−2(+)
1.772 × 10−3
8.608 × 10−2(−)
8.541 × 10−2
1.975 × 10−1(−)
5.000 × 10−3
2.665 × 10−1(−)
2.082 × 10−2
5.944 × 10−2
3.821 × 10−2
DTLZ5Mean
std
2.994 × 10−3(−)
1.467 × 10−4
1.196 × 10−2(−)
1.655 × 10−3
5.464 × 10−2(−)
6.043 × 10−3
8.049 × 10−3(−)
5.991 × 10−4
2.591 × 10−3
1.059 × 10−4
DTLZ6Mean
std
2.562 × 10−3(−)
8.612 × 10−5
4.069 × 10−3(−)
4.003 × 10−4
2.632 × 10−2(−)
1.617 × 10−3
6.633 × 10−1(−)
4.852 × 10−2
2.250 × 10−3
7.815 × 10−5
DTLZ7Mean
std
6.241 × 10−2(+)
2.523 × 10−2
1.435 × 10−1(+)
2.234 × 10−1
2.611 × 10−1(+)
1.241 × 10−1
1.284 × 10−1(+)
8.856 × 10−3
4.359 × 10−1
5.313 × 10−1
UF1Mean
std
6.883 × 10−2(−)
9.406 × 10−3
8.095 × 10−2(−)
1.366 × 10−2
7.321 × 10−2(−)
2.680 × 10−3
9.093 × 10−2(−)
1.614 × 10−2
3.051 × 10−2
5.083 × 10−3
UF2Mean
std
4.440 × 10−2(−)
6.084 × 10−3
3.992 × 10−2(−)
7.258 × 10−3
3.848 × 10−2(−)
1.395 × 10−3
4.028 × 10−2(−)
4.784 × 10−3
1.861 × 10−2
6.154 × 10−3
UF3Mean
std
3.790 × 10−1(−)
1.694 × 10−2
3.914 × 10−1(−)
7.032 × 10−2
3.633 × 10−1(+)
1.058 × 10−2
3.431 × 10−1(+)
1.192 × 10−1
3.644 × 10−1
5.377 × 10−3
UF4Mean
std
8.718 × 10−1(−)
9.023 × 10−4
6.036 × 10−2(−)
7.211 × 10−3
7.941 × 10−2(−)
1.012 × 10−3
5.247 × 10−2(−)
4.552 × 10−3
4.150 × 10−2
5.317 × 10−3
UF5Mean
std
4.645 × 10−1(+)
1.211 × 10−1
7.064 × 10−1(−)
2.217 × 10−1
3.513 × 10−1(+)
4.813 × 10−2
1.098 × 100(−)
1.000 × 10−1
4.857 × 10−1
1.173 × 10−1
UF6Mean
std
5.131 × 10−1(−)
1.039 × 10−1
7.751 × 10−1(−)
2.077 × 10−1
5.960 × 10−1(−)
2.894 × 10−2
1.248 × 100(−)
8.605 × 10−2
4.767 × 10−1
1.132 × 10−1
UF7Mean
std
3.659 × 10−2(−)
4.734 × 10−3
7.740 × 10−2(−)
4.152 × 10−2
5.989 × 10−2(−)
4.014 × 10−3
1.125 × 10−1(−)
1.833 × 10−2
2.660 × 10−2
1.226 × 10−2
UF8Mean
std
2.675 × 10−1(−)
1.825 × 10−2
2.506 × 10−1(−)
6.762 × 10−2
1.234 × 100(−)
1.262 × 10−1
1.748 × 10−1(−)
1.072 × 10−2
1.253 × 10−1
1.655 × 10−2
UF9Mean
Std
1.298 × 10−1(+)
1.958 × 10−2
4.557 × 10−1(−)
5.472 × 10−1
2.352 × 10−1(−)
2.979 × 10−2
2.334 × 10−1(−)
1.316 × 10−1
1.755 × 10−1
3.832 × 10−2
UF10Mean
std
2.549 × 10−1(+)
1.667 × 10−1
1.916 × 100(−)
4.009 × 10−1
7.638 × 10−1(−)
1.098 × 10−2
7.734 × 10−1(−)
3.102 × 10−2
3.530 × 10−1
1.127 × 10−1
+/−/=
Best/All
-8/14/0
8/22
1/21/0
1/22
3/19/0
3/22
2/20/0
2/22
-
13/22
Table 3. Results of HV metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Table 3. Results of HV metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Test ProblemHV MetricMOSSAMOGWOMOSPOMOGNDONSBKA
ZDT1Mean
std
7.222 × 10−1(−)
5.060 × 10−5
7.191 × 10−1(−)
9.644 × 10−4
7.163 × 10−1(−)
2.826 × 10−4
7.010 × 10−1(−)
4.866 × 10−3
7.223 × 10−1
8.856 × 10−5
ZDT2Mean
std
4.468 × 10−1(−)
3.711 × 10−5
4.416 × 10−1(−)
1.724 × 10−3
4.416 × 10−1(−)
1.461 × 10−3
4.255 × 10−1(−)
2.048 × 10−2
4.470 × 10−1
1.066 × 10−4
ZDT3Mean
std
6.005 × 10−1(−)
4.098 × 10−5
5.995 × 10−1(−)
1.651 × 10−3
5.975 × 10−1(−)
1.843 × 10−3
5.979 × 10−1(−)
5.251 × 10−3
6.005 × 10−1
6.044 × 10−5
ZDT4Mean
std
7.223 × 10−1(−)
4.554 × 10−5
5.741 × 10−1(−)
3.210 × 10−1
7.169 × 10−1(−)
1.947 × 10−3
0.000 × 100(−)
0.000 × 100
7.223 × 10−1
1.047 × 10−4
ZDT6Mean
std
3.901 × 10−1(−)
9.325 × 10−5
3.869 × 10−1(−)
2.643 × 10−3
3.804 × 10−1(−)
5.078 × 10−3
2.103 × 10−1(−)
2.624 × 10−2
3.902 × 10−1
1.163 × 10−4
DTLZ1Mean
std
8.151 × 10−1(+)
2.329 × 10−2
0.000 × 100(−)
0.000 × 100
0.000 × 100(−)
0.000 × 100
0.000 × 100(−)
0.000 × 100
7.264 × 10−1
7.982 × 10−2
DTLZ2Mean
std
5.308 × 10−1(+)
5.021 × 10−3
4.466 × 10−1(−)
1.525 × 10−2
4.491 × 10−1(−)
4.189 × 10−3
4.420 × 10−1(−)
3.729 × 10−2
5.286 × 10−1
4.906 × 10−3
DTLZ3Mean
std
4.492 × 10−1(+)
1.027 × 10−1
0.000 × 100(−)
0.000 × 100
0.000 × 100(−)
0.000 × 100
0.000 × 100(−)
0.000 × 100
3.872 × 10−1
1.652 × 10−1
DTLZ4Mean
std
5.545 × 10−1(+)
4.142 × 10−3
5.211 × 10−1(−)
6.889 × 10−2
3.839 × 10−1(−)
4.758 × 10−3
3.344 × 10−1(−)
3.779 × 10−2
5.485 × 10−1
3.032 × 10−2
DTLZ5Mean
std
5.016 × 10−1(+)
7.374 × 10−1
1.935 × 10−1(−)
3.326 × 10−3
1.452 × 10−1(−)
5.615 × 10−3
1.964 × 10−1(−)
8.787 × 10−4
2.007 × 10−1
1.314 × 10−4
DTLZ6Mean
std
2.013 × 10−1(−)
2.663 × 10−5
1.998 × 10−1(−)
8.263 × 10−4
1.884 × 10−1(−)
8.767 × 10−4
5.299 × 10−2(−)
9.178 × 10−2
2.014 × 10−1
3.615 × 10−5
DTLZ7Mean
std
9.091 × 10−2(−)
0.000 × 100
2.679 × 10−1(+)
2.550 × 10−2
1.850 × 10−1(−)
4.305 × 10−2
2.379 × 10−1(+)
6.678 × 10−3
2.198 × 10−1
8.052 × 10−2
UF1Mean
std
6.249 × 10−1(−)
1.108 × 10−2
6.039 × 10−1(−)
2.339 × 10−2
6.102 × 10−1(−)
8.521 × 10−4
5.783 × 10−1(−)
2.800 × 10−2
1.900 × 100
2.719 × 100
UF2Mean
std
6.706 × 10−1(−)
6.248 × 10−3
6.739 × 10−1(−)
9.297 × 10−3
6.755 × 10−1(−)
7.854 × 10−4
6.737 × 10−1(−)
7.245 × 10−3
7.012 × 10−1
8.176 × 10−3
UF3Mean
std
1.870 × 10−1(+)
1.110 × 10−2
2.323 × 10−1(+)
5.034 × 10−2
2.215 × 10−1(+)
1.482 × 10−2
2.783 × 10−1(+)
1.249 × 10−1
1.802 × 10−1
3.002 × 10−3
UF4Mean
std
3.768 × 10−1(−)
1.115 × 10−3
3.623 × 10−1(−)
7.499 × 10−3
1.453 × 10−1(−)
2.132 × 10−3
3.732 × 10−1(−)
3.768 × 10−3
3.901 × 10−1
8.037 × 10−3
UF5Mean
std
8.106 × 10−2(+)
4.729 × 10−2
3.420 × 10−2(−)
6.594 × 10−2
6.743 × 10−2(+)
1.701 × 10−2
0.000 × 100(−)
0.000 × 100
4.870 × 10−2
4.492 × 10−2
UF6Mean
std
1.076 × 10−2(−)
1.500 × 10−2
8.682 × 10−3(−)
2.107 × 10−2
3.638 × 10−3(−)
2.995 × 10−3
0.000 × 100(−)
0.000 × 100
8.447 × 10−2
6.252 × 10−2
UF7Mean
std
5.319 × 10−1(−)
6.393 × 10−3
4.717 × 10−1(−)
5.361 × 10−2
4.965 × 10−1(−)
2.757 × 10−3
4.156 × 10−1(−)
2.924 × 10−2
5.471 × 10−1
1.806 × 10−2
UF8Mean
std
3.256 × 10−1(−)
3.210 × 10−2
2.627 × 10−1(−)
5.815 × 10−2
9.416 × 10−1(+)
1.186 × 10−3
3.185 × 10−1(−)
4.249 × 10−2
4.638 × 10−1
3.373 × 10−2
UF9Mean
std
6.507 × 10−1(+)
2.384 × 10−2
4.231 × 10−1(−)
8.086 × 10−2
2.691 × 10−1(−)
2.255 × 10−2
5.316 × 10−1(−)
1.132 × 10−1
5.930 × 10−1
5.372 × 10−2
UF10Mean
std
2.375 × 10−1(−)
3.469 × 10−2
0.000 × 100(−)
0.000 × 100
5.479 × 10−1(+)
7.714 × 10−4
3.602 × 10−2(−)
3.561 × 10−2
3.335 × 10−1
1.639 × 10−2
+/−/=
Best/All
-8/14/0
8/22
2/20/0
2/22
4/18/0
4/22
2/20/0
2/22
-
12/22
Table 4. Results of CPU runtime (s) metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Table 4. Results of CPU runtime (s) metric of different multi-objective algorithms on ZDT, DTLZ, and UF problems.
Test ProblemMOSSAMOGWOMOSPOMOGNDONSBKA
ZDT122.903276.68163.63019.9679.778
ZDT220.522283.77753.03523.9727.393
ZDT325.893191.58848.05024.91027.827
ZDT423.799211.55436.34240.61418.919
ZDT624.179208.01747.56415.9246.611
DTLZ130.58132.28661.73833.07971.357
DTLZ29.087227.44586.68370.66317.773
DTLZ332.56736.62185.75455.92379.326
DTLZ410.812125.06171.94421.47918.051
DTLZ512.063135.80080.10955.69627.667
DTLZ626.358297.77458.70421.7989.031
DTLZ726.604212.11057.27035.11416.001
UF145.65328.80353.27818.20881.651
UF230.50782.24269.72430.17749.404
UF332.87717.76069.05564.51863.076
UF416.23986.085113.49938.36729.600
UF551.50716.47549.09017.163108.676
UF652.80817.82251.00216.457108.967
UF744.30733.43952.84616.66272.203
UF829.180110.54667.87628.49259.556
UF936.80587.08474.43728.73258.940
UF1037.15946.34152.30919.52435.824
Table 5. The position distribution and size of all obstacles.
Table 5. The position distribution and size of all obstacles.
Number of ObstaclesPositionLength (m)Width (m)Altitude (m)
1(230, 100, 0)1109023
1(0, 580, 0)15016030
3(585, 520, 0)8010048
4(300, 520, 0)16010030
5(810, 100, 0)8015038
6(500, 0, 0)1504028
7(50, 300, 0)601309
8(600, 230, 0)1008024
9(500, 720, 0)1109014
10(320, 330, 0)1206014
11(840, 330, 0)12010014
Table 6. Flight parameters for UAV performance constraints.
Table 6. Flight parameters for UAV performance constraints.
Parameters of the UAVNumeric Value
Flight speed V[9 m/s, 17 m/s]
Flight altitude H[5 m, 20 m]
The minimum track segment Lmin12 m
Pitch angle q[−45°, 45°]
Yaw angle j[−60°, 60°]
Safe distance between UAVs dsafe5 m
Maximum flight range Lmax1800 m
Table 7. Simulation parameters for UAV start and target coordinates.
Table 7. Simulation parameters for UAV start and target coordinates.
Experiment TypeUAV NumberInitial Position (m)Goal Position (m)
1UAV1(12, 94, 2)(620, 910, 4)
UAV2(12, 22, 2)(875, 830, 4)
UAV3(86, 20, 2)(970, 510, 4)
2UAV1(20, 140, 2)(82, 930, 4)
UAV2(20, 20, 2)(620, 910, 4)
UAV3(60, 105, 2)(875, 930, 4)
UAV4(105, 60, 2)(970, 510, 4)
UAV5(140, 20, 2)(860, 30, 4)
Table 8. Evaluation parameters of 3 UAVs path quality under different algorithms.
Table 8. Evaluation parameters of 3 UAVs path quality under different algorithms.
Algorithm NameRunning Time of the CPURepresentative SolutionSafety FactorEnergy Consumption Coefficient
NSBKA1150.66 sSafety3.40-
Energy consump-3321.64
MOSSA1217.83 sSafety3.64-
Energy consump-3400.82
MOGWO1855.74 sSafety3.48-
Energy consump-3397.07
MOSPO1768.76 sSafety3.32-
Energy consump-3432.18
MOGNDO1109.10 sSafety3.99-
Energy consump-3421.16
Table 9. Evaluation parameters of 5 UAVs path quality under different algorithms.
Table 9. Evaluation parameters of 5 UAVs path quality under different algorithms.
Algorithm NameRunning Time of the CPURepresentative SolutionSafety FactorEnergy Consumption Coefficient
NSBKA1894.02 sSafety9.53-
Energy consump-4909.34
MOSSA2010.13 sSafety8.50-
Energy consump-4914.05
MOGWO2416.51sSafety9.90-
Energy consump-4814.62
MOSPO2169.78 sSafety8.47-
Energy consump-5020.19
MOGNDO1698.09 sSafety9.94-
Energy consump-4980.56
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

Liu, X.; Wang, F.; Liu, Y.; Li, L. A Multi-Objective Black-Winged Kite Algorithm for Multi-UAV Cooperative Path Planning. Drones 2025, 9, 118. https://doi.org/10.3390/drones9020118

AMA Style

Liu X, Wang F, Liu Y, Li L. A Multi-Objective Black-Winged Kite Algorithm for Multi-UAV Cooperative Path Planning. Drones. 2025; 9(2):118. https://doi.org/10.3390/drones9020118

Chicago/Turabian Style

Liu, Xiukang, Fufu Wang, Yu Liu, and Long Li. 2025. "A Multi-Objective Black-Winged Kite Algorithm for Multi-UAV Cooperative Path Planning" Drones 9, no. 2: 118. https://doi.org/10.3390/drones9020118

APA Style

Liu, X., Wang, F., Liu, Y., & Li, L. (2025). A Multi-Objective Black-Winged Kite Algorithm for Multi-UAV Cooperative Path Planning. Drones, 9(2), 118. https://doi.org/10.3390/drones9020118

Article Metrics

Back to TopTop