Next Article in Journal
Multi-Objective White Shark Optimizer for Global Optimization and Rural Sports-Facilities Location Problem
Previous Article in Journal
Grid-Based Path Planning of Agricultural Robots Driven by Multi-Strategy Collaborative Evolution Honey Badger Algorithm
Previous Article in Special Issue
Bio-Inspired Design of Mechanical Properties of Hybrid Topological Cellular Honeycomb Structures
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment

Logistics Engineering College, Shanghai Maritime University, Shanghai 201306, China
*
Author to whom correspondence should be addressed.
Biomimetics 2025, 10(8), 536; https://doi.org/10.3390/biomimetics10080536
Submission received: 19 June 2025 / Revised: 12 August 2025 / Accepted: 13 August 2025 / Published: 15 August 2025
(This article belongs to the Special Issue Computer-Aided Biomimetics: 3rd Edition)

Abstract

Aiming at the cooperative path-planning problem of multiple autonomous underwater vehicles in underwater three-dimensional terrain and dynamic ocean current environments, a hybrid algorithm based on the Improved Multi-Objective Particle Swarm Optimization (IMOPSO) and Dynamic Window (DWA) is proposed. The traditional particle swarm optimization algorithm is prone to falling into local optimization in high-dimensional and complex marine environments. It is difficult to meet multiple constraint conditions, the particle distribution is uneven, and the adaptability to dynamic environments is poor. In response to these problems, a hybrid initialization method based on Chebyshev chaotic mapping, pre-iterative elimination, and boundary particle injection (CPB) is proposed, and the particle swarm optimization algorithm is improved by combining dynamic parameter adjustment and a hybrid perturbation mechanism. On this basis, the Dynamic Window Method (DWA) is introduced as the local path optimization module to achieve real-time avoidance of dynamic obstacles and rolling path correction, thereby constructing a globally and locally coupled hybrid path-planning framework. Finally, cubic spline interpolation is used to smooth the planned path. Considering factors such as path length, smoothness, deflection Angle, and ocean current kinetic energy loss, the dynamic penalty function is adopted to optimize the multi-AUV cooperative collision avoidance and terrain constraints. The simulation results show that the proposed algorithm can effectively plan the dynamic safe path planning of multiple AUVs. By comparing it with other algorithms, the efficiency and security of the proposed algorithm are verified, meeting the navigation requirements in the current environment. Experiments show that the IMOPSO–DWA hybrid algorithm reduces the path length by 15.5%, the threat penalty by 8.3%, and the total fitness by 3.2% compared with the traditional PSO algorithm.

1. Introduction

Autonomous Underwater Vehicles (AUVs) have become indispensable tools in modern marine applications such as oceanographic surveys, environmental monitoring, seabed mapping, and search-and-rescue operations [1]. The emergence of multi-AUV systems has significantly enhanced mission efficiency and fault tolerance by enabling distributed task execution. However, planning safe, efficient, and cooperative paths for multiple AUVs in a dynamic underwater environment remains a major challenge. This problem is inherently high-dimensional, nonlinear, and constrained, often involving multiple objectives such as minimizing energy consumption, avoiding inter-vehicle collisions, evading obstacles, and maximizing task coverage [2].
The proposed path-planning methods at present can be roughly divided into four major categories. Classic graph-based algorithms, such as A* [3] and Dijkstra [4], are still widely used because they can calculate the global optimal path on discrete mappings. However, their computing costs limit their applicability in large-scale or real-time multi-AUV systems. Sampling-based methods, including Probabilistic Roadmap [5] and Rapidly Exploring Random Trees [6], can effectively explore high-dimensional space. However, they often generate suboptimal or unstable paths and have limited adaptability to dynamic environments. Based on optimization methods, such as nonlinear programming [7] and dynamic programming [8], continuous control with constraints and precise modeling is provided, but they have the disadvantages of high dimensionality and high computational cost. This makes them unsuitable for online or multi-agent scenarios. In addition, optimization-based algorithms also include meta-heuristic algorithms inspired by nature, such as genetic algorithms [9], ant colony optimization [10], and particle swarm optimization [11]. Due to their flexibility and strong global search capabilities, they are widely popular. In the past two years, a variety of new meta-heuristic methods have emerged. For example, the IMOSBOA proposed by Tang et al. [12] addresses environmental and threat uncertainties in AUV 3D path planning, while the AI-SMA proposed by Ma et al. [13] effectively improves the performance of UAV swarm path planning through an adaptive perturbation strategy. Among them, the particle swarm optimization algorithm has the advantages of simplicity and fast convergence, and is particularly suitable for multi-AUV path planning.
In recent years, machine learning methods have shown increasing potential in path planning in complex environments. Puente-Castro et al. [14] proposed an efficient path-planning method for unmanned aerial vehicle (UAV) swarms with dense obstacles based on Q-learning. Liu et al. [15] designed a deep reinforcement learning framework that combines hybrid heuristic search with policy learning, which improves the quality of real-time paths and control efficiency. Tao et al. [16] introduced an adaptive soft Actor-Critic architecture for local path planning in dynamic environments, emphasizing policy adaptability and obstacle-aware decision-making to ensure smooth and collision-free trajectories.
Recent studies have improved the particle swarm optimization algorithm. Babakhani et al. [17] combined the penalty function with particle swarm optimization technology, which can effectively handle the complex constraints in real marine environments and improve the applicability and accuracy of AUV motion planning. However, its penalty function parameters are highly sensitive, and its application effect in high-dynamic marine environment scenarios may be limited. Wang et al. [18] integrated PSO with the adaptive step-size cuckoo search algorithm, taking into account both global optimization ability and local search accuracy, thereby enhancing the efficiency and robustness of path planning for AUVs in the complex 3D underwater environment. However, its adaptive step-size parameter adjustment mechanism is rather complex, and the convergence speed in high-density obstacle scenarios needs to be optimized. Zhi et al. [19] proposed AMP-PSO, which divided particles into dominant subgroups and follower subgroups and introduced an inter-group exchange mechanism to handle multi-AUV cooperative tasks. It outperformed the classical PSO and other improved methods in simulation, but the mechanism was complex, with many parameters and great difficulty in parameter adjustment. Wang et al. [20] combined Levy flight and orthogonal learning strategies with PSO to systematically mine population historical information. Their optimization accuracy was improved by 2–3 orders of magnitude compared to traditional PSO, and the convergence speed was accelerated by 40%. However, the robustness in dynamic environments still needs to be verified. The random jump characteristic of Levy’s flight may lead to a decrease in path smoothness.
Despite these advantages, standard PSOs lack real-time response capabilities, which are crucial in dynamic underwater environments. For dynamic environments with real-time constraints, online optimization techniques have certain advantages in terms of responsiveness. The Model Predictive Control (MPC) framework achieves rolling horizontal re-programming by solving constrained optimization problems within a limited time window. Liu et al. [21] proposed a real-time reward collection framework for unmanned aerial vehicles based on online optimization, achieving dynamic obstacle response optimization through moving time-domain approximation. Chen et al. [22] proposed a trajectory planning scheme based on online optimization for the problem of heterogeneous multi-robot cooperative landing tasks. Combined with the MPC framework, the optimization problem was solved by rolling in the finite time domain, achieving the real-time replanning capability with high responsiveness. In addition, the dynamic window method [23] has the characteristics of low computational cost and strong real-time performance. It calculates feasible motion instructions within a limited time window by evaluating dynamic constraints and obstacle distances. The adaptability of DWA to underwater robots includes water flow sensing planning [24], real-time obstacle avoidance [25], and cooperative tracking in dynamic environments.
In parallel, the rise of biomimetics—the design and application of systems modeled on biological entities—has injected new vitality into the development of intelligent underwater robotics. Marine animals exhibit remarkable efficiency, adaptability, and robustness in navigating complex aquatic environments. The schooling behavior of fish, the hunting strategies of cephalopods, and the long-distance foraging patterns of seabirds have inspired new methods for group coordination, collision avoidance, and energy-efficient movement in multi-AUV systems. By mimicking these natural behaviors, engineers have developed control strategies and path-planning algorithms that capitalize on the emergent intelligence and adaptability inherent in biological systems.
Among bioinspired techniques, Levy flight [26]—a random walk pattern observed in the foraging behavior of animals like albatrosses and fruit flies—has gained traction for its capacity to balance global exploration with local exploitation in optimization tasks. When integrated with swarm intelligence frameworks such as PSO, Levy flight enhances the algorithm’s ability to escape local optima and explore diverse solution spaces [27]. Additionally, biologically inspired mechanisms like differential mutation and adaptive learning from collective behaviors have further improved swarm diversity and convergence performance in dynamic, high-dimensional environments. These biomimetic enhancements not only provide theoretical grounding for improved performance but also offer practical advantages for path planning in the unpredictable and obstacle-rich domains where AUVs operate.
This paper proposes a hybrid PSO-DWA framework that integrates global trajectory optimization with real-time local trajectory planning. The uniqueness of the PSO improvement strategy proposed in this paper is reflected in three aspects: Firstly, compared with Zhang et al. [28] who only rely on real-time adjustment of ocean currents, this paper adopts a hybrid initialization mechanism that integrates Chebyshev chaotic mapping, pre-iterative transient elimination, and boundary particle injection to solve the problem of uneven particle distribution in high-dimensional terrain in traditional PSO. Secondly, a dynamic parameter adaptive mechanism is introduced to overcome the response lag of static parameters, such as Lin et al. [29] in dynamic obstacle scenarios by introducing an inertia weight index attenuation and asymmetric learning factors. Finally, to avoid the convergent oscillation problem caused by the single Levy strategy adopted by Sutantyo et al. [30], this paper innovatively employs a hybrid perturbation strategy combining Levy flight and differential variation. A multi-objective DWA cost function is designed by integrating obstacle distance, trajectory smoothness, and energy efficiency metrics. Additionally, collaborative strategies such as track prediction, communication topology management, and coordinated collision avoidance are employed to ensure safe and efficient multi-AUV path planning.

2. Underwater Environment Modeling

2.1. Underwater Terrain Environment Modeling

Compared with the land topography formed by crustal movement and weathering erosion, the seabed topography is mainly influenced by seabed volcanic activities and deep-sea sedimentation. Although there are many differences between the seabed topography and the land topography in terms of geomorphic features and environmental conditions, the two still have certain similarities in aspects such as formation mechanisms. Therefore, the land-based mountain model can be used to represent the seabed topography [31].
The complex terrain environment of this study consists of the reference terrain and various types of static obstacles. The modeling of the reference terrain is generated by superimposing multi-scale waveforms, namely trigonometric functions. Meanwhile, to simulate the irregularity of the real terrain, Gaussian white noise is superimposed, and the noise intensity is amplified to simulate the terrain features covering different scales [32]. Its mathematical description is as follows:
H b a s e ( x , y ) = s i n ( y + 10 ) + 0.2 s i n ( x ) + 0.1 c o s ( 0.6 x 2 + y 2 ) + 1.1 c o s ( y ) + s i n ( 0.1 x 2 + y 2 ) + N ( 0 , σ 2 )
where ( s i n ( y + 10 ) ) represents the longitudinal main wave, the periodic undulation of the dominant terrain along the Y-axis direction, and a phase offset of 10 units simulates asymmetric terrain. ( 0.2 s i n ( x ) ) represents the lateral fine-tuning wave, superimposing small amplitude fluctuations in the X-axis direction to form lateral micro-terrain changes. 0.1 c o s ( 0.6 r ) represents radial mesoscale fluctuations, annular ripples centered on the origin, and simulates moderate-scale terrain undulations. ( 1.1 c o s ( y ) ) represents the longitudinal cosine wave. To enhance the symmetry of the terrain in the Y-axis direction and form an alternating ridge and valley structure. ( s i n ( 0.1 r ) ) represents global low-frequency ripples, long-wavelength global fluctuations, and simulates macroscopic terrain trends. N ( 0 , σ 2 ) represents the Gaussian distribution random field. The noise amplitude is approximately 200% of the main wave amplitude of the terrain, significantly increasing the microscopic roughness.
Reference [33] proposes an enhanced dynamic artificial potential field method for the three-dimensional path planning of multi-rotor unmanned aerial vehicles. Terrain modeling is carried out using the sine wave superposition model. However, the sine wave superposition model is more suitable for simulating a large-scale and periodically changing environment. Therefore, the following mathematical model is adopted in this paper to describe the submarine mountains:
H p e a k i ( x , y ) = h i p · e x p ( ( x x i p ) 2 2 ( σ i x ) 2 ( y y i p ) 2 2 ( σ i y ) 2 )
where H p e a k i ( x , y ) represents the terrain height distribution function of the obstacle on the i-th mountain peak; ( x i p , y i p ) represents the center coordinates of the mountain peak, h i p is the peak height of the ith mountain peak in meters, σ i x and σ i y are the attenuation coefficients in the x-direction and y-direction, respectively, which are used to control the steepness of each layer of the mountain ground.
Furthermore, set up a height model of the composite terrain. A highly complex and high-fidelity virtual seabed terrain environment is constructed by nonlinearly superimposing the basic terrain features of multiple Gaussian mixture models [34]. The formula is as follows:
H t o t a l ( x , y ) = m a x ( H b a s e ( x , y ) , max i = 1 N m H p e a k i ( x , y ) ) + N ( 0 , 0.5 ) )
where H b a s e is the reference terrain elevation, and the mountain peak area forms natural obstacles through elevation superposition. H p e a k i is the height field of the i-th obstacle, and N is the Gaussian noise introduced for superposition to simulate the roughness of the seabed.

2.2. Obstacle Modeling

In addition to specific submarine topography modeling, obstacles, as impassable or evasive areas in the environment, directly affect the feasibility and superiority of the path. Obstacles can be roughly divided into static obstacles and dynamic obstacles.

2.2.1. Static Obstacle Modeling

Static obstacles refer to those whose positions and shapes remain unchanged during the path-planning process. Therefore, the topography of submarine mountains can be regarded as a kind of broad static obstacle. In addition to mountains, the underwater environment also features natural obstacles such as reefs and functional obstacles for detecting sonar. Therefore, in this study, the threat areas of obstacles such as reefs are modeled and processed, and their shapes are approximately cuboids. The threat areas formed by monitoring systems such as sonar are modeled, and their shapes are approximately cylinders. The mathematical expressions of the two threat areas are:
O c y l = H j c i f ( x x j c ) 2 + ( y y j c ) 2 R j 2 H ( x , y ) o t h e r w i s e
where O c y l is the original terrain elevation function, ( x j c , y j c ) is the center coordinate of the cylindrical obstacle, R j is its radius, and H j c is its height. The forced elevation within the cylindrical area is Hic, forming an impassable vertical obstacle.
O r e c t = H k r if x k r x x k r + L k x and y k r y y k r + L k y H ( x , y ) o t h e r w i s e
where O r e c t is the original terrain elevation function, ( x k r , y k r ) is the lower left corner coordinate of the cuboid obstacle, L k x and L k y are the length and width of the cuboid, respectively, and H k r represents its height. Define the elevation within the rectangular area as a fixed value H k r to simulate artificial obstacles such as buildings. The terrain model, mountain peak model, and static obstacle model of this paper are shown in Figure 1, respectively.

2.2.2. Dynamic Obstacle Modeling

Unlike static obstacles, dynamic obstacles refer to those whose positions and states change over time during the execution of tasks by the AUV. Common representatives include natural dynamic disorders dominated by fish schools and functional dynamic disorders dominated by unmanned ships. Therefore, although the modeling and obstacle avoidance strategies of dynamic obstacles are more challenging, they are also more in line with reality and have extremely high practical application significance. In most task scenarios, dynamic obstacles have a greater impact on path planning than static obstacles.
Just as the movement of fish schools follows the principles of fluid mechanics and self-organization [35], and the trajectories of unmanned ships are influenced by the wave spectrum model [36]. The motion of dynamic obstacles follows Newton’s second law F = m a , and its acceleration is composed of three parts:
a. Tendency term κ · p i e n d p i ( t ) p i e n d p i ( t ) : Simulates goal-oriented behavior, κ is the gain coefficient trend.
b. Damping term γ · v i ( t ) : characterization of fluid resistance ( γ = 1 2 C d ρ A v , C d is the coefficient of resistance.)
c. Disturbance term ξ a ( t ) : Environmental random perturbation ( ξ a N ( 0 , Σ ) , Σ = diag ( 0.2 , 0.2 , 0.1 ) )
This model can accurately describe the characteristics, such as the fish school’s feeding behavior ( κ term) and the influence of wave surges on unmanned vessels ( ξ a term).
The dynamic obstacles in the environment are uncertain and time-varying, which puts forward higher requirements for the real-time perception, rapid planning, and dynamic adjustment of path planning. The dynamic obstacle model in this paper incorporates acceleration and random perturbations. The specific formula is as follows:
R o b s = C
where R o b s is the parameter shared by all dynamic obstacles, representing the minimum safe distance from the AUV after defining the dynamic obstacle as a sphere with a fixed collision radius. After that, define the motion equation of the dynamic obstacle. The position formula is as follows:
P i i n i t = ( x i i n i t , y i i n i t , z i i n i t )
P i g o a l = ( x i g o a l , y i g o a l , z i g o a l )
where P i i n i t and P i g o a l , respectively, represent the initial position and target position of the ith obstacle.
The dynamic obstacle model in this paper is a dynamic obstacle model that incorporates acceleration and random disturbances. To simulate the non-uniform motion characteristics of dynamic obstacles, the acceleration is defined as follows:
a i ( t ) = κ · p i end p i ( t ) p i end p i ( t ) γ · v i ( t ) + ξ a ( t )
where a i is the tendency term, driving the obstacle to move towards the target point, and κ is the tendency gain coefficient; γ is the damping coefficient; ξ a is the random disturbance term, which follows a Gaussian distribution with a mean of zero and a covariance matrix of a , and is used to simulate environmental disturbances. Then, define the velocity update equation. Let the speed adjust dynamically with the acceleration and superimpose random noise. The formula is as follows:
v i ( t + Δ t ) = v i ( t ) + a i ( t ) · Δ t + σ v · N v ( t )
where σ v is the amplitude vector of velocity perturbation, and N v is the random variable of the standard normal distribution. Afterwards, the position is updated jointly by velocity and acceleration, and a position perturbation is introduced. The position update equation is as follows:
p i ( t + Δ t ) = p i ( t ) + v i ( t ) · Δ t + 1 2 a i ( t ) · ( Δ t ) 2 + σ p · N p ( t )
where p i represents the position at time t, v i represents the velocity at time t, Δ t represents the time step, a i represents the acceleration at time t, σ p represents the standard deviation of the position disturbance, and N p represents the random noise term related to the position.
Then, add a motion constraint condition to limit the height of the obstacle to ensure that it does not touch the seabed terrain. The safe depth threshold Δ h s a f e is the threshold for the safe descent depth of the AUV. These constraint conditions also ensure consistency with the modeling of static obstacles, allowing dynamic obstacles to exist reasonably in three-dimensional space.
z i ( t ) H b a s e ( x i ( t ) , y i ( t ) ) + Δ h s a f e
where H b a s e is the terrain elevation function, and Δ h s a f e is the safe height margin.

2.3. Ocean Current Model with Complex Vortices

In the actual navigation of AUVs, due to the limitations of the equipment itself, there are extremely high requirements for the energy consumption and navigation trajectory of underwater vehicles. Since the actual underwater environment is not constant, ocean currents and vortices fill it, resulting in an increase in the energy consumption of the AUV and an increase in trajectory deviation. In order to be closer to the actual situation, the factor of ocean currents should be considered in the path planning. In underwater AUV path planning, the ocean current field is usually three-dimensional and can exhibit different velocity and flow direction characteristics at different depths. To meet the requirements of hierarchical modeling, we can stratify the flow of the fluid, that is, apply the Navier–Stokes equation, respectively, on different water layers. In this paper, the following Navier–Stokes equation is introduced to model the underwater ocean current field [37]:
ρ u i ( x , y , z ) t + ρ u i ( x , y , z ) · u i ( x , y , z ) = p i ( x , y , z ) + μ 2 u i ( x , y , z )
where ρ i is the fluid density of the i-th layer, u i is the vector of the fluid velocity field of the i-th layer, p i is the fluid pressure field of the i-th layer, μ i is the dynamic viscosity of the fluid in the i-th layer, and p i is the pressure gradient of the i-th layer, reflecting the change in fluid pressure. 2 u i is the viscosity term of the i-th layer, which describes the viscous effect within the fluid. The specific modeling of the field of the ocean current is shown in Figure 2.

3. Improved Multi-Objective Particle Swarm Optimization Algorithm

The complex marine environment described in the second part—including irregular seabed topography, dynamic obstacles with uncertain trajectories, variously distributed ocean currents, and the need for coordination among multiple autonomous underwater vehicles—poses significant challenges to the traditional particle swarm optimization algorithm. These challenges include premature convergence in rugged terrain, insufficient response to moving threats, a decline in community diversity under current interference, and an inability to maintain a safe distance between multiple AUVs. To overcome these limitations, the improved multi-particle swarm optimization algorithm in this paper introduces three key innovations: the CPB initialization strategy that combines Chebyshev chaotic mapping, pre-iteration transient elimination, and boundary particle injection enhances population diversity to avoid local optima, and this strategy significantly improves the search efficiency and solution quality of the autonomous underwater vehicle path-planning task through enhancing the diversity and coverage of the initial population; the dynamic parameter adaptive mechanism balances exploration and exploitation under current interference; the hybrid Levy-differential perturbation can avoid dynamic obstacles in real time, and through ARIMA-guided particle injection ensure coordinated safety.

3.1. The Initialization Method of Hybrid Particle Swarm Based on CPB Method

3.1.1. Hybrid Chaotic Initialization

In the path-planning application of the particle swarm optimization algorithm, the initialization strategy of the particle swarm directly affects the search performance, convergence speed, and the quality of the solution of the algorithm [38]. At present, in the initialization process of the particle swarm optimization algorithm, strategies such as random sampling, linear interpolation, and Latin hypercube sampling are commonly adopted. These traditional methods have high computational efficiency, are easy to implement, and are suitable for general low-dimensional optimization scenarios. However, in the underwater dynamic path-planning task of multi-AUV systems, these initialization methods have exposed several deficiencies.
In recent years, chaotic mapping, as an effective improvement method of swarm intelligence algorithms, has been widely applied in the initialization stage of optimization algorithms due to its advantages, such as strong ergodic ability, good pseudo-randomness, and high initial value sensitivity. Commonly used chaotic mappings include the Logistic mapping, Tent mapping, sine mapping, etc. However, these traditional chaotic mapping models still face some challenges in the dynamic path-planning task [39]. On the one hand, the sequences they generate have limited coverage ability in the boundary region of the search space, resulting in insufficient exploration of edge paths by the particle swarm during the dynamic obstacle avoidance process. On the other hand, these mapping models have fixed control parameters and insufficient adaptability, making it difficult to respond dynamically to complex environmental changes.
Therefore, this paper proposes a strategy for initializing the improved Chebyshev chaotic map using the dynamic order adjustment mechanism and the boundary enhancement operator. The iterative formula of the traditional Chebyshev mapping is as follows:
x k + 1 = cos n · arccos ( x k ) , x k [ 1 , 1 ]
The traditional research on chaotic mapping mainly focuses on static optimization problems. Although the chaotic sequence it generates has ergodicity, in dynamic path planning, there are still problems such as the N-order fixation (usually taking 2 or 4) in traditional methods, which makes it difficult to adapt to dynamic obstacles and ocean current disturbances. There are problems, such as insufficient boundary sensitivity in multi-AUV cooperative obstacle avoidance, which cannot meet the requirements of edge path detection. Therefore, this paper first adopts the dynamic order adjustment mechanism to adaptively adjust the order n according to the environmental complexity. The formula is as follows:
n = 2 + 3 · ρ m a x ρ o b s
where ρ o b s is the real-time obstacle density, and ρ m a x is the preset maximum obstacle density. It effectively addresses the problems of excessive randomization and decreased convergence speed caused by using high chaotic intensity in the traditional fixed-order Chebyshev mapping in dynamic underwater scenes, as well as the insufficient diversity and increased obstacle avoidance failure rate caused by the use of low chaotic intensity. Through the dynamic switching of order n, the algorithm exhibits differentiated search behaviors in different regions. In the obstacle area, local disturbances have been enhanced, the ability to evade local optima has been improved, and the potential for obstacle avoidance has been strengthened. In the sparse area of obstacles, the chaotic intensity is reduced, a smooth sequence is generated, the global optimum is rapidly approached, and convergence is accelerated.

3.1.2. Pre-Iterative Transient Elimination

In the initial iteration stage of chaotic mapping, there will be a non-equilibrium state before the system transitions from the initial value to the steady-state chaos, that is, the transient phenomenon. At this stage, the sequence has problems such as insufficient coverage of the solution space by the sequence, resulting in insufficient ergodicity and strong correlation between adjacent values, and destroying pseudo-randomness. Therefore, this paper proposes a pre-iterative elimination mechanism. Its formula is as follows:
x 0 U ( 1 , 1 ) x p r e ( m ) = f ( x p r e ( m 1 ) ) , m = 1 , 2 , , M p r e X i = ϕ ( x p r e ( M p r e ) )
where x 0 represents the initial value of the chaotic mapping, which is a uniformly randomly generated vector within the interval of [−1, 1]. x p r e is the chaotic value after pre-iteration. X i represents the position vector of the i-th particle in the solution space. M p r e represents the number of pre-iterations, that is, the number of iterations for performing the chaotic mapping before officially initializing the particle swarm using the chaotic sequence. This process can eliminate the transient effect by transitioning the chaotic system from the initial value to the steady-state chaotic state through a sufficient number of pre-iterations, making the steady-state chaotic sequence have higher randomness and ergodicity, and improving the sequence quality [40]. Among them, the expression of ϕ is
ϕ ( x ) = x + 1 2 · ( u b l b ) + l b
where l b represents the lower bound of each dimension in the solution space, that is, the minimum value of the optimization variable. u b represents the upper bound of each dimension in the solution space, that is, the maximum value of the optimization variable. This formula defines the search space for the feasible range of particle positions. In addition, map the chaotic sequence to the actual solution space.

3.1.3. Boundary Particle Injection

The traditional PSO algorithm relies on randomly generating particles, and the probability of particle generation in the boundary region of the solution space is extremely low. Therefore, injecting boundary particles can prevent the algorithm from ignoring these regions due to the insufficient randomness of the initial population. However, in high-dimensional or complex constraint problems, the optimal solution may be located at the boundary of the solution space. Meanwhile, although Chebyshev mapping generates uniform sequences, under high-dimensional or dynamic constraints, boundary coverage may still be insufficient [41]. Therefore, this paper proposes a boundary particle injection strategy that dynamically adjusts the positions and quantities of injected particles according to real-time environmental changes. Let the characteristic vector of the environmental state at time t be the following formula
E ( t ) = ρ o b s ( t ) , v c u r r e n t ( t ) , H m a p ( t ) T
where E represents the characteristic vector of the environmental state at time t, ρ o b s represents the density of obstacles, v c u r r e n t represents the ocean current velocity field, and H m a p represents the dynamic terrain elevation. Then define the number of injected boundary particles as follows:
N b o u n d a r y ( t ) = N b a s e + k · ρ m a x ρ o b s ( t )
where N b o u n d a r y represents the number of injected particles, N b a s e represents the number of fundamental particles with fixed upper and lower bound vertices, k is the sensitivity coefficient, and ρ m a x is the preset maximum obstacle density threshold. This step can inject more particles to enhance the edge exploration ability when obstacles are denser. Next, the Voronoi diagram is constructed, and the formula is as follows.
V ( o i ) = x R 2 | x o i x o j , j i
where both o i and o j are in the set of obstacle positions O = { o 1 , o 2 , , o M } . Furthermore, the edge set E represents the boundary line between adjacent Voronoi regions. Then, for each edge e E , calculate the minimum width. The formula is as follows:
W ( e ) = min x e x o i + x o j , o i , o j O
Then, the key channel screening is carried out. The candidate edge set of the injected particles is represented by the following formula:
E c r i t i c a l = e E | W s a f e W ( e ) 2 W s a f e
where E c r i t i c a l represents the candidate edge set of the injected particles, and W s a f e represents the safe passage width of the AUV. Then, highly dynamic constraints are used to adjust the vertical coordinate z i according to the real-time terrain. The formula is as follows:
z i = max H m a p ( x i , y i ) + Δ h m i n , min z r a w , H m a p ( x i , y i ) + Δ h m a x
where z r a w is the height value generated by the original chaotic mapping, and Δ h m i n and Δ h m a x are the safe height ranges. Then, dynamic adjustment and optimization are carried out, using the prediction-correction mechanism. First, the autoregressive integral moving average model is used to predict the environmental state of the future T p step, and its formula is as follows:
E ^ ( t + T p ) = i = 1 p ϕ i E ( t i ) + j = 1 q θ j ϵ ( t j ) + ϵ ( t )
where ϕ i and θ j represent the model parameters, and ϵ is the white noise element. p and q represent the order of the autoregressive and moving average, respectively. E is the historical value of the time series. Next, the correction of the position of the particles is carried out, and the predicted values are corrected based on the actual observed values. The formula is as follows.
x i ( t ) = α x ^ i ( t ) + ( 1 α ) x i o b s , α [ 0 , 1 ]
where x i represents the predicted position, x i o b s represents the actual observed position, and α represents the control prediction trust degree. Finally, the multi-objective scoring function is defined as:
S ( x i ) = w 1 · 1 W ( x i ) + w 2 · ρ o b s ( x i ) + w 3 · v c u r r e n t ( x i )
where S is the critical score of particle x i , W represents the width of the channel where it is located, and w 1 , w 2 , w 3 are the weight coefficients, which satisfy the sum of 1. Finally, the weight is adaptively adjusted to dynamically optimize the weight based on the performance of the historical path. The formula is as follows:
w j ( t + 1 ) = w j ( t ) + η · J w j
where η represents the learning rate and J represents the path quality index. Its value is equal to the weighted sum of length, energy consumption, and safety margin.

3.2. Dynamic Adaptive Parameter Adjustment

The traditional PSO algorithm adopts a fixed parameter configuration. However, fixed static parameters cannot meet the requirements of different stages of the search process, which is prone to problems such as slow convergence in the early stage or oscillation in the later stage, and difficulty in dealing with complex marine environments, such as dynamic obstacles and time-varying ocean currents. Therefore, the inertial weight exponential attenuation mechanism is introduced, and its formula is as follows:
ω ( t ) = 0.4 + 0.5 · e 3 t T m a x
where ω is the inertia weight and T m a x is the maximum number of iterations. When t < 0.2 T m a x , it is the initial stage. The particles maintain high-speed movement and enhance the global exploration ability. When 0.2 T m a x < t < 0.7 T m a x , it is the transitional stage, balancing exploration and development. When 0.7 T m a x < t, it is the later stage, allowing the particles to accelerate and converge to the optimal solution. Then, the asymmetric learning factor design is used, and its formula is as follows:
c 1 ( t ) = 2.0 1.5 · t T m a x c 2 ( t ) = 0.5 + 1.5 · t T m a x
where c 1 is the individual learning factor and c 2 is the social learning factor. When C 1 > C 2 , it is the period dominated by individual cognition, and particles are encouraged to explore the historical optimal region of the individual. When C 1 < C 2 , it is the period dominated by social cognition, promoting the information sharing of particle groups. This method can effectively increase the convergence speed and improve the convergence efficiency.

3.3. Hybrid Perturbation Strategy

In order to effectively reduce the problems such as premature convergence, diversity attenuation, and dynamic response lag of traditional PSO. This paper proposes a hybrid perturbation strategy combining Levy flight and differential variation.

3.3.1. Levy Flight Disturbance

The Levy flight perturbation is used as the dominant factor for global exploration, and its formula is as follows:
Δ x = 0.01 · u | v | 1 / β
where Δ x is the perturbation step-size vector, β is the Levy index, which is generally taken as 1.5, and u and v are random number generators. Its expression is as follows:
u N ( 0 , 1.5 ) v N ( 0 , 1 )

3.3.2. Differential Mutation Strategy

In order to solve the problems of particle aggregation in the later stage of iteration, which causes the entropy value to drop to the danger zone, and the fact that traditional PSO is prone to stagnation in flat terrain and lacks gradient information, this paper introduces the differential mutation strategy, and its mutation formula is as follows:
x m u t = g b e s t + 0.1 · ( x r 1 x r 2 )
where x m u t is the new position after mutation, g b e s t is the global historical best position, x r 1 and x r 2 are randomly selected particle positions, and it is forced that r 1 r 2 i to avoid invalid differences.

4. Improved Dynamic Window Approach

4.1. Adaptive Dynamic Window Generation

Traditional DWA adopts a fixed-resolution velocity window. Therefore, in complex scenarios, there will be problems such as insufficient trajectory coverage in obstacle-dense areas or redundant calculations due to the inability of the fixed resolution to capture the feasible paths of narrow channels. Therefore, this paper adopts the strategy of dynamically adjusting the angular velocity resolution, and its formula is as follows:
Δ ω ( t ) = Δ ω b a s e · 1 + ρ o b s ( t ) ρ max
where ω b a s e represents the basic resolution, ρ o b s represents the local obstacle density, and ρ m a x represents the density threshold. This formula can dynamically adjust the environmental perception resolution, improve the path discovery rate in complex areas, and optimize the computational efficiency, reducing trajectory evaluations in simple scenarios.

4.2. Multi-Objective Optimization Cost Function

The traditional dynamic window method usually only optimizes the target proximity and obstacle avoidance distance. However, in complex scenarios, the failure to consider motion smoothness may lead to path jitter. The optimization of a single target is prone to falling into suboptimal solutions and cannot globally balance the multi-dimensional performance. Therefore, a single goal or a few goals cannot meet the actual needs. This paper introduces a multi-objective cost function that comprehensively evaluates trajectory safety, efficiency, smoothness, and energy consumption:
C t o t a l = j = 1 4 w j ( t ) C j
where C t o t a l represents the total cost function, which is used to evaluate the global advantages and disadvantages of candidate trajectories, enabling the algorithm to balance safety, efficiency, smoothness, and energy consumption when choosing paths. w j represents the time-varying weight of the jth term. C j represents the jth sub-cost item, corresponding to four optimization objectives. C 1 stands for C g o a l , representing the closeness to the goal. C 2 stands for C o b s , representing the obstacle avoidance distance. C 3 stands for C s m o o t h , representing the smoothness of motion. C 4 stands for C e n e r g y , representing energy consumption. The respective formulas are as follows:
C g o a l = 1 π | θ A U V θ g o a l |
where θ A U V represents the heading angle in the current row of AUV, and θ g o a l represents the target direction angle.
C o b s = 1 d m i n + ϵ
where d m i n represents the nearest distance to the object, and ϵ takes a very small value. Its function is to prevent the denominator from being 0.
C s m o o t h = 1 N 1 i = 1 N 1 θ i + 1 θ i
where θ i is the heading Angle of trajectory segment i, and N is the number of trajectory points.
C e n e r g y = 0 T k 1 v 2 + k 2 ω 2 d t
where k 1 and k 2 are energy consumption coefficients, and v and ω are linear velocities and angular velocities, respectively. Then, the weight adaptive mechanism is utilized, and its formula is as follows:
w j ( t ) = e λ j t k = 1 4 e λ k t , λ = [ 0.5 , 1.0 , 0.3 , 0.7 ]
where λ j represents the attenuation coefficient of the jth term, which controls the rate at which the weight changes over time. t represents the current time step or the number of iterations. This enables the high weight in the initial stage to focus on quickly approaching the target and avoiding obstacles, while the high weight in the later stage focuses on optimizing smoothness and energy consumption.

4.3. Trajectory Prediction and Correction Mechanism

In underwater environments with dynamic obstacles (e.g., moving fish schools), traditional DWA may fail to avoid collisions due to a lack of trajectory prediction. This paper incorporates motion prediction to forecast obstacle movements and correct planned trajectories accordingly [42]. For each predicted time step, dynamic obstacles are extrapolated using constant velocity or learning-based motion models. Future conflicts are detected through forward simulation, and the candidate trajectories are corrected via penalty adjustments to the cost function. This significantly improves DWA performance in dynamic, cluttered environments. Its formula is as follows:
v ^ o b s ( t + Δ t ) = i = 1 p ϕ i v o b s ( t i ) + j = 1 q θ j ϵ ( t j ) + ϵ ( t )
where v ^ o b s is the predicted velocity of the obstacle at time t + Δ t , p is the autoregressive order, ϕ i is the autoregressive coefficient, q is the moving average order, θ j is the moving average coefficient, and ϵ is the white noise term. When the predicted collision probability is greater than 50%. The ARIMA prediction model synergizes with the physics-based acceleration model. This hybrid approach leverages both physical priors and data-driven correction. In addition, the trajectory correction rule is used, and its formula is as follows:
v n e w = v p r e v · 1 d s a f e p ^ o b s p A U V
where v p r e v represents the current linear velocity of the robot, p o b s is the predicted position of the obstacle, p A U V is the current position of AUV, and d s a f e is the dynamic safety distance. The formulas are as follows:
d s a f e = v A U V · t r e s p + δ m i n
where t r e s p is the system response time, and δ m i n is the minimum static safety margin. The above strategies can adjust the speed according to the approaching rate of obstacles to avoid sudden braking. The dynamic safety distance is adaptively adjusted with the AUV speed, and a larger buffer space is reserved at high speeds.

5. Multi-AUV Cooperative Path Planning Based on Improved PSO-DWA

5.1. Multi-Stage Planning Framework Design

This paper proposes a two-tier architecture of “static global planning—dynamic local adjustment”, and realizes the collaboration of multiple AUVs through the path segmentation strategy [43]. Therefore, the set of global path segmentation points is defined as follows:
P s = p k | p k = p g b + λ k ( p e n d p g b ) , λ k ( 0 , 1 )
where P s is the set of global path segmentation points; p k is the k-th segmentation point, which is used to trigger the critical position of local dynamic programming; p g b is the global optimal path point; p e n d is the destination of the goal; λ k is the dynamic segmentation coefficient, which is used to control the relative position of the segmentation point and the global optimal path point. Its formula is as follows:
λ k = 1 v c ( p k ) v c m a x + α · ρ o b s ( p k ) ρ m a x
where v c ( p k ) is the ocean current velocity vector at position p k . v c m a x is the speed of the maximum ocean current; ρ o b s ( p k ) is the local obstacle density at position p k ; p m a x is the threshold of the maximum obstacle density; α is the obstacle sensitive factor, which is used to adjust the influence weight of the obstacle density on the segmentation coefficient.
The collaborative triggering mechanism monitors the AUV spacing in real time through the following formula:
Δ p i j = p i p j
where Δ p i j is the Euclidean distance between AUVs, representing the real-time spatial distance between the i-th and j-th AUVs. When d s a f e < Δ p i j < 2 d s a f e , the collaborative constraints are activated to avoid the frequent start-stop problem caused by the traditional fixed threshold.

5.2. Reconstruction of Multi-Objective Optimization Functions

This paper proposes a four-dimensional time-varying weight objective function, adding communication topology and task priority constraints.
F t o t a l = i = 1 4 w i ( t ) f i + μ ( g 1 + g 2 )
where F t o t a l is the comprehensive objective function; w i is the time-varying weight coefficient; f i is the sub-objective function; μ is the constraint penalty weight, which is used to balance the violation degree of the objective function and the constraint conditions; g 1 is the communication topology constraint; g 2 is the task timeliness constraint. The formulas of g 1 , g 2 , and each sub-objective function are as follows:
g 1 = ( i , j ) ϵ max 0 , d c o m p i p j
where ϵ is the set of communication topology edges, describing the communication connection relationship between AUVs; d c o m is the maximum communication distance.
g 2 = i = 1 M t i t ^ i
where t i is the actual arrival time of the i-th AUV; t ^ i is the task requirement time for the i-th AUV.
f 1 = j = 1 N d o b s ( p j ) 1 + h s a f e · Δ h ( p j )
f 1 is the path safety degree function; d o b s is the Euclidean distance from the path point p j to the nearest point nearest obstacle. Δ h ( p j ) = h ( p j ) H b a s e ( p j ) , that is, the height deviation of the path point p j .
f 2 = i j max 0 , d s a f e p i p j d s a f e 2
f 2 is the cooperative separation function. When the AUV spacing is less than the safety spacing of multiple AUVs, the function value increases squared as the distance decreases, forcibly maintaining the formation safety.
f 3 = j = 1 N α v j 2 + β a j 2 + γ v j v c ( p j )
f 3 is the energy loss degree function, and v j , a j , v c are, respectively, the velocity, acceleration, and ocean current velocity of AUV at the path point p j . α , β , γ are the weight coefficients.
f 4 = j = 2 N 1 arccos Δ p j · Δ p j + 1 Δ p j Δ p j + 1
f 4 is the path smoothness function. The formula Δ p j = p j p j 1 is the vector difference from the path segment p j to p j 1 . The formula Δ p j + 1 = p j + 1 p j represents the vector difference from the path segment p j + 1 to p j . arccos is used to calculate the angle between two vectors. By minimizing the total included angle sum, ensure a smooth path, and reduce unnecessary turns.
The time-varying weight strategy can focus on path security in the early stage of iteration and optimize energy consumption in the later stage. Communication constraints can ensure that multiple AUVs maintain a communication distance greater than the safe distance in complex terrains.

5.3. Collaborative Path Smoothing Enhancement

In order to enhance the security of multi-machine collaboration, optimize the smoothness of motion, and improve environmental adaptability, this paper uses the collaborative path smoothing enhancement strategy, and the formula is as follows:
Q i ( t ) = k = 0 n N k , 3 ( t ) P k ( i ) Q i ( t ) Q j ( t ) d s a f e + η · v r e l d 3 Q i d t 3 J m a x
where Q i represents the B-spline path function of the i-th AUV; N k , 3 is the cubic B-spline basis function; P k ( i ) represents the set of control points of the i-th AUV; v r e l = v i v j , which is the relative velocity between AUV; η is the speed-sensitive factor, regulating the influence of speed on the safety margin; J m a x is the maximum jerk, and is used to limit the smoothness of the path.
By enhancing the safety margin and collision-avoidance success rate in narrow passages and using a parallel solution strategy, the computational time consumption is significantly reduced.

5.4. Dynamic Window Collaborative Expansion

The stand-alone DWA only considers static obstacles and its own motion constraints. Therefore, a new collaborative constraint term is added. Through cooperative AUV window constraint collision-avoidance maneuvers, a chain reaction can be triggered, with a mandatory reserved collaborative response time to avoid conflicting decisions. The constraint formula of the multi-AUV cooperative window is as follows:
W d ( i ) = { ( v , ω )   | a m a x v j v i Δ t t r e s p ( v i , v j ) θ s a f e
where W d ( i ) is the set of dynamic Windows of the i-th AUV, including all feasible combinations of velocity and angular velocity; Δ t is the prediction time domain of the dynamic window method; t r e s p is the system response time; ( v i , v j ) is the velocity vector included Angle, and θ s a f e is the dynamic safety included Angle. Its formula is as follows:
θ s a f e = 30 ° · 1 + ρ o b s ρ m a x
Meanwhile, using the collaborative evaluation function and quantifying the key indicators of multi-machine collaboration, the collision-avoidance decision and motion coordination in path planning are optimized. The specific formula is as follows:
C c o l l a b = j N i 1 p i p j 2 + v i v j v m a x
where N i is the neighbor set determined by the i-th AUV through communication topology or sensing range.

5.5. Computational Complexity and Scalability Analysis

Compared with conventional meta-heuristic frameworks, the proposed hybrid PSO-DWA architecture exhibits a modular yet interdependent computational pattern. Its complexity is not only determined by the iteration scale but also shaped by the adaptivity and multi-level feedback mechanisms introduced in this work.
Let N be the number of particles, T the number of iterations, D the path dimensionality (i.e., number of nodes per AUV), and M the number of AUVs. The global planning stage based on improved PSO integrates CPB initialization, adaptive parameters, and hybrid Levy-differential mutation. Each cost evaluation per particle involves collision checks, ocean current estimation, terrain safety margin computation, and multi-objective aggregation, leading to a cost of O ( D ) per particle. Consequently, the global planning complexity scales as:
O ( N · D · T )
However, the CPB initialization introduces a front-end overhead. Specifically, Chebyshev chaotic mapping with M p r e pre-iterations, Voronoi-based boundary injection, and ARIMA-based prediction-correction require additional preprocessing time. Denoting P i n j as the number of injected edge particles and C e n v as the complexity of terrain and current feature extraction, the extended initialization complexity becomes:
O ( M p r e · N + P i n j · C e n v )
This cost significantly enhances early-stage diversity and reduces the number of required iterations T for convergence.
During online execution, the DWA component is triggered adaptively based on current, obstacle density, and inter-AUV proximity. For each AUV, if the dynamic window samples K velocity pairs per step and executes S local adjustments along its trajectory, the local planning cost becomes:
O ( M · S · K )
Moreover, the proposed trajectory prediction module, which blends physics-informed acceleration with ARIMA-based velocity forecasting, introduces a constant-time correction step, not significantly impacting the overall per-step complexity.
In total, the hybrid algorithm’s complexity can be expressed as:
O ( N · D · T + M p r e · N + P i n j · C e n v + M · S · K )
The design explicitly separates high-complexity global search and lightweight real-time local corrections. Furthermore, particle-level and AUV-level processes are parallelizable by design, enabling deployment on GPU-enabled simulation clusters or multi-core embedded processors. Importantly, the framework tolerates asynchrony in dynamic updates, which makes it robust under partial observability and variable latency scenarios.
Thus, although the algorithm introduces moderate computational overhead compared to traditional PSO or DWA, its multi-resolution planning architecture and bioinspired enhancements ensure scalable performance and real-time responsiveness in complex 3D marine environments with uncertain terrain and fluid dynamics.

5.6. Flowchart of Multi-AUVs Path Planning Based on IMOPSO Algorithm

This paper proposes a multi-AUV dynamic path-planning method based on the combination of the improved Multi-Objective Particle Swarm Optimization Algorithm and the Dynamic Window Algorithm. This method fully integrates the global optimization ability and the local obstacle avoidance ability, and is capable of quickly generating safe and feasible paths in a dynamic and complex environment. The overall process of this algorithm includes steps such as initialization, particle update, local dynamic optimization, path evaluation, and update. To present its execution logic more intuitively, the main process is now presented in the form of pseudo-code, as shown in Algorithm 1.
To clarify the criteria for determining the “non-convergence” condition, this paper adopts the following criteria: Firstly, the algorithm sets a maximum number of iterations T m a x as a forced stop condition to prevent excessive computation; Then, if the rate of change in the global optimal fitness for several consecutive generations is lower than the preset threshold ϵ , it is considered that the population tends to converge; Finally, if the variance of the particle’s position or velocity gradually stabilizes, that is, the fluctuation is less than the threshold δ , it can also be determined that the convergence state has been reached. The mathematical expression is as follows:
f t b e s t f t K b e s t < ϵ
V a r ( x t ) < δ
where f t b e s t represents the global optimal fitness of the t-th generation, K is the number of consecutive observation generations, and x t represents the position vector of all particles in the t-th generation. In this paper, the empirical settings are ϵ = 10 3 , δ = 10 4 , and K = 10 . This criterion takes into account both the convergence of the solution and the diversity of the population, which helps to avoid premature convergence and simultaneously improves the computational efficiency.
Algorithm 1: Hybrid Global-Local Path Planning for Multi-AUV.
  • Require: Terrain map M , current field V c , start/goal sets S , T , constraints K , AUV count M
  • Ensure: { P i } (Planned paths), E (Energy matrix)
  • Global Planning (IMOPSO):
  • Initialize swarm with CPB strategy
  • Define F total w i f i + μ g j
Biomimetics 10 00536 i001
In order to verify the effectiveness of the improved strategy, this paper designs the initialization comparison experiment, the global path planning of each algorithm, and the dynamic cooperative path-planning experiment of multiple underwater robots. The effectiveness of the improved hybrid algorithm in the problem of underwater environment path planning and the feasibility of the improved hybrid algorithm were verified, respectively.

6. Simulation Result and Analysis

6.1. Initialization Comparison Experiment

In this paper, the particle swarm initialization strategy of the CPB strategy is used to improve the PSO algorithm. It includes the Chebyshev hybrid initialization, pre-iterative elimination, and boundary particle injection methods. Meanwhile, dynamic adaptive parameter adjustment and the addition of hybrid perturbation strategies are used. Therefore, each method is compared with the original PSO algorithm, respectively. The relevant parameters of IMOPSO are shown in Table 1.
Figure 3 shows the comparison between the random initialization of PSO and the mixed initialization of CPB in this paper. In Figure 3a, the particles are concentrated in the center of the search space, and the boundary area is sparse. In Figure 3b, the particles uniformly fill the entire space, and the edges are well covered. It can be seen that the initialization strategy adopted in this paper conducts a more comprehensive global search and is less likely to fall into a local optimum.
Figure 4 shows the comparison of the PSO algorithm with and without pre-iteration. In Figure 4a, there is no pre-iteration, and fluctuations, offsets, and local clustering occur in the particle concentration. Figure 4b has pre-iteration, and the particle distribution is symmetrical, regular, and uniform. It can be seen that the pre-iteration strategy adopted in this paper can filter out unstable states and improve the initialization balance.
Figure 5 shows a comparison chart of the PSO algorithm with and without boundary particle injection. In Figure 5a, there is no boundary particle injection, and there are a large number of blanks in the edge area. In Figure 5b, there is boundary particle injection, and the boundary particles clearly fill the periphery. It can be seen that the boundary particle injection strategy adopted in this paper can improve the boundary search ability and avoid losing the optimal boundary solution.
Figure 6 shows the comparison of the PSO algorithm with and without dynamic parameter adjustment. In Figure 6a is a fixed parameter. The convergence path is straight or has large jitter, and it is prone to premature convergence. In Figure 6b shows dynamic parameters. The inertia weight + learning factor is adjusted over time, and the path gradually converges. It can be seen that the dynamic parameter adjustment strategy adopted in this paper can improve the convergence of the algorithm and the global search ability.
Figure 7 shows the comparison of the PSO algorithm with and without a mixed perturbation strategy. In Figure 7a, there is no disturbance. All particles rigidly revolve around the global optimal point with almost no divergence. In Figure 7b features mixed perturbations, appropriate particle jumps/diffuses, and increases exploration potential. It can be seen that the hybrid perturbation strategy adopted in this paper does not disrupt convergence and can also escape from a local optimum.

6.2. Parameter Sensitivity Analysis

To quantitatively evaluate the impact of key parameters on algorithm performance, this section conducts sensitivity experiments on the individual learning factor c 1 , the Levy flight step factor α L e v y , and the inertia weight w p s o . The test environment is a three-dimensional marine scene, with a fixed population size of N = 100 and a maximum number of iterations T m a x = 50. The rest of the parameters remain unchanged. Table 2 compares the convergence speed and solution quality under different parameter combinations. The typical experimental results are shown in the following images and tables.
Figure 8 shows the global path-planning image when w p s o = 0.4. Figure 9 shows the global path-planning image when w p s o = 0.8. Figure 10 shows the global path-planning image when c 1 = 1. Figure 11 shows the global path-planning image when c 1 = 3. Figure 12 shows the global path-planning image when α L e v y = 0.01. Figure 13 shows the global path-planning image when α L e v y = 1. Figure 14 shows the global path-planning image when w P S O = 0.6, c 1 = 2, α L e v y = 0.1.
From the combined analysis of the images and Table 2, it can be seen that when c 1 = 1.0, the particles rely more on individual cognition, the path exploration is sufficient, but the convergence is slow. When c 1 = 3.0, the algorithm prematurely converges to a suboptimal solution, and the path length increases. When c 1 = 2.0, it reaches the optimal value, achieving a balance between exploration and exploitation and enabling the algorithm to converge rapidly and stably. When α L e v y = 0.01, the disturbance is insufficient, and path deadlock is prone to occur in complex terrain. When α L e v y = 1, the particle trajectory oscillates and the energy consumption increases. When α L e v y = 0.1, it reaches the optimal value. By applying moderate perturbations, the obstacle avoidance capability is enhanced and the safety margin is increased. When w p s o = 0.8, unnecessary turns occur in the path; when w p s o decreases from 0.6 to 0.4 using the dynamic attenuation strategy, it balances early exploration and late convergence. Therefore, in the experiment, the combination of c 1 = 2.0, α L e v y = 0.1 and w p s o = 0.4 was adopted.

6.3. Comparative Experiment on Path Planning of IMOPSO Algorithm

To prove the effectiveness and accuracy of the improved multi-objective particle swarm optimization algorithm in global path planning under known environmental conditions, this paper takes the path-planning tasks of multiple AUVs in a three-dimensional marine environment as the research object and designs and implements a series of simulation experiments. The experimental content mainly includes the comparison of the GA algorithm, BOA algorithm, GWO algorithm, WOA algorithm, and IMOPSO algorithm. The comparison is mainly made from several aspects, such as path length, path energy consumption, path smoothness, and total fitness. Among them, Figure 15 is the top view and three-dimensional view of the global path-planning route of the GA algorithm. Figure 16 shows the top view and three-dimensional view of the global path-planning route of the BOA algorithm. Figure 17 shows the top view and 3D view of the global path-planning route of the GWO algorithm. Figure 18 shows the top view and 3D view of the global path-planning route of the PSO algorithm. Figure 19 shows the top view and 3D view of the global path-planning route of the IMOPSO algorithm. Figure 20 shows the fitness curves of the three algorithms. Table 3 presents the final results of several algorithms. As can be seen from the table, the improved multi-objective particle swarm optimization algorithm outperforms other meta-heuristic optimization algorithms in terms of path length, energy consumption, and path smoothness.
The results show that the path length and security performance of the IMOPSO algorithm are relatively outstanding. Compared with other meta-heuristic optimization algorithms, it can obtain the optimal objective function value and has a better iterative curve. The experimental results show that the IMOPSO algorithm proposed in this paper has a strong global search ability and a strong ability to avoid local optima. It can effectively search for the optimal path and obtain a better fitness function value.

6.4. Multi-AUV Dynamic Cooperative Path-Planning Experiment

Because dynamic path planning involves multiple complex environmental factors, it is difficult to uniformly select evaluation indicators (such as path length, energy consumption, obstacle avoidance safety, etc.). Therefore, in this paper, the variation curve of the cost function with the number of iterations in the global path-planning optimization process is adopted as the comparison method to reflect the advantages and disadvantages of different algorithms in terms of convergence speed and stability. The dynamic path planning of the five algorithms is shown in the figure. Figure 21 Dynamic planning results of global path planning using the GA algorithm combined with the DWA algorithm. Figure 22 presents the dynamic programming results of global path planning using the BOA algorithm combined with the DWA algorithm. Figure 23 presents the dynamic programming results of global path planning using the GWO algorithm combined with the DWA algorithm. Figure 24 presents the dynamic programming results of global path planning using the WOA algorithm combined with the DWA algorithm. Figure 25 presents the dynamic programming results of global path planning using the IMOPSO algorithm combined with the DWA algorithm.
The red balls in the figure indicate the differences between the dynamic programming path and the static global programming path. It can be seen from the figure that the performance of the IMOPSO and DWA hybrid algorithm in dynamic path planning is superior to that of other meta-heuristic algorithms. Its advantages are mainly reflected in the early stage of iteration. The cost function of IMOPSO–DWA drops rapidly, indicating that it has a stronger global search ability and a higher initial convergence efficiency. Unlike the oscillation or even regression of the other meta-heuristic optimization algorithms’ curves in the middle and later stages, the cost curve of IMOPSO–DWA tends to stabilize after approaching the optimal solution, showing good robustness and stability. Under the same number of iterations, the final generated value obtained by the IMOPSO–DWA algorithm is significantly lower than that of several other algorithms, indicating that it can search for path solutions of better quality.
To sum up, it can be known that through the comparative analysis of the iterative curves of the cost function, the IMOPSO–DWA hybrid algorithm shows better optimization performance in the dynamic path-planning task, providing an effective solution idea for multi-AUV cooperative path planning in complex dynamic environments.

7. Conclusions

In today’s world, with the continuous growth of demands for marine resource development, environmental monitoring, and marine security, the autonomous path-planning ability of underwater AUVs in complex marine environments is becoming increasingly important. How to achieve efficient and safe path planning in a dynamic environment has become one of the key challenges of intelligent ocean systems.
This paper constructs a three-dimensional complex marine environment simulation platform integrating submarine topography, static obstacles, dynamic threats, and ocean current modeling, and proposes an improved multi-objective particle swarm optimization algorithm based on Chebyshev chaotic initialization for global path planning. Meanwhile, the improved Dynamic Window Method is introduced as the local obstacle avoidance compensation mechanism to achieve the fusion optimization of the global and local paths. The experimental results show that the proposed algorithm is superior to the traditional methods in terms of path feasibility, smoothness, convergence speed, and obstacle avoidance ability. Especially in multi-obstacle and strong ocean current environments, it shows stronger robustness and adaptability.
This study presents an effective multi-level solution for cooperative path planning of AUVs in complex and dynamic marine environments. Future work will focus on several key directions, including incorporating models of underwater communication delays and bandwidth constraints to optimize the real-time performance of multi-AUV collaborative decision-making; integrating reinforcement learning to enable dynamic task allocation and improve adaptability in complex scenarios; and embedding a real-time ocean turbulence prediction module to enhance the robustness of path planning against sudden flow field disturbances.

Author Contributions

Z.L., Conceptualization, Methodology, Writing, original draft, Validation, Simulation. B.S., Review and Editing, Supervision, Resources. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported in part by the National Natural Science Foundation of China under Grant 52271321 and the Natural Science Foundation of Shanghai under Grant 22ZR1426700.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are available in the main text.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
AUVAutonomous Underwater Vehicle
PSOParticle Swarm Optimization
DWADynamic Window Approach
GAGenetic Algorithm

References

  1. Wu, W.; Zhang, W.; Du, X.; Li, Z.; Wang, Q. Homing tracking control of autonomous underwater vehicle based on adaptive integral event-triggered nonlinear model predictive control. Ocean Eng. 2023, 277, 114243. [Google Scholar] [CrossRef]
  2. Li, B.; Mao, J.; Yin, S.; Fu, L.; Wang, Y. Path Planning of Multi-Objective Underwater Robot Based on Improved Sparrow Search Algorithm in Complex Marine Environment. J. Mar. Sci. Eng. 2022, 10, 1695. [Google Scholar] [CrossRef]
  3. Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
  4. Dijkstra, E.W. A Note on Two Problems in Connexion with Graphs. Numer. Math. 1959, 1, 269–271. [Google Scholar] [CrossRef]
  5. Kavraki, L.E.; Švestka, P.; Latombe, J.C.; Overmars, M.H. Probabilistic Roadmaps for Path Planning in High-Dimensional Configuration Spaces. IEEE Trans. Robot. Autom. 1996, 12, 566–580. [Google Scholar] [CrossRef]
  6. LaValle, S.M.; Kuffner, J.J. Randomized Kinodynamic Planning. Int. J. Robot. Res. 2001, 20, 378–400. [Google Scholar] [CrossRef]
  7. Betts, J.T. Practical Methods for Optimal Control and Estimation Using Nonlinear Programming; SIAM: Philadelphia, PA, USA, 2010. [Google Scholar] [CrossRef]
  8. Bertsekas, D.P. Dynamic Programming and Optimal Control; Athena Scientific: Nashua, NH, USA, 2012. [Google Scholar]
  9. Holland, J.H. Adaptation in Natural and Artificial Systems; MIT Press: Cambridge, MA, USA, 1992. [Google Scholar]
  10. Dorigo, M.; Stützle, T. Ant Colony Optimization; MIT Press: Cambridge, MA, USA, 2004. [Google Scholar]
  11. Kennedy, J.; Eberhart, R. Particle Swarm Optimization. In Proceedings of the ICNN’95—International Conference on Neural Networks, Perth, WA, Australia, 27 November–1 December 1995; Volume 4, pp. 1942–1948. [Google Scholar] [CrossRef]
  12. Tang, R.; Qi, L.; Ye, S.; Li, C.; Ni, T.; Guo, J.; Liu, H.; Li, Y.; Zuo, D.; Shi, J. Three-Dimensional Path Planning for AUVs Based on Interval Multi-Objective Secretary Bird Optimization Algorithm. Symmetry 2025, 17, 993. [Google Scholar] [CrossRef]
  13. Ma, Y.; Zhang, Z.; Yao, M.; Fan, G. A Self-Adaptive Improved Slime Mold Algorithm for Multi-UAV Path Planning. Drones 2025, 9, 219. [Google Scholar] [CrossRef]
  14. Puente-Castro, A.; Rivero, D.; Pedrosa, E.; Pereira, A.; Lau, N.; Fernandez-Blanco, E. Q-Learning based system for Path Planning with Unmanned Aerial Vehicles swarms in obstacle environments. Expert Syst. Appl. 2024, 235, 121240. [Google Scholar] [CrossRef]
  15. Liu, H.; Shen, Y.; Yu, S.J.; Gao, Z.J.; Wu, T. Deep Reinforcement Learning for Mobile Robot Path Planning. J. Theory Pract. Eng. Sci. 2024, 4, 37–44. [Google Scholar] [CrossRef]
  16. Tao, B.; Kim, J.H. Deep reinforcement learning-based local path planning in dynamic environments for mobile robot. J. King Saud Univ.-Comput. Inf. Sci. 2024, 36, 102254. [Google Scholar] [CrossRef]
  17. Babakhani, A.; Jahanbakhshi, M.R.; Parsa, H. Autonomous Underwater Vehicle Motion Planning in Realistic Ocean Environments Using Penalty Function-Particle Swarm Optimization Technique. Iran. J. Sci. Technol. Trans. Mech. Eng. 2023, 47, 1303–1318. [Google Scholar] [CrossRef]
  18. Wang, L.; Li, J.; Qi, J.; He, J. AUV underwater 3D path planning based on particle swarm optimization-adaptive step-size cuckoo search algorithm. In Proceedings of the 2022 11th International Conference on Networks, Communication and Computing, Beijing, China, 9–11 December 2023; pp. 215–225. [Google Scholar] [CrossRef]
  19. Zhi, L.W.; Zuo, Y. Collaborative Path Planning of Multiple AUVs Based on Adaptive Multi-Population PSO. J. Mar. Sci. Eng. 2024, 12, 223. [Google Scholar] [CrossRef]
  20. Wang, Z.; Chen, Y.; Ding, S.; Liang, D.; He, H. A novel particle swarm optimization algorithm with Lévy flight and orthogonal learning. Swarm Evol. Comput. 2022, 75, 101207. [Google Scholar] [CrossRef]
  21. Liu, Y.X.; Vogiatzis, C.; Yoshida, R.; Morman, E. Solving reward-collecting problems with UAVs: A comparison of online optimization and Q-learning. arXiv 2021, arXiv:2112.00141. [Google Scholar] [CrossRef]
  22. Chen, J.S.; Xu, L.H.; Ebel, H.; Eberhard, P. An Online Optimization-Based Trajectory Planning Approach for Cooperative Landing Tasks. arXiv 2025, arXiv:2502.13823. [Google Scholar]
  23. Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef]
  24. Liu, Z.; Liu, Y.; Wu, S.; Chen, T. Underwater Path Planning of UUV Based on UDWA. In Proceedings of the 2022 IEEE Intl Conf on Dependable, Autonomic and Secure Computing, Intl Conf on Pervasive Intelligence and Computing, Intl Conf on Cloud and Big Data Computing, Intl Conf on Cyber Science and Technology Congress (DASC/PiCom/CBDCom/CyberSciTech), Falerna, Italy, 12–15 September 2022; pp. 1–4. [Google Scholar] [CrossRef]
  25. Shen, Y.; Xu, H.; Wang, D.; Zhang, Y.; Yan, T.; He, B. Real-time Obstacle Avoidance for AUV Based on Reinforcement Learning and Dynamic Window Approach. In Proceedings of the Global Oceans 2020: Singapore—U.S. Gulf Coast, Biloxi, MS, USA, 5–30 October 2020; pp. 1–4. [Google Scholar] [CrossRef]
  26. Viswanathan, G.M.; Afanasyev, V.; Buldyrev, S.V.; da Luz, M.G.E.; Raposo, E.P.; Stanley, H.E. Lévy flight search patterns of wandering albatrosses. Nature 1996, 381, 413–415. [Google Scholar] [CrossRef]
  27. Reynolds, A.M.; Rhodes, C.J. The Lévy flight paradigm: Random search patterns and mechanisms. Ecology 2009, 90, 877–887. [Google Scholar] [CrossRef]
  28. Zhang, J.; Liu, M.; Zhang, S.; Zheng, R.; Dong, S. Five-Tiered Route Planner for Multi-AUV Accessing Fixed Nodes in Uncertain Ocean Environments. arXiv 2023, arXiv:2311.06579. [Google Scholar] [CrossRef]
  29. Lin, Y.H.; Huang, L.C.; Chen, S.Y.; Yu, C.M. The optimal route planning for inspection task of autonomous underwater vehicle composed of MOPSO-based dynamic routing algorithm in currents. Appl. Ocean Res. 2018, 75, 178–192. [Google Scholar] [CrossRef]
  30. Sutantyo, D.; Levi, P.; Möslinger, C.; Read, M. Collective-adaptive Lévy flight for underwater multi-robot exploration. In Proceedings of the 2013 IEEE International Conference on Mechatronics and Automation, Takamatsu, Japan, 4–7 August 2013; pp. 456–462. [Google Scholar] [CrossRef]
  31. Shen, Z. 3-D Coverage Path Planning for Underwater Terrain Mapping. Master’s Thesis, University of Connecticut, Storrs, CT, USA, 2017. [Google Scholar]
  32. Mu, X.; Gao, W. Coverage Path Planning for Multi-AUV Considering Ocean Currents and Sonar Performance. Front. Mar. Sci. 2025, 11, 1483122. [Google Scholar] [CrossRef]
  33. Yang, L.; Bi, K.; He, Y.; Han, Z. Multi-rotor UAV Track Planning Based on Improved Artificial Potential Field. In Proceedings of the 11th International Conference on Modelling, Identification and Control (ICMIC2019), Tianjin, China, 13–15 July 2019; Springer: Singapore, 2019; pp. 1291–1302. [Google Scholar] [CrossRef]
  34. Srivastava, S.; Michael, N. Efficient, Multifidelity Perceptual Representations via Hierarchical Gaussian Mixture Models. IEEE Trans. Robot. 2019, 35, 248–260. [Google Scholar] [CrossRef]
  35. Couzin, I.D.; Krause, J.; James, R.; Ruxton, G.D.; Franks, N.R. Collective Memory and Spatial Sorting in Animal Groups. J. Theor. Biol. 2002, 218, 1–11. [Google Scholar] [CrossRef]
  36. Fossen, T.I. Guidance and Control of Ocean Vehicles; Wiley: Hoboken, NJ, USA, 2011. [Google Scholar]
  37. Yan, X.; Wang, W.; Huang, C.; Li, L. A new path planning method for AUV based on the Navier–Stokes equations for ocean currents. Math. Comput. Simul. 2024, 222, 199–208. [Google Scholar] [CrossRef]
  38. Bangyal, W.H.; Hameed, A.; Alosaimi, W.; Alyami, H. A New Initialization Approach in Particle Swarm Optimization for Global Optimization Problems. Comput. Intell. Neurosci. 2021, 2021, 6628889. [Google Scholar] [CrossRef]
  39. Chu, H.; Yi, J.; Yang, F. Chaos Particle Swarm Optimization Enhancement Algorithm for UAV Safe Path Planning. Appl. Sci. 2022, 12, 8977. [Google Scholar] [CrossRef]
  40. Xie, X.; Zhang, K.; Zheng, B.; Ning, H.; Zhou, Y.; Peng, Q.; Li, Z. A CML-ECA Chaotic Image Encryption System Based on Multi-Source Perturbation Mechanism and Dynamic DNA Encoding. Symmetry 2025, 17, 1042. [Google Scholar] [CrossRef]
  41. Liu, L.; Jiang, D.; Wang, X.; Rong, X.; Zhang, R. 2D Logistic-Adjusted-Chebyshev map for visual color image encryption. J. Inf. Secur. Appl. 2021, 60, 102854. [Google Scholar] [CrossRef]
  42. Hahn, B. Enhancing Obstacle Avoidance in Dynamic Window Approach via Dynamic Obstacle Behavior Prediction. Actuators 2025, 14, 207. [Google Scholar] [CrossRef]
  43. Hong, L.; Song, C.; Yang, P.; Cui, W. Two-Layer Path Planner for AUVs Based on the Improved AAF-RRT Algorithm. J. Mar. Sci. Appl. 2022, 21, 102–115. [Google Scholar] [CrossRef]
Figure 1. Overview of the environmental model.
Figure 1. Overview of the environmental model.
Biomimetics 10 00536 g001
Figure 2. Ocean current field model.
Figure 2. Ocean current field model.
Biomimetics 10 00536 g002
Figure 3. Initialization comparison.
Figure 3. Initialization comparison.
Biomimetics 10 00536 g003
Figure 4. Comparison with and without pre-iteration.
Figure 4. Comparison with and without pre-iteration.
Biomimetics 10 00536 g004
Figure 5. Comparison with and without boundary injection.
Figure 5. Comparison with and without boundary injection.
Biomimetics 10 00536 g005
Figure 6. Dynamic parameter comparison.
Figure 6. Dynamic parameter comparison.
Biomimetics 10 00536 g006
Figure 7. Comparison of mixed disturbances with and without.
Figure 7. Comparison of mixed disturbances with and without.
Biomimetics 10 00536 g007
Figure 8. Global path planning of w P S O = 0.4.
Figure 8. Global path planning of w P S O = 0.4.
Biomimetics 10 00536 g008
Figure 9. Global path planning of w P S O = 0.8.
Figure 9. Global path planning of w P S O = 0.8.
Biomimetics 10 00536 g009
Figure 10. Global path planning of c 1 = 1.
Figure 10. Global path planning of c 1 = 1.
Biomimetics 10 00536 g010
Figure 11. Global path planning of c 1 = 3.
Figure 11. Global path planning of c 1 = 3.
Biomimetics 10 00536 g011
Figure 12. Global path planning of α L e v y = 0.01.
Figure 12. Global path planning of α L e v y = 0.01.
Biomimetics 10 00536 g012
Figure 13. Global path planning of α L e v y = 1.
Figure 13. Global path planning of α L e v y = 1.
Biomimetics 10 00536 g013
Figure 14. Global path planning of α L e v y = 0.1, c 1 = 2, w P S O = 0.6.
Figure 14. Global path planning of α L e v y = 0.1, c 1 = 2, w P S O = 0.6.
Biomimetics 10 00536 g014
Figure 15. Global path planning GA.
Figure 15. Global path planning GA.
Biomimetics 10 00536 g015
Figure 16. Global path planning of the BOA algorithm.
Figure 16. Global path planning of the BOA algorithm.
Biomimetics 10 00536 g016
Figure 17. Global path planning GWO.
Figure 17. Global path planning GWO.
Biomimetics 10 00536 g017
Figure 18. Global path planning PSO.
Figure 18. Global path planning PSO.
Biomimetics 10 00536 g018
Figure 19. Global path-planning IMOPSO.
Figure 19. Global path-planning IMOPSO.
Biomimetics 10 00536 g019
Figure 20. Global path-planning of IMOPSO algorithm and performance comparison.
Figure 20. Global path-planning of IMOPSO algorithm and performance comparison.
Biomimetics 10 00536 g020
Figure 21. Dynamic path planning based on GA algorithm.
Figure 21. Dynamic path planning based on GA algorithm.
Biomimetics 10 00536 g021
Figure 22. Dynamic path planning based on the BOA algorithm.
Figure 22. Dynamic path planning based on the BOA algorithm.
Biomimetics 10 00536 g022
Figure 23. Dynamic path planning based on GWO algorithm.
Figure 23. Dynamic path planning based on GWO algorithm.
Biomimetics 10 00536 g023
Figure 24. Dynamic path planning based on the PSO algorithm.
Figure 24. Dynamic path planning based on the PSO algorithm.
Biomimetics 10 00536 g024
Figure 25. Dynamic path planning based on IMOPSO algorithm.
Figure 25. Dynamic path planning based on IMOPSO algorithm.
Biomimetics 10 00536 g025
Table 1. Parameter definitions and values.
Table 1. Parameter definitions and values.
Parameter NameParameter DefinitionValue
TMaximum Iterations100
num_particlesPopulation size100
knot_numPath Nodes10
NCubic spline interpolation points200
w m a x Maximum inertia weight0.9
w m i n Minimum inertia weight0.4
c 1 α c 1 lower boundary control factor1
c 1 β c 1 upper boundary control factor1.5
c 2 α c 2 lower boundary control factor1
c 2 β c 2 upper boundary control factor1.5
F m a x Maximum difference weight0.5
F m i n Minimum difference weight0.1
β 0 Initial perturbation amplitude for local search1
α Exponential decay coefficient4
kControl parameter of sine chaotic perturbation1200
δ 0 Initial perturbation amplitude10
Δ ω b a s e Base angular velocity resolution0.1
KVelocity samples per step50
t r e s p System response time0.5
δ m i n Minimum static safety margin3
d s a f e Multi-AUV safety distance5
d c o m Communication distance50
η Velocity sensitivity factor0.8
J m a x Maximum jerk limit2.0
T p Prediction horizon steps10
α Prediction-correction factor0.7
Table 2. Results of parameter sensitivity experiments.
Table 2. Results of parameter sensitivity experiments.
ParametersValueIteration CountPath LengthEnergy
c 1 138562.4215.7
c 1 222541.1197.9
c 1 318548.3206.5
α L e v y 0.0118558.2208.3
α L e v y 0.124542.7199.1
α L e v y 129551.6211.8
w P S O 0.432552.9205.4
w P S O 0.623543.3200.2
w P S O 0.827547.5209.7
Table 3. Comparison of path-planning performance of different algorithms.
Table 3. Comparison of path-planning performance of different algorithms.
AlgorithmPath LengthEnergySmoothnessThreat PenaltyTotal Fitness
GA560.08213.571.8114214.24422,197.93
BOA536.04184.481.5694190.34419,754.35
GWO589.83220.641.8654187.64419,574.23
PSO549.54190.541.4723991.32399,736.68
IMOPSO463.84200.281.5623862.72387,020.33
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

Sun, B.; Lv, Z. Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment. Biomimetics 2025, 10, 536. https://doi.org/10.3390/biomimetics10080536

AMA Style

Sun B, Lv Z. Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment. Biomimetics. 2025; 10(8):536. https://doi.org/10.3390/biomimetics10080536

Chicago/Turabian Style

Sun, Bing, and Ziang Lv. 2025. "Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment" Biomimetics 10, no. 8: 536. https://doi.org/10.3390/biomimetics10080536

APA Style

Sun, B., & Lv, Z. (2025). Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment. Biomimetics, 10(8), 536. https://doi.org/10.3390/biomimetics10080536

Article Metrics

Article metric data becomes available approximately 24 hours after publication online.
Back to TopTop