Next Article in Journal
Improved Super-Twisting Sliding Mode Control of a Brushless Doubly Fed Induction Generator for Standalone Ship Shaft Power Generation Systems
Previous Article in Journal
Experimental and Numerical Study on the Temperature Rise Characteristics of Multi-Layer Winding Non-Metallic Armored Optoelectronic Cable
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Multi-Strategy Fusion Path Planning Algorithm for Autonomous Surface Vessels with Dynamic Obstacles

1
School of Navigation, Wuhan University of Technology, Wuhan 430063, China
2
Hubei Key Laboratory of Inland Shipping Technology, Wuhan University of Technology, Wuhan 430063, China
3
State Key Laboratory of Maritime Technology and Safety, Wuhan University of Technology, Wuhan 430063, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2025, 13(7), 1357; https://doi.org/10.3390/jmse13071357
Submission received: 10 June 2025 / Revised: 4 July 2025 / Accepted: 10 July 2025 / Published: 17 July 2025
(This article belongs to the Section Ocean Engineering)

Abstract

Considering the complexity and variability inherent in maritime environments, path planning algorithms for navigation have consistently been a subject of intense research interest. Nonetheless, single-algorithm approaches often exhibit inherent limitations. Consequently, this study introduces a path planning algorithm for autonomous surface vessels (ASVs) that integrates an improved fast marching method (FMM) with the dynamic window approach (DWA) for underactuated ASVs. The enhanced FMM improves the overall optimality and safety of the determined path in comparison to the conventional approach. Concurrently, it effectively merges the local planning strengths of the DWA algorithm, addressing the safety re-planning needs of the global path when encountering dynamic obstacles, thus augmenting path tracking accuracy and navigational stability. The efficient hybrid algorithm yields notable improvements in the path planning success rate, obstacle avoidance efficacy, and path smoothness compared with the isolated employment of either FMM or DWA, demonstrating superiority and practical applicability in maritime scenarios. Through a comprehensive analysis of its control output, the proposed integrated algorithm accomplishes efficient obstacle avoidance via agile control of angular velocity while preserving navigational stability and achieves path optimization through consistent acceleration adjustments, thereby asserting its superiority and practical worth in challenging maritime environments.

1. Introduction

With the growth of global trade and the increasing density of maritime traffic, planning optimal paths in complex maritime environments to avoid collisions and other potential hazards has become a focal point for both academia and industry [1]. Research on path planning and collision avoidance algorithms for autonomous surface vessels (ASVs) is motivated by ongoing efforts to optimize operations and improve operational safety and efficiency [2]. The path planning of ASVs faces significant challenges due to the maritime environment [3]. The intricacy of real-time obstacle detection, tracking, and collision avoidance further complicates the safety of navigation. Path planning algorithms must also strike a balance between computational efficiency and real-time processing capabilities, ensuring rapid responses to unforeseen changes without compromising performance [4]. Additionally, the inherent uncertainties associated with environmental conditions, vessel performance, and external influences require the incorporation of robust, probabilistic path planning methods capable of effectively managing risk and uncertainty [5]. In particular, the autonomous execution of various missions and tasks within environments that are inaccessible to humans requires a highly autonomous path planning framework. This necessity has consistently attracted significant attention within the field.
From an economic perspective, the transition towards increased autonomy in maritime vessels offers significant advantages, including a reduction in accidents, fuel expenses, and operational costs, while simultaneously improving safety and reliability by reducing human error [6,7,8,9,10]. According to the Global Autonomous Ship and Ocean Surface Robot Market: Analysis and Forecast, 2018–2028, a market intelligence report by BIS Research [11], the autonomous vessel market is anticipated to grow at a rate of 26.7% from 2024 to 2035, generating USD 3.48 billion by 2035. This suggests a rising demand for autonomous systems that navigate efficiently and safely through vast, unpredictable maritime areas, emphasizing the importance of tackling maritime path planning challenges to advance autonomous vessels.
In terms of scientific study, as artificial intelligence algorithms develop, an increasing number of learning-based algorithms are being used for ASV trajectory planning tasks. In [12], a DRL-based policy guideline is established for a USV to learn force-level navigation mapping from route tracking deviation and potential collisions for steering. In [13], a topological homotopy perturbation modeling method is proposed, which innovatively achieves the convergence of ASV to the target point in the perturbation scenario. Although learning-based methods can generalize unmodeled scenarios and outperform model-based methods to some extent, they are heavily data-dependent and need a significant amount of training time. The benefits of learning algorithms are frequently focused within the distribution range covered by the training data due to the assumption of independent and identically distributed (i.i.d.). This also limits the general applicability of learning algorithms to dynamic scenarios. Therefore, we approached from the perspective of traditional planning algorithms and made corresponding improvements in applicability. On this basis, we proposed a planning and control scheme that integrates multiple algorithms to improve the intelligence of existing algorithms in response to the limitations of a single algorithm.
The path planning of maritime vessels constitutes a fundamental technology, ensuring the safe and efficient navigation of ASVs. In contrast to terrestrial or aerial vehicles, maritime vessels operate within unstructured environments that necessitate navigation around other vessels, floating debris, and various potential hazards. Park S et al. have significantly contributed to the field of path planning for autonomous vessels navigating within urban waterways, focusing on the complex challenge of socially compliant navigation [14]. In urban settings, where vessels must navigate in close proximity to each other and interact safely with human-operated vessels, adherence to region-specific regulations and norms is paramount. These regulations have provided a foundation for understanding how autonomous vessels can safely operate in confined and complex environments. Nevertheless, as the scope is expanded to encompass the broader maritime context, which includes vast operational domains and environments characterized by disturbances of greater magnitude, distinct from the comparatively regulated settings of urban waterways, maritime environments present additional complexities. These factors include the global optimality of the route for long-distance navigation across open waters, the safety ensured by avoiding local obstacles on the navigation path, and the rapidity of restoring the original route. There is a pressing need for the development of path planning algorithms that can handle larger-scale, more complex environments, incorporating robust disturbance compensation, real-time adaptation, and global optimization for autonomous vessel navigation.
Numerous methods and tools have been developed within the path planning research to address these challenges. It is widely acknowledged that the method of discretizing the terrain into rectangular grid cells facilitates path planning in robots and video games [15,16]. This grid map method provides an efficient state-space prototype for path planning applications in a variety of domains [17,18,19,20]. The basic search algorithms such as A* and Dijkstra are intended to perform a heuristic search using existing environment information [21]; several notable global path planning methodologies include rapid-exploring random trees (RRTs) [22], the potential field method (PF) [23,24], and various optimization strategies [25,26,27,28,29]. However, grid-based path planning is restricted to the edges or vertices, leading to long and unrealistic paths that require frequent directional changes. Alternatively, high-resolution grids are needed to optimize more nodes along the path. The FMM is a method that considers both the map weighting and goal location by solving the Eikonal Equation of wave propagation [30]. This method extends the functionality of both the Dijkstra and PF methods, and its primary advantages include high computational efficiency, allowing the processing of high-resolution environmental data within a short time [31,32].
It is essential to plan an optimal trajectory in advance, accounting for both static and dynamic obstacles. This pre-emptive planning ensures the maintenance of a safe distance from obstacles in the process of avoiding static ones, aligning with the foundational principle of collision avoidance. Nevertheless, the aforementioned global planning methods are not entirely appropriate for the motion control of underactuated vessels. Moreover, conventional global planning approaches are limited to addressing static obstacles. The enhancement of local obstacle avoidance mechanisms to effectively manage dynamic obstacles within the maritime environment while simultaneously ensuring the efficiency of global planning constitutes a subject needing further investigation. Local path planning algorithms, in contrast to global planning, take into account the vessel’s immediate environment, allowing for adaptive responses to unexpected factors such as unmapped obstacles. Upon encountering a dynamic obstacle or a change in environmental conditions, global path planning strategies can be adapted to function as local path planners to adjust the trajectory and prevent collisions. However, this approach may lead to increased computational demands due to the integration of supplementary algorithms. The line-of-sight (LOS) method, recognized as a traditional and efficient local guidance algorithm, is not restricted by particular models but instead determines the vessel’s desired heading by utilizing its current position and the preplanned trajectory. It has been extensively utilized in the control field due to its minimal susceptibility to high-frequency noise, high reliability, and real-time performance [33]. Nevertheless, the LOS method does not inherently account for obstacles. Although it provides a clear path to the target, environmental obstructions may disrupt this path, resulting in inefficiencies or even a complete failure of the navigation path. The DWA constitutes a local path planning algorithm utilized for real-time obstacle avoidance in robotic systems [34,35,36]. This approach generates a spectrum of potential velocity combinations within the current velocity space, assesses the trajectory quality for each configuration, and elects the velocity with the minimal cost as the subsequent motion directive [37]. Its foremost advantages lie in its real-time responsiveness and adaptability, facilitating prompt modifications to environmental dynamics to ensure the safe diversion of vessels [38]. Despite DWA’s supremacy in real-time obstacle avoidance, its global path planning capabilities are still somewhat limited, which makes it difficult to optimize a vessel’s whole course in complicated surroundings. In the study of collision avoidance, researchers pioneered risk quantification by promoting risk curves for path evaluation and employing fuzzy logic with objective indicators (CPA, TCPA, and DCPA) to infer risk levels [39]. In [40], authors encode COLREG rules, such as crossing, head-on, and overtaking, into a state chart that allows for rule-based maneuver techniques, further advancing regulatory compliance. Our emphasis on combining explicit regulatory limits with DWA for ASV path planning is informed by these studies.
This work seeks to formulate an effective path planning algorithm in maritime environments with multiple obstacles. Incorporating the advantages of the enhanced FMM and the DWA for both global and local path planning, the research develops a path planning framework that employs a multi-strategy fusion approach, thus enabling efficient navigation of maritime vessels within intricate environments replete with obstacles. The proposed approach is specifically designed for the safe navigation of underactuated maritime vessels. The enhanced FMM is employed for initial global path planning, facilitating the determination of a safe and optimal path from the origin to the target location. Grounded in the kinematic modeling of underactuated maritime vessels, real-time motion control is executed, and in conjunction with the smoothing of spline curves and the local real-time obstacle avoidance provided by the DWA algorithm, the proposed framework evolves into an autonomous system. The contributions of this work can be summarized as follows:
  • This study proposes an innovative fusion framework for the trajectory planning of underactuated ASVs. By integrating a global path planner based on the FMM with a local obstacle avoidance strategy leveraging the DWA, the framework enhances adaptability to dynamic obstacles in complex maritime environments, while simultaneously accommodating the kinematic and dynamic specifications of the underactuated ASV.
  • The proposed algorithm significantly improves upon traditional single-paradigm approaches by seamlessly optimizing both global path smoothness and local reactivity. Through an enhanced FMM formulation for efficient global path planning and a refined DWA strategy for real-time obstacle avoidance, this work achieves superior performance than traditional approaches.
  • Extensive results validate the effectiveness of the fusion algorithm, providing a quantitative analysis of its planning performance, including metrics such as path length, planning smoothness, and avoidance success rate. Furthermore, an evaluation of the associated control law demonstrates the algorithm’s compatibility, offering a solid foundation for future implementation in maritime navigation systems.
The sections of this article can be organized as follows: Section 2 establishes a kinematic model of an underactuated ASV; Section 3 introduces the two planning algorithms used in this work; Section 4 introduces the fusion path planning algorithm proposed in this work; Section 5 provides the experimental verification of the algorithm we present for different scenarios; and Section 6 summarizes the contents of this work.

2. Underactuated ASV Motion Model

To clearly describe the ASV motion model and differentiate between surge, sway, and yaw movements, a body-fixed coordinate system and earth-fixed coordinate system are established, as shown in Figure 1 The body-fixed frame, which represents the velocities in surge, sway, and yaw, and the earth-fixed frame, conveys the vessel’s position P ( x , y ) . Additionally, the vessel’s center of geometry (CoG) is utilized as the origin of the body frame coordinate system. This work is mainly concerned with the path planning and motion control of an ASV in the horizontal direction. When the motion of the ASV is constrained to the horizontal plane, the dynamics associated with heave, roll, and pitch are considered insignificant. The mathematical formulation of the ASV’s horizontal steering can be articulated as follows:   
η ˙ = J ( ψ ) v , M v ˙ = C ( v ) v D ( v ) v + τ ,
with η = [ x y ψ ] T , v = [ u v r ] T , τ = [ τ u 0 τ r ] T ,
J ( ψ ) = cos ( ψ ) sin ( ψ ) 0 sin ( ψ ) cos ( ψ ) 0 0 0 1 , M = m 11 0 0 0 m 22 0 0 0 m 33 , C ( v ) = 0 0 m 22 v 0 0 m 11 u m 22 v m 11 u 0 , D ( v ) = X u + X | u | u | u | 0 0 0 Y v + Y | v | v | v | 0 0 0 N r + N | r | r | r | ,
where
m 11 = m X u ˙ , m 22 = m Y v ˙ , m 33 = I z N r ˙ ,
wherein ψ is the yaw angle relative to the X e -axis, m denotes the mass of the vessel, I z signifies the vessel’s moment of inertia concerning the Z b -axis within the body-fixed coordinate system, and x g identifies the position of the vessel’s center of gravity within the same frame. The variables τ u and τ r are indicative of the surge force and yaw moment, respectively, within the body-fixed coordinate system. Furthermore, additional symbols are characterized as hydrodynamic derivatives [41]. For example, the hydrodynamic added mass force Y experienced along the y-axis as a result of an acceleration u ˙ in the x-direction is expressed by Y = Y u ˙ u ˙ u in conjunction with Y u ˙ = Y / u ˙ .
Slow-to-fast vessel applications are referred to by the high-order nonlinear damping terms (i.e., X | u | u | u | , Y | v | v | v | , and  N | r | r | r | ). These factors are frequently ignored at low speeds in order to make control system analysis and design simpler. The ASV is kept sailing at a slow speed for the validation of the method. The yaw angular velocity r, longitudinal sway velocity v, and sway velocity u are all sufficiently small under these circumstances to support the exclusion of certain coupling elements from the M, C, and D matrices [41].
Assuming we can determine the vessel’s longitudinal acceleration and yaw rate, the simplified surge dynamics in (1) convert the commanded longitudinal acceleration ( α ) into surge thrust ( τ u ):
τ u = d 11 u + m 22 v r + m 11 α .
The yaw dynamics in (1) give
m 33 r ˙ = τ r d 33 r ( m 22 m 11 ) u v ,
r ˙ = 1 T r ( r r m ) ,
where T r is the yaw response time constant and ( r m ) is the measured yaw rate from the gyrocompass or inertial measurement units (IMUs). The necessary yaw moment τ r can be given by
τ r = m 33 r r m T r + d 33 r + ( m 22 m 11 ) u v
Typically, the velocities, both linear and angular, are represented through a series of nonlinear generic affine inputs related to forces and torques. Consequently, the complexity of the problem can be mitigated by employing angular velocity and linear acceleration as the control laws within the system. The kinematic model of the underactuated ASV is thus derived as follows:
s ˙ ( t ) = f ( s ( t ) , u ( t ) ) = u ( t ) cos ψ ( t ) v ( t ) sin ψ ( t ) u ( t ) sin ψ ( t ) + v ( t ) cos ψ ( t ) r ( t ) a ( t ) m 11 m 22 u ( t ) r ( t ) d 22 m 22 v ( t ) ,
where d 22 = Y v , s ( t ) = [ x ( t ) y ( t ) ψ ( t ) u ( t ) v ( t ) ] T , and  u ( t ) = [ a ( t ) r ( t ) ] T facilitate the derivation of control laws ( a ( t ) and r ( t ) ) aimed at achieving optimal navigation performance. This is contingent upon meeting a diverse set of criteria, including ensuring a fixed terminal position for the underactuated vessel and maintaining its trajectories within acceptable limits, while concurrently bounding the velocity as indicated by u and v.

3. Related Algorithms for ASV Path Planning

3.1. Fast Marching Method

The FMM is a widely acknowledged method devised to solve the Eikonal Equation (9). It is extensively utilized across numerous scientific and engineering fields. FMM provides a remarkably efficient and numerically stable mechanism for computing travel time fields. Its core principle involves the simulation of wavefront advancement while iteratively updating travel times as the wave propagates, thereby ensuring the solution’s global optimality is maintained. With a computational complexity of O ( N l o g N ) , where N denotes the number of grid points, FMM has garnered significant adoption in scenarios requiring rapid and accurate path planning.
| T ( x , y ) | = 1 F ( x , y ) ,
where T ( x , y ) signifies the travel time from an origin point to a destination P ( x , y ) , and  F ( x , y ) represents the speed function. In maritime environments, the  F ( x , y ) can include factors such as water currents, obstacle density, and navigational constraints, thereby facilitating the modeling of complex, non-uniform scenarios. The algorithm discretizes the environment into a regular grid, assigns travel costs to each cell, and propagates the wavefront from the source. By iteratively selecting the grid point with the minimum current cost and updating its adjacent points, the FMM ensures that the wavefront extends in the direction of increasing travel time, thus maintaining numerical stability and precision. The efficacy of the FMM can be attributed to its ability to determine a globally optimal trajectory while accommodating constraints such as obstacle navigability and variable speed conditions. This functionality makes the FMM particularly beneficial for applications that require a reliable initial trajectory. Additionally, FMM can serve as a foundational component within hybrid methods, integrating with localized optimization strategies to refine the final path. In the design of multi-strategy path planning frameworks, FMM provides the theoretical and computational groundwork for subsequent enhancement phases, thereby guaranteeing that the overall framework remains both robust and efficient.

3.2. Dynamic Window Approach

The DWA is a real-time motion planning algorithm specifically designed for navigation within dynamic and unpredictable environments. This approach operates by consistently evaluating control commands, including linear acceleration and angular velocities, over a short temporal interval, as considered in this work. Unlike global planners, which formulate an overarching path before implementation, the DWA prioritizes local trajectory optimization. This prioritization facilitates the rapid adjustment of the ASV in response to environmental changes, such as the appearance of moving obstacles or modifications to navigational constraints.
The fundamental methodology of DWA involves the delineation of a “dynamic window” predicated on the robot’s current velocity, acceleration limits, and kinematic constraints. This window delineates the feasible range of velocity commands executable within a limited time frame. For each velocity combination within the window, DWA computes a cost function to ascertain the optimal control command. The typical structure of the cost function is delineated as follows:
J ( a , r ) = w path · d path ( a , r ) + w gcal · d gcal ( a , r ) + w cbstacle · d obstacle ( a , r ) ,
where a denotes the linear acceleration, r the angular velocity, and  d p a t h , d g o a l , and d o b s t a c l e signify the distance from the global path, the distance from the target point, and the distance from obstacles, respectively.  w p a t h , w g o a l , and w o b s t a c l e are weighting factors that mediate path adherence, goal-directed movement, and obstacle avoidance. The terms J ( a , r ) quantify the corresponding penalties for deviation from the planned trajectory, regression from the goal, and proximity to obstacles. By minimizing J ( a , r ) , DWA selects motion control laws that best balance the competing objectives of safety, efficiency, and smooth navigation.
In maritime applications, DWA’s adaptability constitutes a significant advantage. It possesses the capacity to facilitate real-time adjustments of a vessel’s trajectory in reaction to dynamic conditions, such as the unforeseen appearance of other vessels, fluctuating currents, or unanticipated hazards. By persistently recalculating the optimal control laws, DWA ensures that the vessel persists on a safe and efficient course. Furthermore, when embedded within a multi-strategy path planning framework, DWA augments global methods such as the FMM. While the global planner generates a broad, long-term route, DWA refines this path in real time, ensuring secure passage through dynamic environments. Consequently, the principal research focus of this work pertains to effectively fortifying the synergy between global and local planning methods, thereby delivering robust and adaptable solutions for complex maritime navigation tasks.

4. Improved FMM-DWA Path Planning Framework

Within complex maritime settings, this work introduces an integrated path planning framework that combines an improved FMM and DWA, as depicted in Figure 2. This framework strives to harness the advantages of both methodologies by merging global path optimization with local obstacle avoidance, thereby addressing various challenges such as areas of high obstacle density, dynamic vessel interactions, and uncertain navigation conditions. The comprehensive framework is fundamentally segmented into two components:
Integration of planning strategies: The refined FMM and DWA algorithms function in a harmonious manner within this framework. The FMM enables global path planning, ensuring the vessel selects the optimal route at the macro level. The DWA addresses local path modifications, adapting in real time to dynamic obstacles and environmental variations. Through the alternating effects of global path planning and local obstacle avoidance, this framework can adeptly manage diverse challenges in complex maritime environments.
Adaptive Re-planning: When substantial alterations in environmental conditions transpire (e.g., the emergence of new static obstacles or alterations in the motion patterns of dynamic obstacles), the framework automatically initiates path re-planning. The enhanced FMM devises a new global path, while the DWA continues to refine locally based on this updated path, ensuring that the navigation trajectory remains in an optimal state.

4.1. Improved FMM Global Path Planning

4.1.1. Eight-Direction Movement and Weight Adjustment

The traditional FMM is confined to employing four orthogonal directions—north, south, east, and west—in path planning. This constraint often results in paths characterized by excessive linearity and a lack of smoothness, particularly during directional transitions, which may consequently lead to abrupt turns. To address this limitation, this work incorporates diagonal movements, extending the conventional FMM algorithm to encompass a total of eight directions, thereby enhancing the flexibility and smoothness of path planning. Moreover, this research introduces a dynamic adjustment mechanism for the direction-specific costs within the FMM algorithm, considering factors such as obstacle density, path smoothness, and goal-oriented guidance. Specifically, the cost associated with each direction in the path planning process is decomposed into three components: the influence of obstacles, the influence of path smoothness, and the influence of goal guidance. The formula for calculating these costs is presented as follows:
Cos t n = w obs · D n + w smooth · S n + w goal · G n ,
where w obs signifies the weight factor for obstacle influence, w smooth represents the weight factor for path smoothness, w goal indicates the weight factor for goal guidance, D n denotes the density of obstacles in the n-th direction, S n corresponds to the cost term associated with path smoothness, and  G n indicates the angular cost between the n-th direction and the goal direction.

4.1.2. Cost Field Construction

The cost field constitutes an essential element of the FMM algorithm, functioning as the composite structure for the cost value correlated with each grid point within the context of path planning. This work undertakes a thorough formulation of the cost field by incorporating multiple factors, such as maritime regions, static obstacles, and dynamic obstacles, to enable obstacle avoidance while complying with the ASV’s movement constraints. Specifically, the cost field (12) delineates cost allocations across diverse zone types: land areas are assigned a cost of infinity (), indicating their impassability, whereas maritime regions are accorded a fundamental cost value, with the effects of static and dynamic obstacles assessed through distinct modeling approaches.
C ( i , j ) = , if Position P ( i , j ) Ξ C ocean , otherwise
where Ξ denotes the land area, and  C ocean = 1 signifies the basic cost of maritime areas. Subsequently, regarding the cost impact of static obstacles, the cost associated with them is determined based on their distance from the surrounding area and the degree of influence, modeled through a Gaussian function. The formula for calculating the cost of static obstacles is as follows:
C ( i , j ) = , if ( l a t i , l o n i ) ( l a t s o l , l o n s o l ) < r inf C ocean + C static , if the distance is within the effective range
where ( l a t s o l , l o n s o l ) denotes the central position of the static obstacle, r inf signifies the radius of the impassable area, and  P static represents the cost weight of the static obstacle. With respect to the cost models of dynamic obstacles, this study models their impact on the surrounding area through the superimposition of multiple Gaussian layers, employing the following calculation formula:
C dynamic ( i , j ) = k = 1 K A k · exp ( β k · d dyn ( i , j ) ) ,
where d dyn ( i , j ) denotes the distance from point ( i , j ) to the center of the dynamic obstacle, and A k and β k denote the amplitude and decay factor of the k-th Gaussian function, respectively. Ultimately, the overall cost value C total ( i , j ) (15) encompasses the fundamental cost of the maritime area, the influence of static obstacles, and the influence of dynamic obstacles. This cost field model ensures the path circumvents both static and dynamic obstacles while planning the optimal path of the ASV, thereby enhancing the efficiency and safety of the navigation.
C total ( i , j ) = C ocean + C static ( i , j ) + C dynamic ( i , j ) .

4.1.3. Path Smoothing

Although the FMM algorithm can provide theoretically optimal paths, the generated paths often contain a large number of sharp turns. Such paths may not be conducive to actual navigation, especially in narrow or complex environments where they may lead to a large turning radius. To improve the smoothness and efficiency of navigation, this study introduces a parameterized spline interpolation method to smooth the discrete paths generated by FMM. Specifically, we adjust the smoothing factor to control the smoothness of the path, thereby optimizing the path’s smoothness while maintaining the optimality of the global path. Using the B-spline interpolation method, we performed parameterized spline interpolation on the path point sequence to generate a smoother path. For the discrete path point sequence { ( x 1 , y 1 ) , ( x 2 , y 2 ) , , ( x N , y N ) } generated by FMM, we generate a smooth path { x ( t ) , y ( t ) , t [ 0 , 1 ] } through spline interpolation. The optimized path point sequence is { ( x j ( t ) , y j ( t ) ) , j = 1 , 2 , , M } , where M > N to ensure the continuity and refinement of the path. This process significantly reduces the sharp turns in the path and improves the smoothness and efficiency of navigation.

4.1.4. Efficient Obstacle Inflation

In complex maritime environments, it is necessary not only to avoid explicitly marked static obstacles but also to consider a safety buffer zone between the vessel and obstacles to prevent collisions caused by positioning errors or the sudden appearance of dynamic obstacles. Therefore, this study applies efficient inflation processing in the environmental matrix to ensure that path planning effectively avoids obstacles while maintaining a necessary safety distance. The basic process of the inflation operation uses a binary inflation method, which gradually expands the obstacle area to form a safety buffer zone and sets the expanded area as impassable.
The implementation steps of the inflation operation are as follows: the initial environmental matrix is Ψ 0 , and after d iterations of inflation, the inflated environmental matrix Ψ k is generated:
Ψ k + 1 = dilate ( Ψ k ) , k = 0 , 1 , , d 1 .
The cost of the inflated obstacle area is set to infinity () to ensure that this area is impassable in path planning. The specific cost function is
Φ expanded ( x , y ) = , if Ψ d ( x , y ) = 1 Φ ( x , y ) , otherwise
where Ψ d ( x , y ) represents the value of the environmental matrix after d iterations of inflation. If the value is 1, it indicates an obstacle area; otherwise, it indicates a passable area. The cost of the inflated obstacle area Φ expanded ( x , y ) is set to infinity () to ensure that the ASV cannot enter these areas during path planning.
In order to enhance the efficiency of the inflation process, this work employs a four-connected structural element (18) operation, facilitating the consideration of neighborhood expansion exclusively in the vertical and horizontal directions, namely up, down, left, and right. Consequently, the inflation operation is restricted to horizontal and vertical expansions of the obstacle area, thereby circumventing the impact of diagonal directions and enhancing the computational efficiency of the inflation process.
S = 0 1 0 1 1 1 0 1 0 .
Additionally, inflation processing not only circumvents static obstacles effectively but also establishes a requisite safety buffer zone for path planning, ensuring that the vessel maintains an adequate safety distance from obstacles during real-world navigation. By means of efficient obstacle inflation processing, the improved FMM algorithm can avert collisions between the vessel and obstacles in path planning and enhance the overall safety and reliability of the route.

4.1.5. Search Algorithm Overview

During the path planning process, we dynamically adjust the cost of each direction based on the dynamic environment information. Specifically, for each node ( x , y ), its cost is updated in the following way:
New . Cos t = C ( x , y ) + Adjusted . Cos t i .
When the cost of a node, N e w . C o s t , is lower than that of a neighboring node, the node’s cost is updated, and it is added to the open list, f r o n t i e r . The corresponding pseudocode is presented in Algorithm 1.
Algorithm 1 FMM algorithm for weight update and shortest path calculation.
1:
Input: Start node ( x start , y start ) , Goal node ( x goal , y goal ) , Obstacle map, Grid dimensions ( grid . width , grid . height )
2:
Output: Shortest path cost from start to goal
3:
Initialize:
4:
for each node ( x , y ) in grid do
5:
     C ( x , y )
6:
end for
7:
C ( x start , y start ) 0
8:
Initialize the f r o n t i e r set:
9:
f r o n t i e r  
10:
Add ( x start , y start ) to f r o n t i e r
11:
while  f r o n t i e r is not empty do
12:
     ( x , y ) Node with minimum cost in f r o n t i e r
13:
    Remove ( x , y ) from f r o n t i e r
14:
    for each neighboring node ( x + Δ x i , y + Δ y i ) , i = 1 to 8 do
15:
         N e w . C o s t = C ( x , y ) + Adjusted . Cos t i
16:
        if  N e w . C o s t  < C ( x + Δ x i , y + Δ y i )  then
17:
            C ( x + Δ x i , y + Δ y i ) N e w . C o s t
18:
           Add ( x + Δ x i , y + Δ y i ) to f r o n t i e r
19:
        end if
20:
    end for
21:
    if  C ( x goal , y goal ) is updated then
22:
        break
23:
    end if
24:
end while
25:
return  C ( x goal , y goal )
Through this approach, the cost associated with each node is iteratively updated until the optimal pathway from the initial to the terminal point is ascertained. The benefit of this methodology lies in its ability to account for the influence of static impediments while simultaneously incorporating goal-oriented guidance and pathway smoothness, thereby producing a safe and uninterrupted trajectory.

4.2. Improved DWA Local Path Planning

The improved DWA algorithm optimizes the traditional DWA by incorporating a simplified dynamic model of the vessel and enhancing path planning robustness and practicality through dynamic obstacle prediction and global path tracking. The following is a detailed description of the improved DWA algorithm.

4.2.1. Dynamic Window Sampling

In the improved DWA algorithm, control laws include acceleration a and angular velocity r. The sampling space for these control laws is expanded based on the consideration of the vessel’s dynamic limitations. To improve sampling accuracy, this work refines the sampling of acceleration and angular velocity, specifically defined as
A = { a i a i = a min + i Δ a , i = 0 , 1 , , N a } , R = { r j r j = r min + j Δ r , j = 0 , 1 , , N r } ,
where a min is the minimum acceleration, Δ a is the acceleration interval, N a is the number of acceleration samples, r min is the minimum angular velocity, Δ r is the angular velocity interval, and N r is the number of angular velocity samples. Thus, the sampling space for control laws is
Ω = { ( a i , r j ) a i A , r j R } .
This sampling space considers the vessel’s acceleration and angular velocity limitations, ensuring that the generated path complies with the vessel’s dynamic constraints while effectively avoiding obstacles.
Each set of sampled control laws ( a , r ) requires trajectory simulation to predict the motion trajectory of the vessel. The simulation results serve as inputs to the evaluation function. Based on the kinematic model of the underactuated ASV constructed in Equation (8), the state updates of the vessel in future time steps are as follows:
s ( t + Δ t ) = s ( t ) + Δ t f ( s ( t ) , u ( t ) ) .

4.2.2. COLREG-Compliant Obstacle Avoidance Rules

In the path planning of the ASV, while ensuring the optimality of the planning results, compliance with COLREG rules is an important issue for ensuring safe interaction between ships. This paper takes COLREG compliance as a supplementary condition for its collision avoidance rules. By analyzing the relative position and heading of the ASV in the forward prediction window and the dynamic obstacles (other ships), violations in the path planning process are filtered out.
This work categorizes collision scenarios into three critical situations defined by COLREGs (see Figure 3) and applies corresponding steering restrictions:
  • Head-On Situation: The vessels are considered to be on reciprocal routes when the relative angle between the ASV and an obstruction fulfills | 180  − relative_angle_deg |   <   6 . The ASV is required to make a starboard (right) turn in accordance with the COLREG rule. Consequently, port-side turns ω > 0 are prohibited.
  • Starboard Crossing Situation: If 67.5   relative _ angle _ deg   174 , the obstruction approaches from the ASV’s starboard side in the starboard crossing scenario. The ASV must turn starboard as the give-way vessel, and port-side maneuvers are not allowed.
  • Port Crossing Situation: If 186   relative _ angle _ deg   292.5 , the ASV, as the stand-on vessel, must avoid blocking the obstacle’s path during the port crossing. For the purpose of complying with COLREGs, right turns ω < 0 are prohibited.
  • Overtaking Situation: The ASV is recognized as the overtaking vessel if 0 <   relative _ angle _ deg   < 67.5 . The ASV is prohibited from making port-side turns ω > 0 when overtaking in order to ensure safety.

4.2.3. Path Following Based on Global Path

The steering constraint condition is integrated with the COLREG rule to filter the forward trajectory and restrict the ASV steering behavior to be consistent with the rule. This method improves the safety of route planning and provides a rule compliance guarantee for the planning results of the fusion algorithm. The evaluation function J ( a , r ) is used to assess the trajectory quality for each set of control laws and is defined as follows:
J ( a , r ) = w path · D path ( a , r ) + w goal · D goal ( a , r ) + w turn · | r | + k = 1 N obs w avoid d k ( a , r ) + 0.1 ,
where D path ( a , r ) is the deviation of the trajectory from the global path, D goal ( a , r ) is the distance of the trajectory from the target point, d k ( a , r ) is the distance to the k-th dynamic obstacle, and w path , w goal , w turn , and w avoid are the weight coefficients for path deviation, goal distance, turning penalty, and obstacle avoidance penalty, respectively. Through this evaluation function, the DWA algorithm can comprehensively consider trajectory smoothness, proximity to the target point, turning penalty, and obstacle avoidance effects, thereby evaluating the quality of control laws.
To effectively predict the position of dynamic obstacles, the improved DWA algorithm uses a uniform motion model to predict the position of obstacles. Assuming that the motion of obstacles follows a uniform motion model in future moments, the position prediction formula is as follows:
x obs ( t + Δ t ) = x obs ( t ) + v obs ( t ) · Δ t y obs ( t + Δ t ) = y obs ( t ) + v obs ( t ) · Δ t
where x obs ( t ) and y obs ( t ) are the positions of the obstacle at time t, and v obs ( t ) is the velocity of the obstacle. Each dynamic obstacle is predicted based on the velocity and time step in each step, avoiding the problem of static obstacle models being unable to dynamically avoid obstacles.
The improved DWA algorithm has another significant advantage: in addition to dynamic obstacle avoidance, it also enables the vessel to follow a global path. In actual navigation, vessels often need to follow a globally planned path while also dealing with the impact of dynamic obstacles. The improved DWA algorithm can navigate by referring to the global path while avoiding obstacles dynamically, thereby enhancing the accuracy of path following and the stability of navigation. Specifically, the DWA algorithm combines global path planning and local obstacle avoidance strategies. When generating local paths, it prioritizes options close to the global path to ensure that the vessel can follow the global path and effectively avoid obstacles. To make the vessel follow the global path more accurately, a deviation term from the global path is added to the evaluation function to encourage the vessel to choose trajectories close to the global path. The fusion path planning approach can be divided into the following steps:
  • Step 1. Calculate the path deviation based on the distance between the vessel’s current position and the nearest point on the global path and incorporate it into the evaluation function.
  • Step 2. When the vessel deviates significantly from the global path, increase the path deviation penalty to force the vessel to choose a local path close to the global path. This strategy ensures that the vessel remains close to the global path in complex dynamic environments and adjusts its course in time to avoid obstacles.
Among all possible control laws ( a , r ) , the DWA algorithm selects the control laws that minimize the evaluation function. In particular, the following procedures are employed in the DWA re-planning phase for selecting the optimal control strategy: For each set of sampled control laws ( a , r ) , calculate the corresponding evaluation function value J ( a , r ) . Choose the control laws corresponding to the minimum J ( a , r ) as the final control strategy. If all control laws are infeasible (i.e., all trajectories result in collisions or violate COLREGs), a low-speed turning strategy is selected. The aforementioned procedures enable the DWA algorithm to choose the optimal control strategy, dynamically modify the control laws at each time step, and accomplish global path following and efficient local path planning.

5. Experiments, Results and Discussion

This section is dedicated to the validation and evaluation of the improved FMM algorithm and its integration with the DWA algorithm through a series of experiments. The experiments are designed to evaluate three primary objectives:
  • Verification of path planning performance in static complex environments: Our initial objective is to assess the performance of the improved FMM algorithm within static complex environments. This involves an evaluation of the capability of various algorithms to produce optimal paths in settings characterized by multiple obstacles and diverse terrains, thereby verifying the foundational performance of the enhanced FMM.
  • Comprehensive evaluation of algorithm advantages in complex dynamic environments: Subsequently, we concentrate on appraising the multi-strategy fusion planning algorithm, which integrates the enhanced algorithm, focusing on its path planning and obstacle avoidance efficacy in dynamic complex environments.
  • Analysis of the control performance in complex dynamic environments: Finally, we discuss the control performance of the improved FMM-DWA fusion algorithm in complex dynamic environments, considering the underactuated characteristics of the ASVs. We provide a quantitative analysis of the effectiveness and robustness of the planning algorithm for underactuated ASVs.
The experiments test algorithms under various conditions to ensure robust and widely applicable findings. The results will present the effectiveness of the improved FMM algorithm integrated with DWA for maritime navigation. Table 1 details the simulation parameters. Simulations ran on a system with an Intel i7-10510U CPU and NVIDIA GeForce MX250 GPU (Intel Corporation, Santa Clara, CA, USA; NVIDIA Corporation, Santa Clara, CA, USA).
Simulation data are provided by the random generation process in the test environment, with static and dynamic obstacles arranged differently. In each simulation scenario, the distribution and dynamic behavior of obstacles are varied to test the algorithm’s performance in environments of different complexities. The motion of the ASV is simulated using an underactuated kinematic model (8), with control laws (such as acceleration and angular velocity) defined within predetermined constraints. The main objective of the experiment is to evaluate the efficiency of path planning, obstacle avoidance capabilities, and computational performance of the FMM-DWA, integrated algorithm in various dynamic environments.

5.1. Improved FMM Path Planning Performance

In pursuit of a realistic representation, the South China Sea region was chosen, encompassing a geographical range from 10° N to 16° N and 118° E to 126° E (see Figure 4). This area, with its numerous reefs, shoals, and significant maritime traffic routes, presents a dense distribution of obstacles, making it highly suitable for assessing the performance of the enhanced FMM algorithm in global path planning. Leveraging the NaturalEarth dataset from the Cartopy library, we simulated natural obstacles such as reefs and shoals in this region. Additionally, integrating data from vessel tracking networks, we introduced 35 static obstacles and 4 dynamic obstacles to increase the complexity of the environment. The positions of dynamic obstacles were modeled using multi-layer Gaussian functions to create a concentric effect, ensuring effective avoidance of potential threats during path planning. The primary objective of selecting this region was to evaluate the algorithm’s path planning capabilities in a continuous environment with multiple obstacles, providing a foundation for subsequent tests of the integrated algorithm in complex terrain scenarios while avoiding the additional complexity introduced by map rasterization.
The influence of path planning utilizing the improved FMM algorithm within this maritime region is depicted in Figure 5. The black dashed line represents the optimal path planned, with green diamonds and red stars indicating the starting and ending points, respectively. It can be observed from the results that the path successfully avoids all obstacles and is continuous without sharp turns, demonstrating the path optimization effect caused by the eight-direction movement. Brighter areas indicate regions with higher cost values, mainly concentrated around obstacles, forming a clear boundary for avoidance. The maritime areas have lower cost values, and the improved FMM algorithm prioritizes selecting routes with lower costs. Through the visualization of the cost field, the effectiveness and feasibility of the improved FMM algorithm in environments with multiple obstacles are demonstrated.
To further enhance the efficient path planning capabilities of the improved FMM algorithm in complex static environments, we continue to test the South China Sea region with specific latitude and longitude ranges from 12° N to 13° N and 123° E to 124° E (see Figure 6). Compared to larger areas, this region has a more dense and dynamic distribution of obstacles. In the experimental setup, in addition to relying on high-resolution geographic information data loaded by the Cartopy library, we also performed binary dilation processing on static obstacles. Specifically, by setting safety distance parameters, an impassable “safety zone” was created, effectively enhancing the safety and adaptability of path planning. At the same time, to simulate a more complex environment, 20 square white static obstacles were generated within the feasible maritime area.
The experimental result presented in Figure 7 illustrates the benefits of the improved FMM algorithm in complex dynamic environments. A comparative analysis with various traditional path planning algorithms under identical scenario settings was conducted, leading to the observation of planning efficacy. Furthermore, the 200 Monte Carlo (MC) test yielded a comprehensive set of quantitative planning performance measurements (see Figure 8). In terms of path planning smoothness, the improved FMM method outperforms conventional algorithms, with an average path length of 667.87 pixels and 12 turning points, demonstrating its effectiveness in path smoothness. The improved FMM algorithm’s global optimization features produce a path with enhanced smoothness post-processing, yielding a shorter geometric length with fewer turning points, which is superior to traditional planning algorithms and meets the stability requirements for ASV navigation. The experimental visualization and statistical analysis substantiate that the global path planning capabilities of the improved FMM algorithm exhibit substantial comprehensive advantages. These findings provide a robust baseline performance for the subsequent integration of algorithms to address dynamic scenario planning tasks.
Remark 1.
All algorithms were subjected to the same degree of path smoothing and obstacle inflation processing during the experiments, and the DPI (dots per inch) was configured to 100.

5.2. Enhancement of Fusion Algorithm in Dynamic Environments

The aforementioned experimental findings confirm the effectiveness of the enhanced FMM algorithm when applied in complex environments. The algorithm’s superiority in global path planning is evidenced by its ability to determine the optimal navigation trajectory for the ASV. The results indicate that the FMM algorithm excels at generating global paths based on static information, especially in static environments. However, when faced with dynamic obstacles, it shows limitations, as observed in the initial stages of path planning where the ASV fails to modify its trajectory in time to avoid collisions (see Figure 9). This observation indicates that while FMM is effective in static scenarios, its efficacy declines in dynamic environments, necessitating further algorithmic enhancements to improve adaptability and real-time obstacle avoidance. Additionally, the DWA algorithm, as demonstrated in Figure 10, shows proficiency in making adjustments to avoid obstacles. It autonomously modifies the control laws of the ASV to facilitate navigation towards the target while avoiding such barriers. However, the DWA algorithm is constrained by its shortsighted and localized approach to path planning, which can lead to inconsistencies and increased computational complexity in environments characterized by dense or rapidly changing obstacles.
The fusion of FMM and DWA without COLREG rule filtering, as depicted in Figure 11, represents a significant advancement in overcoming the inherent constraints of these individual algorithms. The FMM, which is known for its strong global path planning ability, frequently underperforms in dynamic contexts due to its incapability to respond to real-time changes. In contrast, the DWA performs well in real-time obstacle avoidance but lacks a comprehensive global planning strategy. By combining these two strategies, the shortcomings can be efficiently addressed, combining the benefits of global path planning with the agility required for real-time obstacle avoidance.
This multi-strategy fusion planning approach not only ensures the generation of smooth and safe trajectories within dynamic environments but also avoids collisions that might occur when solely utilizing FMM. The integration facilitates real-time path adjustments in response to environmental changes, thus preserving safety and operational efficiency. Specifically, the fusion algorithm dynamically updates the planned trajectory, enabling the system to navigate through complex and changing environments with minimal latency.
While its capability for real-time obstacle avoidance is noteworthy, DWA may complicate the computation of paths and negatively impact overall efficiency and stability in the presence of numerous obstacles. In Figure 12, we provide the single-step computation time for the demonstration examples presented in Figure 11. Even in instances when re-planning is required, the fusion algorithm maintains consistent computation time and demonstrates dependable real-time performance. This also demonstrates that the proposed fusion algorithm framework can effectively exploit the complementary benefits of the two algorithms.
While maintaining the optimality of planning results, adhering to COLREG rules ensures ASV safety, which will be discussed below. This effort utilizes the COLREG rules as a supplement to the collision avoidance rules before filtering the DWA results. Figure 13 shows the local planning results for various ship-meeting conditions. It can be demonstrated that even if the local obstacle avoidance performance is already available, filtering the COLREG rules can bring the obstacle avoidance effect within the anticipated range. Figure 14 shows two different sets of simulation results. Compared to Figure 11, the compliance of local obstacle avoidance is obvious. Similarly, the tracking performance on the planned path remains consistent. Specifically, we counted the number of re-planning events and rule violations for different algorithms in the form of MC tests, and counted the corresponding rule compliance rate under the condition of 200 groups of MC tests for each algorithm (see Table 2). It is evident that the results are comparable to our findings when planning using a single algorithm, which further supports the validity of the fundamental algorithm we selected for our fusion algorithm framework.

5.3. Fusion Algorithm for Underactuated ASVs Control

The overall framework of our work includes global path planning and local obstacle avoidance of ASVs. In global path planning, an optimal path is actually planned for the current scenario. However, achieving path tracking by the considered ASV entails vessel kinematics. Simultaneously, due to the interference of local obstacles, the actual driving process will eventually need to be re-planned. As a supplement, we employ DWA with rule constraints for local re-planning. In this phase, the vessel kinematics also need to be considered. For this, our experimental demonstration of the control laws aims to demonstrate the effectiveness and agility of the actual control laws provided by the algorithm fusion framework for global path tracking based on this kinematic model. The effectiveness and robustness of the fusion algorithm in adjusting the control laws of underactuated ASVs have been further validated through a comprehensive analysis of its control profile. State-control information for the trajectory from the experiment in Figure 14 was collected for visualization and analysis.
Figure 15a,b show the adjustment in acceleration and angular velocity over time, indicating that frequent adjustments to angular velocity are mainly concentrated in areas with dense dynamic obstacles. In the initial stage, since there are no obstacles, the adjustment of the control laws can quickly accelerate the ASV in the direction of the planned path. After successfully crossing the complex obstacle area, the forward speed gradually increases again, indicating that the algorithm has completed the initial path planning and then made real-time adjustments through DWA to reach the target speed, thereby improving the overall operation efficiency. This dynamic speed adjustment highlights the ability of the algorithm to strike a balance between obstacle avoidance and operation efficiency. The FMM provides a reliable global path, while the DWA dynamically adjusts the speed and heading according to the real-time environmental conditions. In contrast, the stability of the acceleration trend ensures the stable operation of the ASV. This highlights the ability of the fusion algorithm to perform precise obstacle avoidance in complex environments through flexible angular velocity adjustments, while minimizing the instability that may be caused by frequent acceleration or deceleration. The algorithm combines global path planning with local obstacle avoidance and properly allocates control laws to ensure efficient obstacle avoidance and navigation. Figure 15c,d show that the distance between the ASV and the target is decreasing, indicating that the ASV is steadily approaching the target and that there is a brief turnaround due to the need for obstacle avoidance. This highlights the ability of the integrated algorithm to cleverly bypass obstacles and move towards the target under the guidance of global path planning. The consistency between the effectiveness of path planning and dynamic obstacle avoidance confirms the comprehensive performance of the algorithm, which together ensures that the ASV can complete the mission along the optimal trajectory.
In addition, we analyze the impact of control laws on overall navigation from a different perspective. When the control laws’ distribution is compared to the map position, it is clear that to a great extent, the ASV control laws have an expected regularity in the corresponding coverage response. The characteristics of the changes in acceleration and angular velocity on the X coordinate and Y coordinate are those in areas with dense obstacles, the angular velocity adjustment frequency is higher, and the acceleration change is relatively stable (see Figure 15e–h). In particular, in areas with fewer obstacles, the control laws tend to be stable, reflecting the adaptability of the algorithm to different environmental conditions. This control characteristic reflects the algorithm’s precise response to complex marine environments, while minimizing unnecessary adjustments and saving computing resources. The acceleration and angular velocity on the Y coordinate are consistent with those on the X coordinate. In areas with dense dynamic obstacles, angular velocity adjustments dominate, with modest acceleration fluctuations, ensuring the ASV’s stability. The fusion algorithm effectively avoids obstacles using adaptive angular velocity control, while retaining navigation stability and path optimization with stable acceleration adjustment.

6. Conclusions

This study presents the development and efficacy of a hybrid ASV’s path planning algorithm, integrating both improved FMM and DWA. The multi-strategy fusion framework overcomes the inherent limitations of singular algorithmic paradigms by advancing path optimality while ensuring safety and seamless navigation with dynamic obstacles in complex maritime settings. We provided the algorithm parameter priors for the maritime scenario we analyzed, as well as a transparent algorithm fusion pipeline. The notable advancements in path planning success and efficacy in obstacle avoidance highlight its potential applicability and superiority for practical marine applications. Our future research will focus on how to adaptively adjust algorithm weights using learning-based methods and control theory in response to more complex scenarios, broaden the scope of this planning framework, and apply it to real-world scenarios.

Author Contributions

Methodology, C.L.; Software, Y.X.; Investigation, K.L.; Visualization, Y.H.; Supervision, Y.M. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Natural Science Foundation of China (Grant Nos. 52071249 and 62073251).

Data Availability Statement

The original contributions presented in this study are included in the article. The source code is not publicly available due to confidentiality considerations. Interested researchers are welcome to contact the corresponding author to discuss potential access for non-commercial academic purposes.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Zhou, X.; Wu, P.; Zhang, H.; Guo, W.; Liu, Y. Learn to navigate: Cooperative path planning for unmanned surface vehicles using deep reinforcement learning. IEEE Access 2019, 7, 165262–165278. [Google Scholar] [CrossRef]
  2. Zhou, C.; Gu, S.; Wen, Y.; Du, Z.; Xiao, C.; Huang, L.; Zhu, M. The review unmanned surface vehicle path planning: Based on multi-modality constraint. Ocean Eng. 2020, 200, 107043. [Google Scholar] [CrossRef]
  3. Wang, N.; Xu, H. Dynamics-constrained global-local hybrid path planning of an autonomous surface vehicle. IEEE Trans. Veh. Technol. 2020, 69, 6928–6942. [Google Scholar] [CrossRef]
  4. Krell, E.; King, S.A.; Carrillo, L.R.G. Autonomous Surface Vehicle energy-efficient and reward-based path planning using Particle Swarm Optimization and Visibility Graphs. Appl. Ocean Res. 2022, 122, 103125. [Google Scholar] [CrossRef]
  5. Chen, Z.; Zhang, Y.; Zhang, Y.; Nie, Y.; Tang, J.; Zhu, S. A hybrid path planning algorithm for unmanned surface vehicles in complex environment with dynamic obstacles. IEEE Access 2019, 7, 126439–126449. [Google Scholar] [CrossRef]
  6. Zhang, Y.; Sun, X.; Chen, J.; Cheng, C. Spatial patterns and characteristics of global maritime accidents. Reliab. Eng. Syst. Saf. 2021, 206, 107310. [Google Scholar] [CrossRef]
  7. Öztürk, Ü.; Akdağ, M.; Ayabakan, T. A review of path planning algorithms in maritime autonomous surface ships: Navigation safety perspective. Ocean Eng. 2022, 251, 111010. [Google Scholar] [CrossRef]
  8. Li, F.F.; Du, Y.; Jia, K.J. Path planning and smoothing of mobile robot based on improved artificial fish swarm algorithm. Sci. Rep. 2022, 12, 659. [Google Scholar] [CrossRef]
  9. Kuwata, Y.; Wolf, M.T.; Zarzhitsky, D.; Huntsberger, T.L. Safe maritime autonomous navigation with COLREGS, using velocity obstacles. IEEE J. Ocean. Eng. 2013, 39, 110–119. [Google Scholar] [CrossRef]
  10. To, W.M.; Lee, P.K. China’s maritime economic development: A review, the future trend, and sustainability implications. Sustainability 2018, 10, 4844. [Google Scholar] [CrossRef]
  11. Vagale, A.; Oucheikh, R.; Bye, R.T.; Osen, O.L.; Fossen, T.I. Path planning and collision avoidance for autonomous surface vehicles I: A review. J. Mar. Sci. Technol. 2021, 26, 1292–1306. [Google Scholar] [CrossRef]
  12. Wang, N.; Zhang, Y.; Ahn, C.K.; Xu, Q. Autonomous pilot of unmanned surface vehicles: Bridging path planning and tracking. IEEE Trans. Veh. Technol. 2021, 71, 2358–2374. [Google Scholar] [CrossRef]
  13. Lai, J.; Ren, Z.; Wu, Z.; Tan, Q.; Xie, S. Learning-based real-time optimal control of unmanned surface vessels in dynamic environment with obstacles. Ocean Eng. 2025, 335, 121505. [Google Scholar] [CrossRef]
  14. Park, S.; Cap, M.; Alonso-Mora, J.; Ratti, C.; Rus, D. Social trajectory planning for urban autonomous surface vessels. IEEE Trans. Robot. 2020, 37, 452–465. [Google Scholar] [CrossRef]
  15. DeLoura, M. Game Programming Gems 2; Charles River Media, Inc.: Needham Heights, MA, USA, 2001. [Google Scholar]
  16. Mannarini, G.; Subramani, D.N.; Lermusiaux, P.F.; Pinardi, N. Graph-search and differential equations for time-optimal vessel route planning in dynamic ocean waves. IEEE Trans. Intell. Transp. Syst. 2019, 21, 3581–3593. [Google Scholar] [CrossRef]
  17. Sanchez-Ibanez, J.R.; Pérez-del Pulgar, C.J.; García-Cerezo, A. Path planning for autonomous mobile robots: A review. Sensors 2021, 21, 7898. [Google Scholar] [CrossRef]
  18. Tan, C.S.; Mohd-Mokhtar, R.; Arshad, M.R. A comprehensive review of coverage path planning in robotics using classical and heuristic algorithms. IEEE Access 2021, 9, 119310–119342. [Google Scholar] [CrossRef]
  19. Flores-Caballero, G.; Rodríguez-Molina, A.; Aldape-Pérez, M.; Villarreal-Cervantes, M.G. Optimized path-planning in continuous spaces for unmanned aerial vehicles using meta-heuristics. IEEE Access 2020, 8, 176774–176788. [Google Scholar] [CrossRef]
  20. Xiang, D.; Lin, H.; Ouyang, J.; Huang, D. Combined improved A* and greedy algorithm for path planning of multi-objective mobile robot. Sci. Rep. 2022, 12, 13273. [Google Scholar] [CrossRef]
  21. Wang, X.; Zhang, H.; Liu, S.; Wang, J.; Wang, Y.; Shangguan, D. Path planning of scenic spots based on improved A* algorithm. Sci. Rep. 2022, 12, 1320. [Google Scholar] [CrossRef]
  22. Wang, J.; Li, B.; Meng, M.Q.H. Kinematic Constrained Bi-directional RRT with Efficient Branch Pruning for robot path planning. Expert Syst. Appl. 2021, 170, 114541. [Google Scholar] [CrossRef]
  23. Tao, F.; Ding, Z.; Fu, Z.; Li, M.; Ji, B. Efficient path planning for autonomous vehicles based on RRT* with variable probability strategy and artificial potential field approach. Sci. Rep. 2024, 14, 24698. [Google Scholar] [CrossRef]
  24. Suo, Y.; Chen, X.; Yue, J.; Yang, S.; Claramunt, C. An Improved Artificial Potential Field Method for Ship Path Planning Based on Artificial Potential Field—Mined Customary Navigation Routes. J. Mar. Sci. Eng. 2024, 12, 731. [Google Scholar] [CrossRef]
  25. Ghiaskar, A.; Amiri, A.; Mirjalili, S. Polar fox optimization algorithm: A novel meta-heuristic algorithm. Neural Comput. Appl. 2024, 36, 20983–21022. [Google Scholar] [CrossRef]
  26. Mylonopoulos, F.; Polinder, H.; Coraddu, A. A comprehensive review of modeling and optimization methods for ship energy systems. IEEE Access 2023, 11, 32697–32707. [Google Scholar] [CrossRef]
  27. Mirjalili, S.; Mirjalili, S.M.; Lewis, A. Grey wolf optimizer. Adv. Eng. Softw. 2014, 69, 46–61. [Google Scholar] [CrossRef]
  28. Liu, D.; Shi, G.; Hirayama, K. Vessel scheduling optimization model based on variable speed in a seaport with one-way navigation channel. Sensors 2021, 21, 5478. [Google Scholar] [CrossRef]
  29. Wu, M.; Zhang, A.; Gao, M.; Zhang, J. Ship motion planning for MASS based on a multi-objective optimization HA* algorithm in complex navigation conditions. J. Mar. Sci. Eng. 2021, 9, 1126. [Google Scholar] [CrossRef]
  30. Sethian, J.A. Fast marching methods. SIAM Rev. 1999, 41, 199–235. [Google Scholar] [CrossRef]
  31. Yan, X.p.; Wang, S.w.; Ma, F.; Liu, Y.c.; Wang, J. A novel path planning approach for smart cargo ships based on anisotropic fast marching. Expert Syst. Appl. 2020, 159, 113558. [Google Scholar] [CrossRef]
  32. Wu, Y.; Wang, T.; Liu, S. A Review of Path Planning Methods for Marine Autonomous Surface Vehicles. J. Mar. Sci. Eng. 2024, 12, 833. [Google Scholar] [CrossRef]
  33. Caharija, W.; Pettersen, K.Y.; Bibuli, M.; Calado, P.; Zereik, E.; Braga, J.; Gravdahl, J.T.; Sørensen, A.J.; Milovanović, M.; Bruzzone, G. Integral line-of-sight guidance and control of underactuated marine vehicles: Theory, simulations, and experiments. IEEE Trans. Control Syst. Technol. 2016, 24, 1623–1642. [Google Scholar] [CrossRef]
  34. Fox, D.; Burgard, W.; Thrun, S. The dynamic window approach to collision avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef]
  35. Malone, N.; Chiang, H.T.; Lesser, K.; Oishi, M.; Tapia, L. Hybrid dynamic moving obstacle avoidance using a stochastic reachable set-based potential field. IEEE Trans. Robot. 2017, 33, 1124–1138. [Google Scholar] [CrossRef]
  36. Saenrit, K.; Phaoharuhansa, D. Development of Obstacle Avoidance Control System Using Modified Attractive Equations of Gaussian Potential Function. Int. J. Mech. Eng. Robot. Res. 2024, 13, 408–413. [Google Scholar] [CrossRef]
  37. Wang, Z.; Liang, Y.; Gong, C.; Zhou, Y.; Zeng, C.; Zhu, S. Improved dynamic window approach for Unmanned Surface Vehicles’ local path planning considering the impact of environmental factors. Sensors 2022, 22, 5181. [Google Scholar] [CrossRef]
  38. Han, S.; Wang, Y.; Wang, L.; He, H. Automatic berthing for an underactuated unmanned surface vehicle: A real-time motion planning approach. Ocean Eng. 2021, 235, 109352. [Google Scholar] [CrossRef]
  39. Namgung, H.; Kim, J.S. Collision risk inference system for maritime autonomous surface ships using COLREGs rules compliant collision avoidance. IEEE Access 2021, 9, 7823–7835. [Google Scholar] [CrossRef]
  40. Namgung, H. Local route planning for collision avoidance of maritime autonomous surface ships in compliance with COLREGs rules. Sustainability 2021, 14, 198. [Google Scholar] [CrossRef]
  41. Fossen, T.I. Handbook of Marine Craft Hydrodynamics and Motion Control; John Wiley & Sons: Hoboken, NJ, USA, 2011. [Google Scholar]
Figure 1. Dynamic model of an underactuated ASV.
Figure 1. Dynamic model of an underactuated ASV.
Jmse 13 01357 g001
Figure 2. The overall framework of multi-strategy fusion path planning for ASV.
Figure 2. The overall framework of multi-strategy fusion path planning for ASV.
Jmse 13 01357 g002
Figure 3. Overall diagram of COLREG rules: (a) Head-on situation; (b) Starboard crossing situation; (c) Port crossing situation; (d) Overtaking situation.
Figure 3. Overall diagram of COLREG rules: (a) Head-on situation; (b) Starboard crossing situation; (c) Port crossing situation; (d) Overtaking situation.
Jmse 13 01357 g003
Figure 4. Experimental scenario 1. The green dots indicate static obstacles, while the red dotted lines outline concentric circles, symbolizing the potential range of motion exhibited by dynamic obstacles.
Figure 4. Experimental scenario 1. The green dots indicate static obstacles, while the red dotted lines outline concentric circles, symbolizing the potential range of motion exhibited by dynamic obstacles.
Jmse 13 01357 g004
Figure 5. Path planning based on improved FMM algorithm. This figure illustrates the path planning effect of the improved FMM algorithm in the selected maritime area. The black dashed line represents the optimal path planned, with green diamonds and red stars indicating the starting and ending points, respectively. The color gradient from purple to yellow indicates the cost of the path.
Figure 5. Path planning based on improved FMM algorithm. This figure illustrates the path planning effect of the improved FMM algorithm in the selected maritime area. The black dashed line represents the optimal path planned, with green diamonds and red stars indicating the starting and ending points, respectively. The color gradient from purple to yellow indicates the cost of the path.
Jmse 13 01357 g005
Figure 6. Experimental scenario 2.
Figure 6. Experimental scenario 2.
Jmse 13 01357 g006
Figure 7. Comparison of path planning algorithms. (a) A*; (b) Dijkstra; (c) RRT; (d) FMM. Each panel illustrates distinct navigation strategies through obstacles, from the green start point to the red endpoint.
Figure 7. Comparison of path planning algorithms. (a) A*; (b) Dijkstra; (c) RRT; (d) FMM. Each panel illustrates distinct navigation strategies through obstacles, from the green start point to the red endpoint.
Jmse 13 01357 g007
Figure 8. Comparison of statistical indicators of various path planning algorithms. The figure contains the statistical data of the four algorithms on three indicators: (a) unsmoothed path length; (b) unsmoothed sharp turns (≤15°); and (c) smoothed nodes.
Figure 8. Comparison of statistical indicators of various path planning algorithms. The figure contains the statistical data of the four algorithms on three indicators: (a) unsmoothed path length; (b) unsmoothed sharp turns (≤15°); and (c) smoothed nodes.
Jmse 13 01357 g008
Figure 9. Performance of the single-FMM algorithm in dynamic environments. Panel (a) shows the initial planned path from the start (green star) to the goal (red star). Panels (b,c) present the ASV’s adjustments in response to static obstacles (white squares) located midway along the path. Panel (d) indicates the detection of a collision due to the algorithm’s inability to avoid dynamic obstacles (red triangles).
Figure 9. Performance of the single-FMM algorithm in dynamic environments. Panel (a) shows the initial planned path from the start (green star) to the goal (red star). Panels (b,c) present the ASV’s adjustments in response to static obstacles (white squares) located midway along the path. Panel (d) indicates the detection of a collision due to the algorithm’s inability to avoid dynamic obstacles (red triangles).
Jmse 13 01357 g009
Figure 10. Performance of the single-DWA algorithm in dynamic environments. Panel (a) shows the initial planned path from the start (green star) toward the target point (red star). Panels (bd) represent the ASV’s adjustments in response to static obstacles (white squares) and dynamic obstacles (red triangles) located midway along the path.
Figure 10. Performance of the single-DWA algorithm in dynamic environments. Panel (a) shows the initial planned path from the start (green star) toward the target point (red star). Panels (bd) represent the ASV’s adjustments in response to static obstacles (white squares) and dynamic obstacles (red triangles) located midway along the path.
Jmse 13 01357 g010
Figure 11. Performance the improved FMM-DWA algorithm’s fusion in dynamic environments. Panel (a) shows the initial path planning with the global path (white) and ASV’s starting point (green star). Panels (b,c) show the halfway adjustments, with the real path (yellow) deviating from the global route to avoid static obstacles (white squares) and dynamic obstacles (red triangles). Panel (d) presents the final approach to the destination (red star) with continued path optimization.
Figure 11. Performance the improved FMM-DWA algorithm’s fusion in dynamic environments. Panel (a) shows the initial path planning with the global path (white) and ASV’s starting point (green star). Panels (b,c) show the halfway adjustments, with the real path (yellow) deviating from the global route to avoid static obstacles (white squares) and dynamic obstacles (red triangles). Panel (d) presents the final approach to the destination (red star) with continued path optimization.
Jmse 13 01357 g011
Figure 12. Single-step computation time of the fusion algorithm for the demonstration in Figure 11.
Figure 12. Single-step computation time of the fusion algorithm for the demonstration in Figure 11.
Jmse 13 01357 g012
Figure 13. Path planning with obstacle constraints that complies with COLREGs. The primary vessel is represented by the green vessel, the obstruction by the red vessel, and the simultaneous positional movement is depicted by the color gradient of the vessel’s moving route.
Figure 13. Path planning with obstacle constraints that complies with COLREGs. The primary vessel is represented by the green vessel, the obstruction by the red vessel, and the simultaneous positional movement is depicted by the color gradient of the vessel’s moving route.
Jmse 13 01357 g013
Figure 14. Performance of the COLREG-compliant FMM-DWA algorithm in dynamic environments with random initial conditions. Panels (ad) show a complete planning process from the start point (green star) to the goal point (red star), with the ASV avoiding static obstacles (white squares) and dynamic obstacles (red triangles). Panels (eh) represent additional planning cases under varying initial conditions.
Figure 14. Performance of the COLREG-compliant FMM-DWA algorithm in dynamic environments with random initial conditions. Panels (ad) show a complete planning process from the start point (green star) to the goal point (red star), with the ASV avoiding static obstacles (white squares) and dynamic obstacles (red triangles). Panels (eh) represent additional planning cases under varying initial conditions.
Jmse 13 01357 g014
Figure 15. Display and analysis of the control laws corresponding to the two simulation examples in Figure 14. Panels (a,b) indicate the variations in the ASV’s linear acceleration a and angular velocity r over a given time period. Panels (c,d) illustrate the trend of the distance to the goal as time progresses. The acceleration is represented by the green line, while the angular velocity is represented by the red line. Panels (eh) display the distribution of control laws over various positions, revealing the relationship between control laws and their positions.
Figure 15. Display and analysis of the control laws corresponding to the two simulation examples in Figure 14. Panels (a,b) indicate the variations in the ASV’s linear acceleration a and angular velocity r over a given time period. Panels (c,d) illustrate the trend of the distance to the goal as time progresses. The acceleration is represented by the green line, while the angular velocity is represented by the red line. Panels (eh) display the distribution of control laws over various positions, revealing the relationship between control laws and their positions.
Jmse 13 01357 g015
Table 1. Experiment parameter setting.
Table 1. Experiment parameter setting.
ParameterValueUnitDescription
Δ t 0.2sTime step
V mobs 8.0pixels/sMaximum speed of dynamic obstacles
a max 0.5pixels/s2Maximum acceleration
a min −2.0pixels/s2Maximum deceleration
r max 1.0rad/sMaximum angular velocity
d safe 10pixelsMinimum safe distance between the vessel and obstacles
w path 2.0-Path deviation weight coefficient
w turn 0.3-Turning penalty weight coefficient
w goal 2.0-Goal distance weight coefficient
w avoid 3000-Obstacle avoidance penalty weight coefficient
w speed 400-Low-speed penalty weight coefficient
d goal 10pixelsDistance threshold for the vessel to reach the target point
d obs 15pixelsBuffer distance for obstacle inflation
m long 25.8kgMass component of the vessel in longitudinal motion
m lat 33.8kgMass component of the vessel in lateral motion
d damp 17.0kg/sHydrodynamic damping
L15pixelsVessel length
B10pixelsVessel width
S300-Smoothing factor
R obs 5pixelsStatic obstacle radius
R dyn 7pixelsDynamic obstacle radius
Table 2. Rule compliance rate for different algorithms fused with DWA.
Table 2. Rule compliance rate for different algorithms fused with DWA.
Statistical IndicatorDijkstra + DWAA* + DWARRT + DWAFMM + DWA
Rule compliance rate86.5%86.0%90.5%92.5%
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

Xie, Y.; Liu, C.; He, Y.; Ma, Y.; Liu, K. Multi-Strategy Fusion Path Planning Algorithm for Autonomous Surface Vessels with Dynamic Obstacles. J. Mar. Sci. Eng. 2025, 13, 1357. https://doi.org/10.3390/jmse13071357

AMA Style

Xie Y, Liu C, He Y, Ma Y, Liu K. Multi-Strategy Fusion Path Planning Algorithm for Autonomous Surface Vessels with Dynamic Obstacles. Journal of Marine Science and Engineering. 2025; 13(7):1357. https://doi.org/10.3390/jmse13071357

Chicago/Turabian Style

Xie, Yongshun, Chengyong Liu, Yixiong He, Yong Ma, and Kang Liu. 2025. "Multi-Strategy Fusion Path Planning Algorithm for Autonomous Surface Vessels with Dynamic Obstacles" Journal of Marine Science and Engineering 13, no. 7: 1357. https://doi.org/10.3390/jmse13071357

APA Style

Xie, Y., Liu, C., He, Y., Ma, Y., & Liu, K. (2025). Multi-Strategy Fusion Path Planning Algorithm for Autonomous Surface Vessels with Dynamic Obstacles. Journal of Marine Science and Engineering, 13(7), 1357. https://doi.org/10.3390/jmse13071357

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop