1. Introduction
In this paper, we present an innovative bird-driving strategy for airport environments that leverages quadcopter unmanned aerial vehicles (UAV). The proposed method capitalizes on the high maneuverability and ease of control offered by quadrotor UAVs, combined with deep learning algorithms to effectively drive birds in airport settings. The bird-driving process is divided into three stages: target bird trajectory prediction, UAV swarm task assignment, and UAV swarm path planning. First, the motion trajectory of the target bird is predicted as it enters the protected area. Second, bird-driving tasks are allocated to the UAV swarm by calculating the flight cost between each UAV and the target bird. Finally, as the UAV swarm formation approaches the target bird, it employs containment and repulsion maneuvers to drive the bird away from the protected area.
Bird strikes are a critical safety concern in global civil aviation, posing significant risks to airport operations. Large birds, such as ospreys and storks, can cause severe air accidents by entering turbofan engines or striking critical parts of aircraft, including wings and cockpits, during high-speed flight [
1,
2,
3]. Therefore, it is crucial to adopt effective bird dispersal measures to mitigate the risk of bird strikes in both airport and route operations, ensuring flight safety and operational continuity. Currently, conventional bird dispersal methods employed by airports primarily include acoustic interference, visual deterrence, physical interception, and chemical deterrence [
4]. Traditional airport bird-driving strategies can be broadly categorized into three stages: observing bird conditions [
5], detecting bird presence, and executing bird dispersal. However, these traditional methods suffer from limitations such as low bird-driving intensity, inefficiency, poor reuse rates, and high demand for manual operations, making it difficult to address the problem fundamentally. Therefore, some researchers have also conducted a series of studies on bird repelling, as shown in
Table 1.
Although these studies have achieved certain results, there are still areas that need improvement. In recent years, UAVs equipped with bird-driving devices have emerged as a promising solution to the bird strike problem [
12,
13,
14,
15]. Compared to traditional bird-driving methods, UAVs offer enhanced mobility, flexibility, and programmability [
16,
17,
18], enabling more targeted and effective bird dispersal efforts [
13]. Additionally, UAV swarm cooperative bird-driving leverages synergistic advantages, improving system efficiency in terms of agility and reliability and enhancing overall system performance across multiple dimensions. Compared to existing bird-driving methods at airports, our strategy significantly reduces labor costs and enhances bird-driving efficiency, which is crucial for ensuring the safety of aircraft operations.
The bird-driving problem addressed in this paper can be regarded as a specific instance of the multi-agent “herding problem” commonly explored within the field of multi-agent systems (MAS). In a typical herding scenario, a group of cooperative agents—such as robots, drones, or shepherd dogs—collaborate to drive or guide a group of targets into or out of a designated area. This problem involves complex challenges related to path planning, task allocation [
19], and real-time control among the agents to achieve the desired outcomes. Existing studies on herding in MAS [
20] have explored various algorithms, including reinforcement learning, particle swarm optimization, the A* algorithm [
21], and distributed control, primarily focusing on multi-target scenarios to address challenges in path planning and task allocation [
22]. Notably, Lama and di Bernardo (2024) investigated the relationship between target density and the minimum number of herding agents required for successful outcomes, identifying critical thresholds that impact herding efficiency [
23]. In contrast, our proposed UAV swarm-based bird-driving strategy is designed to address the unique challenges posed by single-target dynamics. Our approach integrates Long Short-Term Memory (LSTM) networks with the Kalman Filter (KF) to predict the dynamic trajectory of the bird, demonstrating superior performance in handling nonlinear and long-time series data [
24]. Additionally, we employ the Hungarian algorithm for optimal task allocation among UAVs and utilize 3D Dubins path planning to optimize the UAVs’ flight paths. These strategies enhance the swarm’s responsiveness and decision-making precision in dynamic environments, making the entire bird-driving process more real-time and adaptive [
25]. When compared to existing herding studies, our method exhibits significant advantages in trajectory prediction accuracy and real-time performance. Furthermore, research by Li et al. (2024) highlights ongoing challenges faced by large language models in managing complex multi-agent tasks, underscoring the novelty and effectiveness of our approach within this domain [
26].
In the realm of dynamic target trajectory prediction, the most commonly applied algorithms can be broadly categorized into two types: model-based Kalman Filter (KF) algorithms [
27] and data-driven deep learning prediction algorithms. The traditional Kalman Filter algorithm excels in speed and accuracy when handling linear models, but it has limitations when dealing with nonlinear, non-Gaussian noisy data, as it does not adapt well to such conditions. Additionally, the prediction accuracy of the Kalman Filter heavily depends on the precision of the established target motion model [
28]. In contrast, deep learning prediction algorithms offer a different and more flexible approach. The traditional Recurrent Neural Network (RNN) model is prone to gradient explosion issues when dealing with long-time series data [
29]. However, the Long Short-Term Memory (LSTM) neural network, an advanced variant of the RNN model, effectively addresses the long-term dependency problem inherent in RNNs through its gating mechanism. LSTM demonstrates excellent adaptability when handling long time series of nonlinear data and exhibits robustness against non-Gaussian noise [
30].
In this paper, we first designed a UAV swarm cooperative bird-driving strategy for airports, capable of driving birds in a timely and effective manner, thereby significantly contributing to the safety of aircraft. Next, we proposed a bird trajectory prediction algorithm based on the LSTM-KF approach. This approach combines the real-time recursive state estimation and adaptive noise-handling capabilities of the Kalman Filter (KF) with the robust capacity of Long Short-Term Memory (LSTM) networks to model complex dynamics and deliver accurate long-term predictions. This ensures precise prediction of the target’s flight trajectory, thereby enabling the UAV swarm formation to more effectively evict the target from the protected area.
2. Problem Description and System Model
In this section, we discuss the problem of UAV swarm bird-driving in airport environments, with a focus on the mathematical formulation of the UAV swarm’s task of bird-driving from a protected area. We present the models governing the interaction between the UAVs and the target bird, including the motion dynamics of both the UAVs and the bird. Additionally, we detail the criteria for successful bird expulsion and the constraints on UAV movement within the protected area. The problem is further structured by defining the objective functions and constraints that guide the cooperative behavior of the UAV swarm.
2.1. Problem Description
The presence of birds near airports poses a significant threat to aviation safety, as bird strikes can cause severe damage to aircraft, potentially leading to catastrophic outcomes. Traditional bird deterrence methods, such as acoustic, visual, and physical interventions, often prove inadequate in dynamic and unpredictable environments. The advent of unmanned aerial vehicles (UAVs) offers a promising solution, enabling more flexible and adaptive bird repulsion strategies. However, effectively coordinating a swarm of UAVs to herd birds away from critical areas, such as runways, requires precise trajectory prediction and real-time decision-making capabilities.
In this study, we frame the problem as a multi-agent herding scenario, where a group of UAVs, operating as a coordinated swarm, is tasked with driving one or more avian targets out of a designated protected area. The challenge lies in dynamically predicting the birds’ flight paths and synchronizing the UAVs to intercept and guide them away from the restricted area. This requires not only accurate trajectory prediction algorithms that can handle the non-linear, stochastic nature of bird flight but also efficient task allocation and path planning strategies within the UAV swarm.
The proposed solution must address several key challenges: (1) the unpredictable behavior of birds, which complicates trajectory prediction; (2) the need for real-time, decentralized control of the UAV swarm to ensure responsiveness and adaptability; and (3) the computational efficiency required to maintain real-time performance, given the constraints of onboard processing power and communication bandwidth. Addressing these challenges is crucial for developing a robust UAV-based bird deterrence system that can reliably protect airport airspace from bird incursions.
2.2. System Model
Our UAV swarm bird-driving is carried out inside the sphere
D , which has an elliptical protective area
E with its center represented by
O. A formation of five UAVs
Ui,
Uij denotes the
j-th UAV in the
i-th UAV formation (
i = 1, …,
N,
j = 1, …, 5 (See
Section 4.1 for details)), with a target bird of
B, is dynamically defined as follows:
where (
pij)
0 ∈
D is the initial position of the
Uij, (
pB)
0 ∈
D is the original position of the target bird
B,
uij are the velocity control inputs of
Uij, and
uB are the velocity control inputs of
B, respectively. Assume that
≤
vmax,
≤
vmax, ∀
t ≥ 0, ∀
i = 1, …,
N, where
vmax is the maximum control input speed.
The distance between
B and
Uij at any given time
t is defined as
At any given time
t, the distance
dB(
t) between
B and the center
O of the area
E is defined
where
xB(
t),
yB(
t),
zB(
t) are the three-dimensional spatial coordinate values of the target
B relative to the center
O at the moment
t.
Then, the eviction success condition is defined as
where
rc > 0 is the specified expulsion radius and
T < ∞ is the expulsion time. We assume
rc = 100 m and
vmax = 5 m/s in this paper. To prevent target
B from entering protected area
E, the UAV formation
must ensure that
p: = (
pB,
, …,
) remains within the following set
Problem: For any initial p0: = ((pB)0, (p1)0, …, (pN)0) ∈ Dp*, and for any admissible target input uB(t), find an expulsion strategy uij(t) for each UAV formation Uij such that (i) the expulsion condition (Equation (4)) satisfies finite T < ∞, and ii) for any T∈(0, T], the trajectory defined by Equation (1) satisfies p(t): = (pB(t), p1 (t), …, pN (t))∈Dp
An UAV in each UAV swarm formation is set as the Virtual Leader; when the target does not appear, the rest of the UAVs are maintained around the Virtual Leader formation; when the target enters the protected area, the UAV swarm formation closest to the target starts to drive away the target, and the overall modeling is as shown in
Figure 1.
3. Target Trajectory Prediction
In this section, we describe the problem of target trajectory prediction in UAV swarm-based bird-driving operations. We present two core algorithms—Kalman Filter (KF) and Long Short-Term Memory (LSTM) networks—each addressing specific challenges in predicting the bird’s flight path. The Kalman Filter excels in real-time state estimation, particularly in linear models, while LSTM networks are adept at handling non-linear, long-term dependencies in the bird’s trajectory. We then introduce a novel approach that combines the strengths of both KF and LSTM to create an enhanced trajectory prediction algorithm. This hybrid algorithm is designed to improve accuracy and adaptability in dynamic environments. Furthermore, experimental results are provided to validate the effectiveness of the proposed algorithm, demonstrating its superiority over using either algorithm alone in various bird-driving scenarios.
3.1. Principles of Target Trajectory Prediction Algorithms
The bird-driving strategy presented in this paper (see
Section 4 for details) is based on the prediction of the target’s trajectory. Accurate trajectory prediction is essential for enabling the UAV swarm to encircle and drive the target along its probable flight path, thereby forcing it to move away from the protected area. To determine the optimal interception position, the UAV swarm formation must continuously predict the target’s movement based on both the formation’s speed and the target’s speed.
Traditional methods, such as Kalman Filtering, rely heavily on the modeled physical motion of the target and perform poorly with non-Gaussian noise or nonlinear data. In contrast, Long Short-Term Memory (LSTM) networks excel in handling these challenges, particularly when managing non-Gaussian noise, nonlinear data, and long-time series data commonly found in dynamic environments. This capability makes LSTM networks particularly effective for applications requiring robust prediction, such as target trajectory forecasting. Considering the strengths and weaknesses of these two algorithms, we propose an LSTM-KF hybrid algorithm that leverages LSTM’s nonlinear learning capacity alongside the Kalman Filter’s real-time update capabilities for enhanced target trajectory prediction. This method aims to improve the accuracy and real-time performance of trajectory prediction in dynamic and complex environments.
The network structure diagram of the hidden unit in the LSTM network is shown in
Figure 2. Assume that the LSTM model accepts a series of observations {
pB(0),
pB(1), …,
pB(
t)} and predicts the position of the next state
pB(
t + 1). In LSTM, the computation of each time step can be expressed as
Hidden state:
where
σ is the sigmoid function,
W and
b represent the weight and bias terms, and
h(
t) and
C(
t) are the hidden and cell states at time
t, respectively.
Eventually, the output
pB(
t + 1) of the LSTM can be further transformed by
h(
t) to obtain:
where
pB(
t + 1) is the target state prediction of LSTM at time
t + 1.
The predicted output
pB(
t + 1) of the LSTM is used as the initial state estimate for the KF and then further corrected and updated through the prediction and update steps of the KF. Set the initial state estimate of the KF to be
p0(t + 1) and the initial covariance matrix to be
p0(t + 1). So, there are
The KF process can be performed in the following steps
- (1)
Predicting stage:
- (2)
Updating stage:
where
F(
t) is the state transition matrix,
Ppred(
t + 1) is the estimation error covariance at time
t, and
Q(
t) is the process noise covariance matrix. In the prediction phase of the Kalman Filter, the process noise covariance matrix
Q(
t) represents the uncertainty in the system’s dynamic model. It accounts for the differences between the modeled system dynamics and the actual state, often caused by unmodeled dynamics or random disturbances in the environment. Essentially, the matrix
Q(
t) determines how much confidence we place in the system’s predicted state. For example, if the dynamic model of the system is highly accurate and not affected by external disturbances, the process noise covariance matrix can be set to a small value, indicating a high level of confidence in the model’s predictions. However, when the system is subject to significant external influences or when the target’s behavior (such as bird flight trajectories) is unpredictable, the matrix
Q(
t) should be set to a larger value to reflect lower confidence in the predictions, relying more on measurement updates during the filtering process. In this study, the process noise covariance matrix
Q(
t) is adjusted to account for the stochastic and unpredictable nature of bird flight trajectories. By carefully balancing the weight between prediction and measurement updates, the Kalman Filter can better handle the dynamic changes in bird movements, leading to more accurate and stable target trajectory predictions.
H(
t + 1) is the observation model matrix,
R(
t + 1) is the observation noise covariance matrix,
z(
t + 1) is the actual observation at time
t + 1, and
I is the unit matrix.
In general, the approximate steps of the algorithm are: 1. Use the predicted value pB(t + 1) of LSTM as the initial state estimate p0(t + 1) of the Kalman filter. 2. According to the prediction steps of the Kalman filter, calculate the next state prediction (pB)pred(t + 1) and prediction covariance matrix Ppred(t + 1). 3. After observing new data, use the update step to correct the state estimate pB(t + 1) and covariance matrix P(t + 1).
3.2. Algorithm Experiment
The algorithm proposed in this paper combines the advantages of two mainstream trajectory prediction algorithms to more accurately reflect the actual trajectory while reducing prediction error. Using this algorithm, we predicted the target’s motion trajectory in a simulation experiment; among them, the LSTM model was trained by collecting over 300 real bird flight trajectories as the training set. The LSTM model is trained by collecting over 300 real bird flight trajectories (extracted from real bird flight videos) as the training set.
3.2.1. Comparative Experiment on Prediction Steps
To thoroughly assess the impact of different prediction steps on trajectory prediction accuracy and overall task performance, we conducted a comparative experiment. This experiment evaluates the performance of our UAV swarm bird-driving strategy under varying prediction step sizes, specifically comparing one-step, three-step, and five-step trajectory predictions. We utilized the same simulation environment described earlier in the paper, with the UAV swarm tasked with driving a target bird out of a protected area. The LSTM-Kalman Filter (LSTM-KF) hybrid model was used for trajectory prediction across all experiments. The primary variables of interest were the prediction error (measured as the difference between the predicted and actual bird positions) and the overall task completion time (measured from the moment the bird enters the protected area until it is successfully driven out).
3.2.2. Results and Analysis
The results of the comparative experiment are summarized in
Table 2. As shown in
Table 2, the prediction error increases with the number of prediction steps. The one-step prediction achieved the lowest mean squared error (MSE) for all models. Specifically, the LSTM-KF model had the lowest MSE at 0.9092 m, followed by the LSTM model at 1.1686 m and the KF model at 1.4475 m. However, as the prediction steps increased, the error grew significantly. By the third step, the LSTM-KF model still had the lowest MSE at 5.1434 m, compared to 8.1849 m for the LSTM model and 8.5391 m for the KF model. This demonstrates that while longer prediction steps introduce more uncertainty, the LSTM-KF model consistently outperforms the others in terms of accuracy. This indicates that longer prediction steps introduce greater uncertainty and inaccuracy, likely due to the accumulation of prediction errors over time. Correspondingly, the task completion time also increased as the prediction step lengthened. The one-step prediction scenario completed the task in the shortest time (71 s), while the five-step prediction scenario required the longest time (82 s). This suggests that the higher prediction errors in three steps and five steps resulted in less efficient task execution, as the UAVs may have relied on less accurate data to guide their movements.
3.2.3. Algorithm Experiment and Analysis
Figure 3a shows the target trajectory and the predicted trajectories using the three prediction algorithms. The red line represents the actual trajectory of the target, while the green, blue, and black dashed lines represent the predicted trajectories using the LSTM, KF, and LSTM-KF algorithms, respectively.
Figure 3b shows the prediction errors of the three algorithms. The total absolute error of the prediction results of the three algorithms on the X, Y, and Z axes. It is evident that the accuracy of the KF algorithm decreases when the velocity direction of the target changes rapidly. Compared to the KF algorithm, the LSTM algorithm produces significantly smaller errors; with time, LSTM has become more and more accurate in predicting the trajectory of the target with its unique memory function. However, at the same time, the error of the LSTM prediction results will gradually accumulate. As shown in
Figure 3b, the LSTM-KF algorithm proposed in this paper effectively combines the advantages of both algorithms, further reducing the prediction error.
3.2.4. Discussion
The comparative experiment highlights the trade-offs associated with different prediction steps. While longer prediction steps provide a more extended view of the bird’s future trajectory, the increased prediction errors can lead to suboptimal UAV positioning and slower task completion. The one-step prediction approach, on the other hand, offers the best balance between accuracy and real-time adaptability, supporting faster and more precise UAV coordination. These findings justify our initial decision to use one-step-ahead predictions in the UAV swarm bird-driving strategy. By minimizing prediction errors and maintaining high accuracy, the UAVs can effectively respond to the bird’s movements in real-time, ensuring a more efficient and successful driving process.
4. UAV Swarm Cooperative Bird-Driving Strategy at Airport
The basic idea of our proposed UAV swarm airport bird eviction scheme is as follows: there are several UAV swarm formations, each consisting of five UAVs. When the distance dB between the target and the center O of the protected area E is less than rc, the UAV formation closest to the target is assigned to evict the target. Firstly, the flight trajectory of the target is predicted, and then the flight cost of each UAV in the formation to reach the target is calculated to derive a suitable blocking position. Subsequently, each UAV in the formation is assigned a task. After obtaining the target mission location points for each UAV, the flight path of the UAVs is planned.
4.1. Research Hypothesis
4.1.1. Equipment Required
In our proposed system, the UAVs are not equipped with additional cameras or onboard GPS trackers. Instead, we leverage the airport’s bird detection radar system for tracking bird movements in the airspace. The radar system provides continuous real-time data about bird flocks’ positions, allowing the ground-based system to monitor and track birds without needing additional sensors or hardware on the UAVs themselves. This setup significantly reduces the UAV’s complexity and cost.
4.1.2. Computation and UAV Control
All computational tasks related to bird detection, trajectory prediction, and UAV path planning are conducted by a ground-based upper computer (base station). The UAVs are not responsible for executing these complex computations. Their role is limited to executing flight commands provided by the base station. The base station processes the radar data to generate the optimal flight paths for the UAVs. These flight paths are dynamically adjusted in real-time based on the updated positions of the bird flocks. This ensures that the UAVs can quickly and efficiently respond to bird movements.
4.1.3. Information Flow
The base station receives bird position data from the radar system and uses this information to compute the optimal flight paths for each UAV. These commands are then sent to the UAVs, which execute the given commands without needing additional onboard decision-making capabilities. Unlike other systems that may rely on UAV-mounted cameras or GPS trackers to detect birds, our system benefits from centralized data processing at the base station. This allows for more efficient coordination between the UAVs and reduces the burden on each individual drone.
4.1.4. Bird Behavior
In this section, we assume that the birds act individually without considering the dynamics of group behavior. This simplification allows us to focus on the interactions between individual birds and the UAV formations, making the modeling more manageable and straightforward. Furthermore, we posit that the number of bird attacks does not exceed the number of UAV formations deployed in our simulations. For instance, if we deploy N UAV formations, we assume a maximum of N individual bird attacks can occur during the simulation period.
The general process is illustrated in
Figure 4. Finally, the target is blocked and driven away from its predicted trajectory, forcing it to move away from the protected area
E. The eviction is considered successful when the distance
dB between the target and the center
O of the protected area
E is greater than
rc. During this process, if the target is driven away but then attempts to approach the protected area again with
dB less than
rc, the UAV formation responsible for the eviction will continue to drive the target away. The overall process of the strategy is shown in
Figure 4.
4.2. Optimal UAV Configuration Analysis
Before detailing the UAV swarm cooperative bird-driving strategy, we conducted a comprehensive cost–benefit analysis to determine the optimal number of UAVs for each group. The objective was to find a configuration that maintains high efficiency in bird repulsion while effectively controlling the associated costs.
The analysis considered various UAV configurations ranging from 4 to 8 drones in each group, with each configuration subjected to 15 simulation trials. Key parameters such as time step, maximum acceleration, and maximum speed were set alongside a fixed cost for each UAV (in this paper, it is assumed to be
$1000). For each configuration, we standardized the total costs and task completion times to evaluate the cost–benefit ratio. A weighted scoring system was applied, assigning a cost weight of 0.6 and an efficiency weight of 0.4. This approach ensured a balanced consideration of both cost and efficiency in the evaluation. The specific calculation methods for cost–benefit ratio and scores are as follows:
Experimental verification was conducted according to the proposed method, and the experimental results are shown in
Table 3:
As can be seen from
Figure 5, the configuration with 5 UAVs in each group offers the best overall performance, yielding the lowest score and thus the highest cost-effectiveness. While increasing the number of UAVs beyond 5 did lead to marginal improvements in efficiency, these gains were outweighed by the disproportionate rise in costs, leading to diminishing returns. As shown in
Figure 6, the configuration with 5 UAVs in each group was selected as the optimal solution, providing the best trade-off between operational efficiency and cost management.
It is assumed that each UAV can completely cover [
31,
32] any one of these directions, as shown in
Figure 6. Then it means that one direction will be left for the target to escape, and this direction is the direction we expect the target to move.
Assume that target
B can move in six directions: up, down, left, right, front, and back, and each UAV can completely block any direction of motion of the targets shown in
Figure 7.
where
dir1 represents the zone in front of the target (directly in front in the direction of the target speed),
dir2 represents the zone behind the target,
dir3 represents the zone to the left of the target,
dir4 represents the zone to the right of the target,
dir5 represents the zone above the target, and
dir6 represents the zone below the target.
4.3. Motion Based on Proportional Guidance Law
When the UAV formation is too far away from the target (in this paper, we assume the distance threshold
d is 50), a motion based on the proportional guidance law [
33] is used to approach the target quickly. Line of Sight (LOS) refers to the direction of the UAV’s line of sight pointing to the target. In the target tracking system, as long as the LOS direction is calculated in real-time and the UAV moves along the LOS direction, target interception can be realized. Our overall motion based on the proportional guidance law is summarized in Algorithm 1.
Algorithm 1 Motion based on proportional guidance law |
Require: Target position pB(t), UAV position pij(t), UAV velocity uij(t), UAV acceleration (t). Maximum detection range dmax, safety threshold d, proportional gain kp, maximum angular velocity ωmax. |
Ensure: Updated UAV’s speed uij(t) and position pij(t) |
1: while dij(t) > dmax: |
2: Initialization: Set Δt, kp, ωij(t) = 0 |
3: Detect pB(t) |
4: Calculate dij(t) = //pij(t) − pB(t)// |
5: if dij(t) > dmax then |
6: Target search subroutine |
7: else if dij(t) ≤ d then |
uij(t) = kp·(pB(t) − pij(t)/(dij(t) + d) |
8: Apply braking using aij(t) |
9: else if dij(t) > d then |
10: Calculate the 3D LOS unit vector: |
11: Adjust the LOS for dynamic target motion: ladj = l + (d(pB(t))/dt)·Δt |
12: Calculate ωij(t): ωij(t) = min(ladj × (uij(t) − uB(t)///pij(t) − pB(t)//), ωmax) |
13: if ωij(t) > ωmax 14: Apply constraints |
15: end if |
16: Calculate the optimal unit direction vector: η(t) = (uij(t) + kp·ωij(t))///uij(t) + kp·ωij(t)// |
17: update: uij(t + Δt) = uij(t) + (t)·Δt |
18: update: pij(t + Δt) = pij(t)+ uij(t)·Δt |
19: return uij(t) and pij(t) |
20: end if |
21: end while |
The UAV formation decides whether to approach the target via proportional guidance by calculating the distance between the UAV and the target. If the distance to the target exceeds a certain range d, it calculates the 3D LOS unit vector l and the angular rate ωl and then obtains the unit vector η in the direction of the UAV’s movement, which is used to update its own position.
4.4. Assignment of Tasks
When preparing to implement the repulsion, it is necessary to determine the flight destination of each UAV in the formation.
Figure 7 shows the prospective flight paths for each UAV in the UAV formation. This problem can be regarded as an allocation problem, and in this paper, the Hungarian algorithm [
34] is used to solve it.
The Hungarian algorithm is employed in UAV task allocation to optimize target positioning in bird-driving operations by minimizing the overall cost, such as distance and time. This method is chosen for its computational efficiency, optimality, and suitability for real-time applications. Unlike more complex algorithms like reinforcement learning or particle swarm optimization, which require extensive computational resources and tuning, the Hungarian algorithm offers a deterministic and reliable solution that ensures rapid and precise positioning of UAVs. This is crucial in dynamic bird-driving scenarios, where maintaining control over the bird’s trajectory is essential to prevent it from entering protected areas. Furthermore, the integration of the Hungarian algorithm with techniques such as LSTM-KF for trajectory prediction and 3D Dubins path planning enhances the overall effectiveness of the UAV swarm, ensuring each UAV is optimally positioned to fulfill its role. In summary, the Hungarian algorithm’s balance of simplicity, computational efficiency, and effectiveness makes it an ideal choice for task allocation in UAV swarm operations.
First, determine whether the UAV has been assigned a mission, and if so, calculate the cost required for the current UAV to reach each target zone, then build a cost matrix as follows:
where
cij (
i = 1, …, 5,
j = 1, …, 5) denotes the
j-th zone of the target expected to be reached by the
Uij. In this paper
where
m∈[0,1],
n∈[0,1], and
m +
n = 1,
m is the distance cost coefficient and
n is the speed cost coefficient, i.e., the flight cost of the UAV depends on the distance between
Uij and the target and the flight speed of the target.
The optimal allocation is then solved by the Hungarian algorithm to obtain the allocation matrix
which determines the target location to be flown to by each UAV in the UAV formation
Ui = {
u1,
u2,
u3,
u4,
u5}. The elements
aij in the allocation matrix
A are all 0 or 1, and there is only one element of 1 in the
j-th column of the
i-th row, representing the
j-th directional position of the
i-th UAV to fly to the target.
If the distance between the UAV responsible for eviction in the formation and the center O of the protected area E is greater than rc, the task assignment matrix is reset.
4.5. UAV Swarm Path Planning
After assigning a task to each UAV in the formation, path planning is needed to find the optimal path for the UAV to reach the specified target location as quickly as possible. In this paper, the 3D Dubins path planning algorithm is used for UAV path planning. Each UAV in the formation is traversed, and the optimal path for the UAV to reach the target location is calculated using the 3D Dubins path.
Dubins path is a method to connect the shortest curved path between two oriented points (points of a given direction), which is commonly used in path planning for UAVs, robots, etc. [
35]. 3D Dubins path is a method to extend the Dubins path to the three-dimensional space, which is used to solve the shortest curved path connecting two oriented points in the three-dimensional space [
36].
Figure 8 shows the 3D Dubins path for each UAV in a UAV formation to reach the target location at a given moment in time.