Optimization of Multi-Unmanned Aerial Vehicle Cooperative Search Paths Under Communication Constraints

In recent years, Unmanned Aerial Vehicles (UAVs) have been widely applied in various fields, including civil aviation and military operations, such as package delivery, search and rescue missions, and target surveillance. However, when a single Unmanned Aerial Vehicle is tasked with complex and numerous missions, issues like low efficiency and high error rates often arise. In contrast, multi-Unmanned Aerial Vehicle systems offer greater flexibility, the ability to execute more complex tasks, and improved robustness, making them a key technology for future diverse missions. Cooperative search path planning is a critical technology for multi-Unmanned Aerial Vehicle systems, gradually becoming a core technique in military, civilian, and research domains. Through coordinated path planning and task allocation, multi-UAV systems can cover exponentially larger areas, reduce search time, and achieve redundancy through distributed architectures, significantly enhancing system reliability. This approach has become a vital tool for addressing emergent challenges.

Path planning representation typically involves two methods: one based on dynamics, consisting of time sequences of heading and speed, and the other based on geometry, comprising spatial sequences of coordinates. Path planning first requires modeling the search space and constraints. In some cases, the problem can be simplified to two-dimensional space. Common spatial modeling methods include grid-based approaches, waypoint methods, and potential field methods. Grid methods discretize three-dimensional space into two-dimensional problems but face inherent trade-offs between resolution and computational load. Voronoi diagram methods reduce the search space through topological segmentation but limit path diversity. Additionally, communication coupling effects in dynamic environments, such as signal attenuation due to obstacle occlusion, are often oversimplified or ignored, leading to discrepancies between models and real-world scenarios.

Compared to single Unmanned Aerial Vehicle systems, multi-Unmanned Aerial Vehicle path planning involves higher complexity and more constraints, necessitating superior multi-objective optimization algorithms. Existing path planning algorithms can be categorized into mathematical programming methods, artificial potential field methods, graph-based methods, and intelligent optimization algorithms. Mathematical programming methods, such as mixed integer linear programming (MILP), nonlinear programming (NP), and dynamic programming, have a rigorous mathematical foundation and guarantee optimal solutions but are only suitable for small-scale path planning problems due to high computational complexity. Artificial potential field methods offer real-time advantages but may fall into local optima or even fail to find solutions due to the balance between attractive forces from targets and repulsive forces from obstacles. Graph-based methods’ performance heavily depends on the division of path space; when the path space is complex, these algorithms consume substantial computational resources. Intelligent optimization algorithms include genetic algorithm (GA), ant colony optimization (ACO), particle swarm optimization (PSO), wolf pack algorithm (WPA), and artificial bee colony (ABC) algorithm. For instance, one study combined dynamic multi-swarm PSO (DMSPSO) and comprehensive learning PSO (CLPSO) to propose a comprehensive learning DMSPSO (CL-DMSPSO) algorithm, demonstrating its superiority in multi-constraint path planning for multi-Unmanned Aerial Vehicles, especially under communication constraints. Another study introduced variable pheromone enhancement factors and evaporation coefficients into the ACO algorithm, proposing an ACO based on variable pheromone (ACO-VP) algorithm, which showed good performance in multi-UAV path planning through simulations. Research on partially observable Markov decision process (POMDP) models utilized model predictive control (MPC) to achieve nominal belief state optimization (NBO) and introduced full-dimensional obstacle avoidance distance metrics, proposing a reinforcement learning-based NBO Q-learning (QL-NBO) algorithm for dynamic parameter adjustment in the MPC framework, proving the framework’s robustness and feasibility through simulations. Other studies proposed combined differential evolution algorithms, improved pigeon-inspired optimization, and improved Harris hawks optimization (HHO) algorithms, demonstrating high efficiency in multi-Unmanned Aerial Vehicle cooperative search problems. One study designed a UAV-assisted Internet of Things system and proposed a hybrid algorithm based on dynamic programming and improved k-means clustering to effectively address UAV trajectory optimization. Another study presented a heuristic method for multi-UAV reconnaissance task allocation considering heterogeneous target characteristics, showing through simulations that negative feedback regulation significantly improved convergence speed. However, these algorithms’ performance improvements often rely on empirical parameter tuning rather than theoretical breakthroughs, still facing limitations in balancing optimization accuracy and computational efficiency, and struggling with collaborative optimization of multi-objective conflicts (e.g., path length, energy consumption, communication) and dynamic constraints (e.g., real-time obstacle avoidance).

The HHO algorithm, proposed by Heidari et al. in 2019, simulates the cooperative foraging behavior of Harris hawks. Its unique bio-inspired mechanism and efficient optimization capabilities have shown significant advantages in various fields. However, its application in multi-Unmanned Aerial Vehicle cooperative search path planning is limited due to issues such as limited multi-objective optimization ability, lack of adaptive mechanisms, and exploration-exploitation imbalance, which pose risks of premature convergence and local optima in multi-constraint path planning. Based on these considerations, we propose a chaotic adaptive cycle HHO (CACHHO) algorithm, making improvements from both modeling and algorithmic perspectives. Building on traditional constraints like path length, turning angle limits, and obstacle avoidance, we introduce a distance-obstacle coupled communication model to quantify the impact of communication attenuation on cooperative search path planning, enabling more precise optimization of multi-Unmanned Aerial Vehicle cooperative search paths. By incorporating a Tent chaos strategy to enhance population initialization diversity, this strategy, with its randomness, ergodicity, and sensitivity to initial values, allows the algorithm to achieve faster convergence speeds, effectively solving multi-UAV multi-constraint problems and meeting the real-time requirements of path planning. Simultaneously, we introduce an energy periodic decrease strategy, changing the linearly varying escape energy factor to periodic decrease, setting reasonable parameters to balance global exploration and local exploitation capabilities. To further improve convergence speed while maintaining accuracy, we introduce an adaptive inertia weight update formula to enhance the global exploration and local development capabilities of Harris hawks. Through benchmark function validation and simulation experiments, we demonstrate that the algorithm outperforms HHO, PSO, and other comparison methods in planning quality, providing an extensible algorithmic framework for autonomous cooperative search of UAV clusters in complex environments.

Problem Description

Multi-Unmanned Aerial Vehicle cooperative search path planning is a critical prerequisite for effective multi-UAV search, accompanied by numerous practical constraints. Considering typical mission scenarios such as disaster relief and battlefield reconnaissance, Unmanned Aerial Vehicles need to achieve rapid target coverage in structured obstacle environments like buildings and mountains, while being constrained by the dispersion of takeoff and landing sites. Heterogeneous starting point design effectively simulates the spatial heterogeneity of real missions. Based on these considerations, the problem assumptions are as follows: multiple Unmanned Aerial Vehicles need to fly from different starting points in a limited space to the same search target, with some known obstacles in the space. The goal is to find the shortest path for each UAV under various constraints. Considering UAV flight control stability and energy efficiency, the flight path must be smooth. Additionally, since there are several obstacles and multiple Unmanned Aerial Vehicles, safety must be ensured, meaning the UAVs must avoid obstacles and not collide with each other. Traditional cooperative search studies often simplify communication capability to an idealized distance threshold model, whereas this paper addresses the realistic electromagnetic propagation characteristics in complex obstacle environments, proposing a topological connectivity and obstacle-coupled attenuation model to ensure group decision information is synchronized across the network, avoiding connectivity misjudgments caused by ignoring obstacle occlusion in traditional methods.

Based on the above, this study focuses on multi-Unmanned Aerial Vehicle cooperative search path planning under the following constraints to find the shortest path:

  1. During flight, the turning angle at UAV waypoints is limited.
  2. Unmanned Aerial Vehicles must avoid collisions with each other.
  3. UAV paths must avoid obstacles.
  4. Topological connectivity must be guaranteed, meaning there is at least one effective communication path between any two UAVs.

Model Establishment

Based on Section 2.1, we establish the objective function to seek the shortest path under four necessary practical constraints in a limited flight space. This paper uses a geometry-based spatial coordinate representation for paths. Assuming M UAVs fly at the same altitude, each UAV’s path contains N waypoints, including the start and target points. Therefore, each UAV’s path can be represented by $$(x_{i1}, y_{i1}, x_{i2}, y_{i2}, \ldots, x_{iN}, y_{iN})$$ for i = 1, 2, …, M.

Geometry-based UAV constraints can be divided into two representation types. The first type of flight constraints can be evaluated using waypoints, meaning they can be represented by the coordinates of waypoints and their geometric relationships, such as path length and maximum turning angle limits. The second type of flight constraints cannot be fully expressed with existing waypoints; even if waypoints are in suitable positions, the entire path may not be flyable, such as collision risks between UAVs and obstacles, between UAVs themselves, and communication connectivity. To address this, we divide the paths between waypoints into shorter segments and compute the cost at these division points, which then serve as reasonable constraints for UAV path planning.

By introducing penalty functions, we transform the constrained optimization problem into an unconstrained one, constructing the corresponding objective function as described below.

Path Cost

As analyzed, path length can be represented using waypoint coordinates as follows:

$$f_L = \sum_{j=2}^{N} \sqrt{(x_{ij} – x_{ij-1})^2 + (y_{ij} – y_{ij-1})^2}$$

This equation calculates the sum of Euclidean distances between consecutive waypoints, representing the path length cost for the i-th Unmanned Aerial Vehicle. Based on the problem background, under the four constraints, a smaller f_L value indicates higher path quality. By introducing penalty functions, the corresponding constraints are constructed into the objective function, thus converting the multi-constraint optimization problem into an unconstrained one. However, to find the optimal path for multiple Unmanned Aerial Vehicles, the following scenarios must be considered:

  1. The objective function value (OFV) of feasible paths must be less than that of infeasible paths.
  2. Among feasible paths, those with fewer violations of communication constraints should have smaller OFVs.
  3. The feasible path with the smallest OFV value is selected.

Turning Angle Penalty Function

Based on the inherent maneuvering characteristics of Unmanned Aerial Vehicles, the planned path must be smooth. Specifically, the path generated by the algorithm must conform to the UAV’s small turning angle characteristics. The turning angle can be calculated based on waypoints, defined here as the angle between the previous direction and the current direction of the UAV, as shown in the figure below.

The turning angle calculation formula and penalty function design are as follows:

$$\theta_{ij} = \arccos \left( \frac{ (x_{ij} – x_{ij-1}, y_{ij} – y_{ij-1}) \cdot (x_{ij+1} – x_{ij}, y_{ij+1} – y_{ij})^T }{ \| (x_{ij} – x_{ij-1}, y_{ij} – y_{ij-1}) \| \cdot \| (x_{ij+1} – x_{ij}, y_{ij+1} – y_{ij}) \| } \right)$$
$$f_T = \begin{cases} 10, & \theta_{ij} > \theta_{\text{max}} \\ 0, & \theta_{ij} \leq \theta_{\text{max}} \end{cases}$$

Here, θ_ij is the turning angle at the j-th waypoint of the i-th UAV, and θ_max is the maximum turning angle for the UAV, where j = 2, 3, …, N-1.

Collision Avoidance Constraint

During flight, ensuring a safe distance between Unmanned Aerial Vehicles is paramount. Assuming UAV speeds vary within a certain range to meet path planning needs, the speed between any two waypoints remains constant, but speeds can differ between waypoints. In this problem, we uniformly divide the segment between the j-th and (j+1)-th waypoints of the i-th UAV into N_s segments, resulting in N_s division points including the start and target points. These division points are called division evaluation points. The u-th division evaluation point of the i-th UAV can be represented as (x_{iu}, y_{iu}) for u = 1, 2, …, N_s, and its values can be calculated from the waypoints.

Given the paths of UAVs m and n, for m, n = 1, 2, …, M, m ≠ n, let the minimum distance between UAVs be d_min. The distance between the u-th division evaluation points of UAV m and n is d_{mn}^u. When d_{mn}^u < d_min, a collision is considered to have occurred, and the objective function for this path is penalized. Thus, the collision avoidance penalty function is designed as:

$$f_S = \begin{cases} 10, & d_{uv}^u < d_{\text{min}} \\ 0, & d_{uv}^u \geq d_{\text{min}} \end{cases}$$

Obstacle Avoidance Constraint

For safety, Unmanned Aerial Vehicles must avoid collisions with obstacles during flight. In different environments, obstacle sizes vary; larger obstacles mean less flyable space, and relatively shorter paths inevitably come with higher collision risks, while longer paths relatively ensure UAV flight safety. Assuming obstacle positions and sizes are known, each UAV’s path is divided into N_r risk assessment points, including start and target points. N_r balances computational cost and path planning accuracy, with values determined case by case. Let (x_{ir}, y_{ir}) for r = 1, 2, …, N_r denote the r-th risk assessment point of the i-th UAV, which can be calculated from the N waypoints. When a risk assessment point is inside an obstacle, the objective function is penalized. The obstacle avoidance penalty function is designed as:

$$f_R = \begin{cases} 10, & (x_{ik}, y_{ik}) \text{ inside obstacle} \\ 0, & \text{otherwise} \end{cases}$$

Communication Constraint

Communication between Unmanned Aerial Vehicles is key to cooperative task execution. Typically, any two UAVs are required to maintain communication connectivity during flight. In this paper, due to the presence of obstacles, we distinguish between line-of-sight (LOS) and non-line-of-sight (NLOS) communication. The relevant formulas are as follows:

$$\beta(d) = \begin{cases} \beta_0 d^{-\alpha}, & \text{LOS environment} \\ k \beta_0 d^{-\alpha}, & \text{NLOS environment} \end{cases}$$
$$\beta_0 = \left( \frac{c}{4\pi f_c} \right)^2$$
$$\text{SNR} = \beta(d) \cdot 10^{\frac{P_t – P_n}{10}}$$

Here, β(d) is the communication coefficient function varying with the distance d between UAVs; β_0 is the path loss at reference distance 1 m under LOS; k is the additional attenuation factor under NLOS; c is the speed of light; f_c is the carrier frequency. Whether two UAVs are in LOS is determined by the presence of obstacles between them. The signal-to-noise ratio (SNR) is the ratio of signal power to noise power; a higher value indicates better signal quality and less interference. P_t represents the UAV signal transmission power, P_n represents the noise power, and with SNR_t as the standard, when SNR ≤ SNR_t, the two UAVs are considered to have no communication.

In this paper, we introduce a continuous connectivity constraint for the communication topology. Specifically, as shown in the figure below, UAV 1 can communicate with UAV 3 and UAV 4 but not directly with UAV 2 and UAV 5. Through UAV 4’s communication relay, UAV 1 can maintain communication with UAV 2 and UAV 5. The labeled UAV in the figure serves as a communication relay.

Based on the above, the communication constraint objective function is designed as:

$$f_C = \begin{cases} 0, & \text{SNR} > \text{SNR}_t \\ 10, & \text{SNR} \leq \text{SNR}_t \end{cases}$$

Overall Objective Function

After the above discussion, by introducing penalty functions, the multi-constraint multi-Unmanned Aerial Vehicle cooperative search path planning problem is transformed into an unconstrained optimization problem. The overall objective function F_obj can be viewed as a linear combination of Equations (1), (3), (4), (5), and (9):

$$F_{\text{obj}} = \omega_1 f_L + \omega_2 f_T + \omega_3 f_S + \omega_4 f_R + \omega_5 f_C$$

Here, ω_i (i = 1, 2, …, 5) are weight factors, and ω_1 + ω_2 + ω_3 + ω_4 + ω_5 = 1. The weight vector acts as a decision lever for the multi-objective optimization problem. Specifically, when navigating through complex obstacles, to ensure safety, it is necessary to appropriately increase path length to guarantee flight safety, i.e., reduce ω_1 and increase ω_3, ω_4, forcing the algorithm to prioritize routes with higher safety factors and accept suboptimal solutions for other objective functions, thereby achieving safe flight. Depending on the mission, the weight vector can be adjusted to obtain the optimal path. When a feasible flight path satisfying all four constraints is found, the value of F_obj is the path length. The value of F_obj for infeasible paths will be larger, depending on the number of constraint violations. Therefore, this objective function meets the aforementioned requirements. After converting the multi-constraint optimization problem into an unconstrained one, the goal is to minimize F_obj. In the next section, we introduce a CACHHO algorithm to solve this optimization problem.

Path Planning Algorithm

HHO Algorithm

The HHO algorithm, proposed by Heidari et al., is based on the grey wolf optimizer and simulates the cooperative hunting behavior of Harris hawks. The strategy is illustrated in the figure below, mimicking the hunting process of Harris hawks, where the hunting method is selected based on the prey’s escape behavior, divided into global search and local development phases. The transition between these phases depends on the prey’s escape energy factor E_r. In the global search phase, the HHO algorithm uses random numbers to quickly find the optimal interval through different group behaviors, conducting extensive searches. In the local development phase, cooperative hunting enhances the intensity and responsiveness of predation, employing a “surprise pounce” strategy that considers the prey’s self-protection behaviors like jumping, divided into four siege strategies, enabling faster and more accurate breakthroughs against the prey’s defenses for efficient capture.

Global Search Phase

In the global search phase, Harris hawks search within the space [lb, ub] and update their positions based on two strategies, with a random probability q as the criterion. The position update formula is as follows:

$$X(t+1) = \begin{cases} X_{\text{rand}}(t) – r_1 |X_{\text{rand}}(t) – 2r_2 X(t)| \mathbf{1}_{D \times 1}, & q \geq 0.5 \\ (X_{\text{rabbit}}(t) – X_m(t)) – r_3 (\text{lb} + r_4 (\text{ub} – \text{lb}) \mathbf{1}_{D \times 1}, & q < 0.5 \end{cases}$$

Here, X(t) is the position vector of the Harris hawk at iteration t; X_rabbit(t) is the position vector of the prey at iteration t; r_i (i=1,2,3,4) and q are random numbers between [0,1]; lb and ub are the lower and upper bounds of the search space; X_rand(t) is a random Harris hawk’s position vector at iteration t; X_m(t) is the average position vector of Harris hawks at iteration t.

In the standard HHO algorithm, the key to balancing global search and local exploration is the prey’s escape energy |E_r|, given by:

$$E = 2 \left(1 – \frac{t}{T}\right)$$
$$E_r = E_0 \cdot E$$

Here, E is the prey energy factor; E_0 is the initial escape energy of the prey, typically set as a random number between [-1,1]; T is the total number of iterations. When |E_r| ≥ 1, Harris hawks perform global search; when |E_r| < 1, they choose one of four strategies for local development.

Local Development Phase

Strategy 1: Soft Siege. When 0.5 ≤ |E_r| < 1 and λ ≥ 0.5, the position update formula is:

$$X(t+1) = X_{\text{rabbit}}(t) – X(t) – E |J X_{\text{rabbit}}(t) – X(t)| \mathbf{1}_{D \times 1}$$

Here, J is the random jump of the prey during escape.

Strategy 2: Hard Siege. When |E_r| < 0.5 and λ ≥ 0.5, the position update formula is:

$$X(t+1) = X_{\text{rabbit}}(t) – E |X_{\text{rabbit}}(t) – X(t)| \mathbf{1}_{D \times 1}$$

Due to decreased prey escape energy, it cannot jump.

Strategy 3: Rapid Dive Soft Siege. When 0.5 ≤ |E_r| < 1 and λ < 0.5, the position update formula is:

$$X(t+1) = \begin{cases} Y = X_{\text{rabbit}}(t) – E |J X_{\text{rabbit}}(t) – X(t)| \mathbf{1}_{D \times 1}, & F(Y) < F(X(t)) \\ Z = Y + S \cdot \text{LF}(D), & F(Z) < F(X(t)) \end{cases}$$

Here, D is the target dimension; S is a D-dimensional random row vector.

Strategy 4: Rapid Dive Hard Siege. When |E_r| < 0.5 and λ < 0.5, the position update formula is:

$$X(t+1) = \begin{cases} Y = X_{\text{rabbit}}(t) – E |J X_{\text{rabbit}}(t) – X_m(t)| \mathbf{1}_{D \times 1}, & F(Y) < F(X(t)) \\ Z = Y + S \cdot \text{LF}(D), & F(Z) < F(X(t)) \end{cases}$$

The strategy selection is illustrated in the figure below.

Proposed CACHHO Algorithm

Tent Chaotic Mapping Strategy

High-quality initial populations significantly help with accuracy and convergence speed. The standard HHO algorithm’s initial population is random but cannot guarantee uniform distribution in the search space. Therefore, we employ a Tent chaotic mapping strategy to obtain a high-quality, uniformly distributed initial population in [0,1], accelerating algorithm convergence and ensuring the effectiveness and scientificity of Harris hawk searches. The specific formula is as follows:

$$X_{n+1} = \begin{cases} \mu X_n, & X_n < 0.5 \\ \mu (1 – X_n), & X_n \geq 0.5 \end{cases}$$

Here, μ is the chaos coefficient, and as it approaches 2, chaos and uniformity enhance. However, when μ = 2, the mapping may degenerate into a short-period system, causing distribution clustering. Thus, in this paper, μ = 1.999.

Select data with small numerical fluctuations and inversely map it to the research interval as follows:

$$Y_i = \text{lb} + X_i \cdot (\text{ub} – \text{lb})$$

Periodic Decrease in Escape Energy Factor

In the HHO algorithm, the escape energy factor E_r determines the Harris hawk’s search strategy. When |E_r| > 1, Harris hawks perform global search; when |E_r| < 1, they perform local development. The original linearly decreasing escape energy factor allocates only 12.5% of total iterations to global exploration. By proposing a nonlinear decrease function, we enhance the Harris hawk’s global search capability, helping to escape local optima for complex function solving. The nonlinear decrease function expression is:

$$E = 2 \sqrt{1 – \left( \frac{t}{T} \right)^2}$$

A comparison between traditional and improved energy factors is shown in the figure below.

Simultaneously, to simulate the multiple rounds of “siege-escape” behavior between Harris hawks and prey, we introduce periodic decrease in energy, using the periodic number of E to represent the rounds of capturing prey, achieving effective “global + local” search for optimization problems. The prey energy factor and escape energy factor are updated as follows:

$$E = 2 \sqrt{1 – \left( \frac{t}{T} \right)^2} \cdot \cos \left( \left(2k + \frac{1}{2}\right) \pi \frac{t}{T} \right)$$
$$E_r = E_0 \cdot E_r$$

Here, k is the period parameter, achieving multiple alternations between global search and local development. A larger k value results in more alternations and more pronounced local development, while a smaller k focuses more on global search. A comparison between traditional escape energy factor and the improved escape energy factor at k=1 is shown in the figure below.

Adaptive Inertia Weight

Inertia weight ω helps balance the algorithm’s global and local search capabilities. By introducing adaptive inertia weight ω into the position update formula, we adjust the algorithm’s global and local search processes. Adaptive inertia weight ω decreases nonlinearly (as shown in the figure below), focusing on global search capability in the early stages and local development capability in the later stages.

The specific formula is as follows:

$$\omega = e^{-\tan^3 \left( \frac{\pi}{2} \cdot \frac{t}{T} \right)}$$

The global search position formula is updated as follows:

$$X(t+1) = \begin{cases} X_{\text{rand}}(t) – r_1 |X_{\text{rand}}(t) – 2r_2 X(t)| \mathbf{1}_{D \times 1}, & q \geq 0.5 \\ ((\omega X_{\text{rabbit}}(t) – X_m(t)) – r_3 (\text{lb} + r_4 (\text{ub} – \text{lb})) \mathbf{1}_{D \times 1}, & q < 0.5 \end{cases}$$

The soft siege position formula is updated as follows:

$$X(t+1) = \omega X_{\text{rabbit}}(t) – X(t) – E |J X_{\text{rabbit}}(t) – X(t)| \mathbf{1}_{D \times 1}$$

The rapid dive soft siege position formula is updated as follows:

$$X(t+1) = \begin{cases} Y = \omega X_{\text{rabbit}}(t) – E |J X_{\text{rabbit}}(t) – X(t)| \mathbf{1}_{D \times 1}, & F(Y) < F(X(t)) \\ Z = Y + S \cdot \text{LF}(D), & F(Z) < F(X(t)) \end{cases}$$

The rapid dive hard siege position formula is updated as follows:

$$X(t+1) = \begin{cases} Y = \omega X_{\text{rabbit}}(t) – E |J X_{\text{rabbit}}(t) – X_m(t)| \mathbf{1}_{D \times 1}, & F(Y) < F(X(t)) \\ Z = Y + S \cdot \text{LF}(D), & F(Z) < F(X(t)) \end{cases}$$

Algorithm 1 provides the pseudocode for the CACHHO algorithm.

Algorithm 1: CACHHO Algorithm

Input: Search space and objective function

Output: Optimal solution and best objective function value

Parameter initialization: Population size N, maximum iterations T, Harris hawk dimension D, chaos coefficient μ, adaptive inertia coefficient ω.

Generate initial population using Equations (18) and (19)

While (t < T) do

 Calculate individual objective function values using Equation (10)

 Store the best position vector in X_rabbit

 For k = 1 to N do

  Update escape energy factor using Equations (20)-(22)

  If |E_r| ≥ 1 then % Global search

   Update individual position vector using Equation (24)

  Else

   If 0.5 ≤ |E_r| < 1 and λ ≥ 0.5 then

    Update individual position vector using Equation (25)

   Else if |E_r| < 0.5 and λ ≥ 0.5 then

    Update individual position vector using Equation (15)

   Else if 0.5 ≤ |E_r| < 1 and λ < 0.5 then

    Update individual position vector using Equation (26)

   Else if |E_r| < 0.5 and λ < 0.5 then

    Update individual position vector using Equation (27)

   End if

  End if

 End for

End while

Return optimal solution and best objective function value

Benchmark Function Testing

To demonstrate the effectiveness of the proposed CACHHO algorithm, we selected 13 benchmark functions to test algorithm performance, including 5 unimodal functions (f1 to f5) and 8 multimodal functions (f6 to f13). The specific functions are listed in Table 1. The selected 13 benchmark functions all have a minimum value of 0, and results closer to 0 reflect better algorithm performance.

Table 1: Test Functions
Test Function Name Feature Minimum Search Space
f1 Sphere Unimodal 0 [-100,100]
f2 Rosenbrock Unimodal 0 [-2.048,2.048]
f3 Schwefel P2.22 Unimodal 0 [-10,10]
f4 Quartic Noise Unimodal 0 [-1.28,1.28]
f5 De Jong Unimodal 0 [-1.28,1.28]
f6 Alpine Multimodal 0 [-10,10]
f7 Ackley Multimodal 0 [-32,32]
f8 Schwefel Multimodal 0 [-500,500]
f9 Rastrigin Multimodal 0 [-5.12,5.12]
f10 Noncontinuous Rastrigin Multimodal 0 [-5.12,5.12]
f11 Weierstrass Multimodal 0 [-0.5,0.5]
f12 Penalized 1 Multimodal 0 [-50,50]
f13 Penalized 2 Multimodal 0 [-50,50]

Considering that traditional algorithms have undergone long-term theoretical research and engineering verification, we selected various classic algorithms for comparison, including HHO and new hybrid particle swarm optimization (NHPSO). The main parameters are listed in Table 2. Each algorithm has a population size of 50, the benchmark function dimension is 30, and the final function value is obtained after 5,000 iterations. For each function, the experiment is repeated 50 times to obtain its average and standard deviation. The final results are shown in Table 3, with the best result for each function highlighted in bold. Due to the introduction of the Tent chaotic mapping strategy, nonlinear energy periodic decrease, and adaptive inertia weight, the CACHHO algorithm enhances “search + siege” capability, improves algorithm accuracy, and effectively avoids falling into local optima, performing best on the 5 unimodal functions. Meanwhile, it also performs excellently on multimodal functions, only performing relatively poorly on multimodal functions f14 and f15, but outperforming other algorithms on the remaining multimodal functions. The test data results are plotted as line error bar charts, as shown in the figure below. Across the 13 benchmark test functions, the CACHHO algorithm demonstrates high solving accuracy, with small curve fluctuations and stable performance. In contrast, ABC, WPA, PSO, and ACO have poor accuracy for specific test functions, causing significant fluctuations in their corresponding curves and unstable performance.

Table 2: Comparison Algorithm Parameters
Algorithm Main Parameters
CACHHO μ = 1.999, β = 1.5, k = 2
HHO β = 1.5, E = 2(1 – t/T)
NHPSO w0 = 0.9, w1 = 0.4, c = 1.494, n = 7, m0 = 4
ABC limit = 20
WPA α = 2 – 2t/T
PSO ω = 0.8, c1 = 2, c2 = 2
ACO α = 1, β = 2, ρ = 0.1, Q = 1
Table 3: Test Data Results
Function CACHHO NHPSO HHO ABC WPA PSO ACO
f1 0.00E+00 ±0.00E+00 2.61E-23 ±5.03E-23 0.00E+00 ±0.00E+00 6.40E-15 ±1.41E-16 0.00E+00 ±0.00E+00 1.24E+01 ±9.10E-01 8.30E+02 ±8.47E+01
f2 2.82E-10 ±4.74E-09 2.21E+01 ±1.74E+00 6.05E-08 ±9.12E-08 2.66E+01 ±3.31E+01 2.50E+01 ±2.69E+01 3.05E+01 ±5.92E+01 1.84E+02 ±1.16E+01
f3 0.00E+00 ±0.00E+00 1.12E-15 ±1.39E-15 0.00E+00 ±0.00E+00 1.96E-13 ±7.28E-13 0.00E+00 ±0.00E+00 4.58E+00 ±1.02E+00 4.72E+01 ±9.64E+00
f4 9.66E-07 ±1.33E-08 1.49E-03 ±4.74E-04 4.08E-06 ±4.95E-06 6.15E-01 ±7.55E-01 1.41E-04 ±2.76E-04 1.30E-03 ±4.34E-03 9.58E-03 ±8.39E-03
f5 0.00E+00 ±0.00E+00 6.24E-36 ±1.49E-35 0.00E+00 ±0.00E+00 1.60E+01 ±3.60E+01 0.00E+00 ±0.00E+00 0.00E+00 ±0.00E+00 5.25E+02 ±1.77E+02
f6 0.00E+00 ±0.00E+00 7.93E-12 ±2.52E-11 0.00E+00 ±0.00E+00 1.81E-01 ±5.03E-01 9.40E-323 ±8.30E-324 5.09E-01 ±5.94E-01 7.09E+00 ±2.95E+00
f7 4.44E-16 ±3.93E-15 8.88E-13 ±7.09E-13 9.37E-12 ±9.35E-15 1.79E+00 ±1.12E+00 4.00E-15 ±7.08E-14 5.39E+00 ±6.22E+00 1.79E+01 ±5.31E+01
f8 3.82E-04 ±7.59E-04 1.18E+01 ±3.55E+00 3.86E-04 ±3.56E-05 1.86E+03 ±1.03E+02 6.51E+03 ±8.40E+02 6.30E+03 ±3.61E+02 2.57E+03 ±2.59E+02
f9 0.00E+00 ±0.00E+00 8.93E-08 ±5.01E-07 0.00E+00 ±0.00E+00 1.31E+01 ±6.14E+00 0.00E+00 ±0.00E+00 2.12E+01 ±8.88E+00 1.90E+02 ±7.34E+01
f10 0.00E+00 ±0.00E+00 8.05E-07 ±2.17E-06 0.00E+00 ±0.00E+00 1.89E+01 ±1.96E+00 0.00E+00 ±0.00E+00 3.50E+01 ±5.73E+00 1.21E+02 ±1.96E+01
f11 0.00E+00 ±0.00E+00 0.00E+00 ±0.00E+00 0.00E+00 ±0.00E+00 2.66E-02 ±3.27E-02 0.00E+00 ±0.00E+00 9.39E+00 ±1.77E+00 1.81E+01 ±4.20E+00
f12 6.51E-10 ±5.48E-10 1.05E-24 ±1.65E-24 7.65E-08 ±7.20E-08 3.56E-21 ±3.95E-21 2.32E+01 ±7.12E+00 2.60E+00 ±4.89E+00 1.81E+01 ±7.26E+00
f13 5.16E-10 ±3.97E-10 1.47E-23 ±2.68E-23 2.90E-07 ±9.37E-08 1.07E-15 ±5.66E-14 2.89E-01 ±3.08E-02 1.00E-01 ±2.41E-01 7.04E+03 ±9.44E+01

To further illustrate, we characterize algorithm performance using the number of functions where each algorithm achieves TOP-Z. TOP-1 represents the number of functions where the algorithm obtains the best solution among the 13 test functions, TOP-2 represents the number of functions where it obtains the second-best solution, and so on. Specifically, as shown in the figure below, the proposed CACHHO algorithm’s curve remains above other algorithms, reaching 20 at TOP-3, demonstrating its superior applicability.

CACHHO Algorithm for Multi-Unmanned Aerial Vehicle Cooperative Search Path Planning Experiment

This section applies the proposed CACHHO algorithm to multi-Unmanned Aerial Vehicle cooperative search path planning. The CACHHO algorithm iterates on the waypoints $$(x_{i1}, y_{i1}, x_{i2}, y_{i2}, \ldots, x_{iN}, y_{iN})$$ for the i-th UAV according to Equation (10) to obtain the optimal objective function value. Each Harris hawk in the CACHHO algorithm should have a dimension of 2D, and the i-th UAV obtains the best candidate solutions of other UAVs in each iteration, continuously updating the objective function value to find a flight path that satisfies safety and communication constraints. The specific process is as follows:

Step 1: Initialize parameters for multi-Unmanned Aerial Vehicle cooperative search path planning, including the number of UAVs M, number of waypoints N, start and end points for each UAV, and UAV flight constraints.

Step 2: Initialize the population and parameters of the CACHHO algorithm for the i-th UAV, continuously updating its candidate solution $$(x_{i1}, y_{i1}, x_{i2}, y_{i2}, \ldots, x_{iN}, y_{iN})$$.

Step 3: In each iteration, for the i-th UAV, obtain the best candidate solutions of other UAVs, calculate the cost of each candidate solution, then solve using Equation (10) to obtain F_obj for each scheme.

Step 4: For the i-th UAV, apply Algorithm 1 to update its position in each iteration. If the maximum number of iterations is reached, output the optimal flight scheme for this UAV; otherwise, return to Step 3 to continue iterating.

Experimental Results Analysis

Simulation Experiment Setup

Considering the multi-Unmanned Aerial Vehicle cooperative search path planning problem, we introduce UAV1 to UAV5, totaling 5 UAVs. Detailed positions are listed in Table 4. Assume they fly at the same constant altitude, and speeds can vary. The flight space is defined within [0,100] km, and 5 obstacles (no-fly zones) are set, with detailed types and positions listed in Table 5. All Unmanned Aerial Vehicles take off simultaneously from their start points and arrive at the target position simultaneously.

Table 4: UAV Start and End Points
Coordinate Point UAV1 UAV2 UAV3 UAV4 UAV5
(x0, y0) (20,80) (8,60) (5,47) (5,40) (10,20)
(xd, yd) (85,50) (85,50) (85,50) (85,50) (85,50)
Table 5: Obstacle Types and Positions
Obstacle Number Type Position
Obstacle 1 Circular (20,55), r=6
Obstacle 2 Circular (65,70), r=6
Obstacle 3 Circular (70,40), r=8
Obstacle 4 Rectangular (22,32), l=8, w=11
Obstacle 5 Rectangular (40,60), l=8, w=11

Based on Section 1.3, we construct the multi-Unmanned Aerial Vehicle cooperative search path planning model with specified parameters as follows: The number of waypoints N balances computational cost and approximate solution precision. Generally, larger N increases computational cost but results in smoother and more accurate paths. In this paper, N is set to 10, so with start and target points excluded, there are 8 intermediate waypoints. Thus, when using the CACHHO algorithm, D=16. The number of division evaluation points N_s=5, risk evaluation points N_r=20, maximum turning angle limit θ_max=45°, minimum distance between UAVs d_min is affected by flight speed, set to 0.02 km here. Communication constraint parameters: c=3×10^8 m/s, f_c=2.4 GHz, P_t=26 dBm, P_n=-110 dBm, k=0.1, α=2, SNR_t=2.5. Then, we use the CACHHO algorithm to solve the above model and compare it with other algorithms for analysis. Each algorithm has T_max=500, population size 50, and continues to use the parameters in Table 2.

Experimental Results

Under one experimental scenario, we use the proposed CACHHO algorithm for multi-Unmanned Aerial Vehicle cooperative search path optimization simulation. The experimental results are shown in the figure below. The CACHHO algorithm generates a flyable path, and the turning angles at all waypoints are less than θ_max. If there are local LOS communication clusters among UAVs in the figure, they are represented by dashed connections. Specifically, in Figure (a), when UAVs fly to p1, UAV2 to UAV4 can conduct LOS communication; between UAV1 and UAV2, and between UAV4 and UAV5, due to path loss接近接收灵敏度临界值, they are in weak connectivity; other UAV pairs cannot communicate due to distance or obstacle limitations. When UAVs fly to the second waypoint in Figure (b), between UAV2 and UAV3, and between UAV4 and UAV5, due to additional penetration loss from obstacles, communication is interrupted; direct communication exists between UAV1 and UAV2, UAV1 and UAV3, UAV3 and UAV4, UAV3 and UAV5. It is particularly noteworthy that UAV3 is selected as the topology center, performing accelerated maneuvers to shorten distances between UAVs, playing a key role in this flight. UAV1 increases cruise speed because UAV2 cannot communicate with UAV3, maintaining communication connectivity; UAV5 performs accelerated maneuvers to attempt communication as communication with UAV4 deteriorates; UAV3 primarily flies to find the shortest path. After bypassing obstacles, as shown in Figures (c) to (h), there are no obstacles between all UAVs, and distances remain within LOS communication range, returning to LOS communication mode. Only ensuring flight safety, they find the shortest path to the target position. Finally, as shown in Figure (i), all UAVs successfully complete the search target mission.

To verify the effectiveness of multi-Unmanned Aerial Vehicle cooperative obstacle and collision avoidance, we construct a quantitative evaluation system based on high-resolution discrete sampling. We discretize each UAV’s continuous trajectory into 200 equally spaced evaluation nodes, and by calculating the Euclidean distance between UAVs at each node and the shortest distance from UAV to obstacle boundaries, we achieve dynamic monitoring and statistical verification of safety constraints. Figure 12 shows the distance between each UAV and the 5 obstacles, with the minimum distance to the obstacle boundary labeled. The minimum distances all significantly exceed the safety threshold for rotary-wing UAVs stipulated by the International Civil Aviation Organization (0.3 km), e.g., the closest distance between UAV3 and Obstacle 1 is 0.35 km (safety margin 16.7%), and between UAV5 and Obstacle 3 is 0.41 km (safety margin 36.7%), indicating the algorithm’s excellent path optimization capability in complex obstacle environments. Figure 13 shows the distances between the 5 UAVs. It can be seen that during flight, all UAVs meet the minimum separation requirement for medium UAV formations per NATO STANAG 4676 (≥1.0 km), ensuring flight safety.

This simulation confirms that the CACHHO algorithm effectively addresses the shortcomings of traditional methods in communication constraints and multi-objective dynamic trade-offs. UAV3’s intelligent relay behavior reveals the role of topological communication models in maintaining system robustness, ensuring static obstacle avoidance accuracy while achieving dynamic communication in complex environments, providing quantitative verification basis for reliable cooperation of high-density UAV clusters.

Algorithm Comparison

In this section, to compare the superiority of the CACHHO algorithm, we use different algorithms (parameters refer to Table 2) for repeated experiments. Considering the randomness in the algorithm search process, each algorithm is run 30 times. We use multiple indicators to evaluate the effectiveness of different algorithms in solving this problem and conduct a fair and convincing comparison. The detailed analysis is as follows.

In the algorithm comparison experiment, we selected various group optimization algorithms including standard HHO. Specific experimental data are shown in Table 6 and Figure 14. From the average objective function value (AOFV), optimal objective function value (OOFV), and worst objective function value (WOFV), we observe that the proposed CACHHO algorithm achieves the best objective function value when T_max=500 and population size=50, outperforming previous classic optimization algorithms. The chaotic adaptive mechanism and periodic energy factor introduced in CACHHO enhance global exploration capability (avoiding premature convergence) and dynamic environment adaptability (obstacle/communication constraints), thus obtaining better solutions in multi-objective trade-offs. As the basic algorithm, HHO’s fitness value is inferior to CACHHO, verifying HHO’s exploration-exploitation imbalance in multi-constraint cooperative search. Analyzing from the standard deviation (Std) perspective, CACHHO’s Std value is lower than HHO and other algorithms, indicating that its chaos initialization strategy and adaptive switching mechanism effectively suppress algorithm randomness, meeting the stringent stability requirements of high-dimensional optimization problems. Simultaneously, using the ACO algorithm as a benchmark, we quantify the performance improvement of each algorithm through the improvement percentage (IP). CACHHO’s optimization accuracy improved by 25.39% and 8.67% compared to ACO and HHO, respectively. Through analysis, we prove CACHHO’s advantage in communication-motion strongly coupled scenarios, demonstrating the algorithm’s multi-objective collaborative optimization capability, successfully completing the multi-Unmanned Aerial Vehicle cooperative search path optimization task in complex environments.

Table 6: Algorithm Comparison Results
Parameter CACHHO HHO ABC WPA PSO ACO
AOFV 89.12 97.58 102.41 102.72 104.27 119.44
OOFV 80.182 86.65 90.38 93.81 96.73 106.25
WOFV 103.60 111.44 126.30 125.32 129.60 150.41
Std 2.88 3.79 5.22 4.71 5.07 6.20
IP/% 25.39 18.30 13.26 14.00 12.70
Task Completion Rate/% 83 60 63 57 60 53

In addition to the optimality of calculation results, task success rate is also an important indicator for evaluating algorithm performance. Task success rate means that all Unmanned Aerial Vehicles can find flight paths that meet the constraints, i.e., the objective function value is the flight path length. Detailed data are shown in Figure 15. CACHHO has the highest task success rate among all comparison algorithms, 23% higher than the standard HHO algorithm, reflecting the algorithm’s effectiveness in the multi-objective optimization framework and further demonstrating the significant advantage of CACHHO-based multi-Unmanned Aerial Vehicle cooperative search path optimization.

Conclusion

This paper primarily studies the multi-Unmanned Aerial Vehicle cooperative search path optimization problem under complex constraint coupling. Different from traditional single-dimensional methods considering only geometric path optimization, we introduce a dynamic weight mechanism for LOS and NLOS communication, constructing a decision paradigm based on communication-motion joint optimization. Then, we introduce weight factors to balance different constraints and design the corresponding overall objective function. Subsequently, we propose the CACHHO algorithm to solve the multi-Unmanned Aerial Vehicle cooperative optimization path problem. Through Tent chaotic mapping, periodic escape energy factor decrease, and position update weight factors, we effectively improve convergence accuracy while ensuring convergence speed, enhancing algorithm performance. We demonstrate the superiority of our algorithm through benchmark function tests and multi-Unmanned Aerial Vehicle cooperative path optimization simulation experiments, achieving the goal from “single-objective optimization” to “multi-constraint dynamic balance”. Finally, simulation experiment comparisons show that the proposed CACHHO algorithm has significant advantages over other methods in optimizing high-quality flyable paths for multiple Unmanned Aerial Vehicles. Next, we will consider the impact of UAV real complex tasks and flight speeds, angular velocities on multi-Unmanned Aerial Vehicle cooperative search, and conduct further research on multi-UAV complex search task problems.

Scroll to Top