Next Article in Journal
Experimental Study on Strength Characteristics of Overconsolidated Gassy Clay
Previous Article in Journal
Marine Voyage Optimization and Weather Routing with Deep Reinforcement Learning
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Novel COLREGs-Based Automatic Berthing Scheme for Autonomous Surface Vessels

1
China Ship Scientific Research Center, Wuxi 214082, China
2
Taihu Laboratory of Deepsea Technological Science, Wuxi 214082, China
3
School of Internet of Things, Wuxi University, Wuxi 214105, China
4
College of Intelligent Systems Science and Engineering, Harbin Engineering University, Harbin 150006, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2025, 13(5), 903; https://doi.org/10.3390/jmse13050903
Submission received: 18 March 2025 / Revised: 23 April 2025 / Accepted: 25 April 2025 / Published: 30 April 2025
(This article belongs to the Section Ocean Engineering)

Abstract

:
This paper tackles the highly challenging problem of automatic berthing for autonomous surface vessels (ASVs), encompassing trajectory planning, trajectory tracking, and collision avoidance. Firstly, a novel A* algorithm integrated with a quasi-uniform B-spline and quadratic interpolation method (A*QB) is proposed for generating a smooth trajectory from the initial position to the berth, utilizing an offline-generated scaled map. Secondly, the optimal nonlinear model predictive control (NMPC)-based trajectory-tracking framework is established, incorporating the model’s uncertainty, the input saturation, and environmental disturbances, based on a 3-DOF model of a ship. Finally, considering the collision risks during port berthing, a COLREGs-based collision avoidance method is investigated. Consequently, a novel trajectory-tracking and COLREGs-based collision avoidance (TTCCA) scheme is proposed, ensuring that the ASV navigates along the desired trajectory, safely avoids both static and dynamic obstacles, and successfully reaches the berth. To validate the TTCCA approach, numerical simulations are conducted across four scenarios with comparisons to existing methods. The experimental results demonstrate the effectiveness and superiority of the proposed scheme.

1. Introduction

1.1. Background

The recurring COVID−19 pandemic has had a significant impact on maritime transportation [1,2]. On one hand, traders significantly increased their overseas purchase orders due to the growth of online trade; on the other hand, the pandemic reduced workforce availability at docks, resulting in delayed cargo handling and severe port congestion. Furthermore, port congestion [3] causes adverse effects such as delayed ship schedules, overdue cargo, and increased freight rates. To alleviate these issues, an intelligent transportation system (ITS) is required for autonomous surface vessel (ASV) management in ports [4] with growing attention focused on ASV automatic berthing [5,6].
Automatic berthing represents one of the most complex challenges regarding the motion control of ASVs [7]. First, ASV berthing operations occur at low speeds near shorelines, significantly increasing the difficulty of maneuvering [8,9]. Additionally, ASVs face restricted navigation areas and potential obstacles, particularly in congested port environments. Moreover, adherence to the International Regulations for Preventing Collisions at Sea (COLREGs) [10] is mandatory when collision risks arise. Thus, automatic berthing integrates three critical components: trajectory planning, tracking, and collision avoidance.

1.2. A Literature Review

Different techniques have been applied to automatic berthing problems for ASVs. Considering the complex maneuvering behavior required by ASVs during berthing, artificial neural networks can be used to replace the manipulator. Ref. [11] first employed an artificial neural network for ship berthing, and excellent experimental results were obtained. Ref. [12] proposed a parallel ANN for ship berthing, where the engine and the rudder were controlled separately. The results showed that automatic berthing from every direction could be accomplished, which was better than the results with a centralized network. Considering the disturbances generated by wind, nonlinear programming methods and virtual windows are employed to train the ANN in [13]’s work. To address hydrodynamic uncertainties and composite disturbances experienced by autonomous surface vehicles (ASVs), ref. [14] developed an adaptive control framework integrating neural network compensation mechanisms. Distinct from conventional approaches requiring full-parameter optimization, this method employs a streamlined parameter-updating strategy that necessitates adjustments to only four critical parameters. While neural networks have demonstrated success in simulation studies [11,12,13,14], their practical applicability remains constrained by several inherent limitations. First, neural-based controllers require extensive retraining when applied to vessels with different hydrodynamic characteristics, leading to significant computational overhead and operational inflexibility [15]. Second, the black-box nature of neural networks complicates the incorporation of explicit safety constraints and COLREGs compliance during real-time navigation. These limitations restrict their deployment in dynamic port environments, where interpretable and adaptive obstacle avoidance is critical.
Other techniques have been applied to achieve ASV’s autonomous berthing besides neural networks and optimal control techniques. Ref. [16] proposed a potential field virtual ship (PFVS) guidance and a self-tuning iterative learning control (STILC) method for ASV automatic berthing. Ref. [17] presents a Flow Matching Double Section Bezier Berth Method (FM-DSB) for managing downstream and upstream berthing instructions, ensuring speed matching along the berthing path through vessel acceleration/deceleration capability analysis. Building on prior work, ref. [18] introduced a layered berthing architecture using potential fields and fuzzy PID control, which was validated via simulations and field trials. Ref. [19] addressed dynamic constraints with an extended dynamic window approach for real-time maneuvers under actuator limits. While these studies focus on planning for static and dynamic obstacle environments in simulations, COLREGs-compliant collision avoidance remains unaddressed. Ref. [9] incorporated a supervised machine learning model into the ship’s dynamic model, significantly improving prediction accuracy.
Furthermore, path/trajectory tracking and collision avoidance must be considered during ASV berthing. Ref. [20] proposed a vision-based target motion analysis and collision avoidance method for ASVs, simulating diverse encounter scenarios. Ref. [19] developed an NDO-NMPC (nonlinear disturbance observer-integrated nonlinear model predictive control) scheme for trajectory tracking and collision avoidance. Although this work considers both static and dynamic obstacle avoidance under COLREGs, it neglects harbor navigation planning. Notably, static obstacles’ immobility compared to dynamic targets may degrade avoidance performance. Ref. [21] proposed a multi-objective NMPC method for USV automatic berthing but omitted collision avoidance. Recent advances in ASV navigation have addressed distinct facets of trajectory tracking and collision avoidance. Ref. [22] introduced an event-triggered adaptive-horizon nonlinear model predictive control (EAHNMPC) framework for marine surface vehicles (MSVs), prioritizing computational efficiency through adaptive horizon adjustments. While this method reduces the computational burden of conventional NMPC, it does not explicitly address environmental disturbances or multi-obstacle scenarios. In contrast, ref. [23] developed a COLREGs-compliant RRT-based path planner* integrating motion planning, guidance, and control modules to enhance real-time performance. Despite its regulatory adherence, the generated trajectories exhibit kinematically infeasible sharp turns, limiting practical deployment in dynamic environments.
For short-term collision avoidance, ref. [24] proposed a branching-course MPC algorithm incorporating an elliptical COLREGs penalty function to prioritize regulation-compliant maneuvers. While effective in constrained scenarios, this approach neglects the combined effects of environmental disturbances (e.g., currents, waves) and model parameter uncertainties, restricting its robustness in real-world operations. Addressing these limitations, ref. [25] devised an event-triggered model predictive motion replanning (EMPMR) framework for unmanned surface vehicles (USVs), which synergizes dynamic trajectory replanning with real-time control optimization to handle disturbances during automatic berthing.

1.3. Contributions

This study proposes a COLREGs-compliant automatic berthing scheme motivated by previous research. In this scheme, the automatic berthing problem is decomposed into three parts: trajectory planning via the A* algorithm integrated with quasi-uniform B-spline and quadratic interpolation (A*QB), trajectory tracking, and COLREGs-compliant collision avoidance (TTCCA). To enhance real-time performance, we combine offline trajectory planning with online collision avoidance. Furthermore, both static obstacle avoidance and COLREGs-compliant dynamic obstacle avoidance are integrated into the optimization framework.
The primary contributions are outlined below:
(1)
A comprehensive framework for ASV automatic berthing in harbor environments, encompassing trajectory planning, tracking, and obstacle avoidance to address complex low-speed maneuvers.
(2)
The A*QB method, which enhances trajectory smoothness and kinematic feasibility for ASVs by combining A* global planning with quasi-uniform B-spline and quadratic interpolation. Compared to conventional A*, the proposed method generates trajectories better suited for low-speed, near-shore berthing.
(3)
A novel TTCCA scheme incorporating obstacle avoidance functions for static and dynamic obstacles compliant with COLREGs, ensuring safe and regulation-adherent navigation.
(4)
Extensive numerical simulations across four scenarios demonstrating the scheme’s superiority over existing methods (e.g., [19]) in tracking accuracy, obstacle avoidance efficiency, and berthing success rates.

1.4. Article Overview

This paper is structured as follows. Section 2 introduces the mathematical model and introduces the synthetic scheme briefly. Section 3 introduces the trajectory planning subsystem. An optimal berthing problem is established, and the navigation control subsystem is presented. To verify the effectiveness of the proposed scheme, simulation experiments are performed in several scenarios in Section 4. Section 5 gives the conclusion.

2. Automatic Berthing System Overview

2.1. Notations

In this paper, R and Z + represent the real and positive integers, respectively. For matrix x , x = x T Qx with a positive definite matrix Q .

2.2. Mathematical Model

In order to predict the berthing motion under model uncertainty and disturbances, the standard three-degree-of-freedom (3-DOF) dynamics model of the ASV is applied [26]. In this model, only the surge, sway, and yaw motion are considered:
η ˙ = R ( ψ ) v
M v ˙ + C ( v ) v + D ( v ) v = τ + R T ( ψ ) d
where η = [ x , y , ψ ] T represents the position and heading vector, v = [ u , v , r ] T represents the velocity vector, and R ( ψ ) R 3 × 3 denotes the transfer matrix from the body-fixed frame to the earth-fixed frame. Considering the model uncertainties, M = M 0 + Δ M , C = C 0 + Δ C , and D = D 0 + Δ D denote the system inertia matrix, the Coriolis-centripetal matrix, and the damping matrix, respectively. M 0 , C 0 , and D 0 denote the nominal system inertia matrix, nominal Coriolis-centripetal matrix, and nominal damping matrix, respectively. Δ M , Δ C , and Δ D denote the deviations between the real matrices and the nominal matrices. Moreover, M 0 , C 0 , D 0 , and R ( ψ ) are given as
M 0 = m X u ˙ 0 0 0 m Y v ˙ m x g Y r ˙ 0 m x g Y r ˙ I z N r ˙
C 0 = 0 0 m 22 v m 23 r 0 0 m 11 u m 22 v + m 23 r m 11 u 0
D 0 = X u 0 0 0 Y v Y r 0 N v N r
R ( ψ ) = cos ( ψ ) sin ( ψ ) 0 sin ( ψ ) cos ( ψ ) 0 0 0 1
where X u ˙ , Y v ˙ , Y r ˙ , N r ˙ , X u , Y v , Y r , N v , and N r represent the hydrodynamic coefficients, x g and I z represent the transverse coordinate of the gravity’s center and inertia around the Z-axis, respectively. For the ASV’s dynamics model (2), τ = [ τ 1 , τ 2 , τ 3 ] T denotes the control vector, including the surge force, sway force, and yaw moment, respectively. d = [ d 1 , d 2 , d 3 ] T represents the unknown disturbances generated by winds, waves, and currents. As the berthing motion of the ASV is near-shore and low-speed, the following assumptions are adopted.
Assumption 1. 
The deviation matrices Δ M , Δ C , and, Δ D are all bounded.
Assumption 2. 
The changing rate of unknown disturbances d ˙ is bounded, where d ˙ d ˙ < and d ˙ is an unknown constant vector.
Assumption 3. 
The ASV integrates multi-sensor fusion for real-time maritime perception: Automatic Identification System (AIS) transceivers and onboard Global Positioning System (GPS) modules provide the continuous acquisition of a target vessel’s navigation parameters (position, velocity, heading), while millimeter-wave radar enables the precise detection of obstacle spatial coordinates and geometric profiles.
Assumption 4. 
The ASV’s multi-sensor fusion system (AIS, GPS, and millimeter-wave radar) is assumed to provide bounded measurement noise. While sensor errors (e.g., GPS positioning inaccuracies, radar ranging noise) inherently exist, their effects are mitigated through two mechanisms:
(1) Kalman filtering: Sensor data fusion via an embedded Kalman filter reduces high-frequency noise components.
(2) NMPC feedback correction: The rolling horizon optimization in NMPC compensates for low-frequency drift errors through state estimation updates.
Further, due to the saturation characteristics of the actuator input, the control inputs are subject to saturation constraints. Taking the input saturation into consideration,
τ i m i n τ i τ i m a x , i = u , v , r
where τ i m i n and τ i m a x denote the minimal and maximal force or moment provided by the propellers and rudders. And the control input can be defined by
τ i = τ i m a x , τ i < τ i m a x τ i , τ i m a x τ i τ i m a x , i = u , v , r τ i m i n , τ i > τ i m i n
Equations (1) and (2) can be rewritten in the compact form
x ˙ ( t ) = f ( x ( t ) , u ( t ) , d ( t ) )
y ( t ) = C ( t ) x ( t )
where x ( t ) = [x,y, ψ ,u,v,r]T represents the state vector, u ( t ) = τ represents the control input, and f (·) represents the nonlinear function. y ( t ) = x ( t ) represents the output vector, and C ( t ) represents the output matrix. Typically, NMPC is used for discrete models. Therefore, Equations (9) and (10) can be discrete to
x ( k + 1 ) = f ( x ( k ) , u ( k ) , d ( k ) )
y ( k ) = C ( k ) x ( k )
where x ( k ) X denotes the states vector at time k, and the time interval between k and k + 1 is T S , where u ( k ) U denotes the control vector at time k.

2.3. Synthetic Scheme

Figure 1 depicts the flow chart for the automatic berthing system. First, the colored port map is processed into a binary grid map where grids are labeled as blocked (black) and unblocked (white). The ASV is modeled as a particle navigating within unblocked regions. Next, the global trajectory from the initial position to the berth is generated offline using the A* algorithm integrated with quasi-uniform B-spline interpolation, and the ASV tracks this trajectory until obstacles are detected. Subsequently, obstacle-specific collision avoidance strategies are activated based on obstacle type. The berthing process concludes upon the ASV’s arrival at the target position.
In this study, the system is designed for minimum navigation distance, though alternative objectives such as minimum time [27] or energy optimization [28] could be substituted depending on operational priorities.

3. Trajectory Planning Subsystem

Motion planning is a critical component of ASV automatic berthing. As a highly efficient global path-planning algorithm, A* generates navigation paths with optimal topological connectivity. However, its conventional implementation produces jagged trajectories unsuitable for ASV motion constraints. To address this limitation, we propose an enhanced AQB (A-quasi-uniform B-spline) trajectory planner that integrates quasi-uniform B-spline smoothing. Existing research predominantly focuses on ASV path planning [29,30], while systematic trajectory planning with temporal constraints remains underexplored. Distinct from path planning, trajectory planning embeds temporal information into spatial paths, thereby imposing stricter requirements on dynamic tracking controllers. The proposed A*QB methodology will be comprehensively elaborated in Section 3.

3.1. Grid Map Generation

As a widely adopted spatial discretization technique, the grid method demonstrates exceptional efficacy in robotic path-planning applications. This approach is characterized by its straightforward data structure facilitating spatial analysis and surface modeling coupled with robust representational capacity. Nevertheless, its computational efficiency is compromised by substantial data storage requirements. The berthing system mitigates real-time constraints through the offline execution of grid mapping and global trajectory generation. The implementation workflow initiates with the acquisition of a 1:25,000 scale chromatic port chart from Google Maps (Figure 2a). Following grayscale conversion and binarization processes (Figure 2b), the spatial domain undergoes grid-based spatial decomposition. Critical obstacle boundaries are conservatively expanded by dual grid units to ensure collision-free navigation margins, as visualized in Figure 2c.

3.2. Global Path-Planning Algorithm

Before the desired trajectory is generated, the desired path is required to be obtained. The path-planning algorithms of ASV have been extensively studied over recent years [31,32]. The A* algorithm is one of the most efficient direct search methods that uses the grids to solve the shortest paths and is a common heuristic for many other problems [33]. Typically, four-connectivity and eight-connectivity matrices are used to associate two adjacent grids. Considering that the global path planning is offline and the dynamics of ASV steering, the A* algorithm based on the eight-adjacency matrix is chosen. The schematics of the four-connectivity and eight-connectivity A* algorithms are given in Figure 3a and Figure 3b, respectively.
The evaluation function of the A* algorithm is defined as
f ( n ) = g ( n ) + h ( n )
where f ( n ) represents the estimated distance of the path between the target node and the start node, g ( n ) represents the actual distance that the ASV has traveled from the start node to the current node, and h ( n ) represents the estimated distance of the optimal path between the current node to the target node. In detail, when the ASV is in one node, all the eight nodes connected to the current one will be evaluated by f ( n ) , and the one with the lowest cost will be selected as the next node. h ( n ) is represented by the Euclidean distance of the following equation
h ( n ) = ( x f x i ) 2 + ( y f y i ) 2
where ( x i , y i ) denote the coordinates of the current node, and ( x f , y f ) denote the coordinates of the target berthing node. Thus, given the starting point and the target point, an optimal path can be obtained based on the available map information and the A* algorithm. However, the trajectory obtained by the A* algorithm is not smooth enough for the trajectory tracking of ASVs. Therefore, a path-smoothing method needs to be applied, which is described in detail in the following subsection.

3.3. Path Smoothing Method

Building upon the preceding methodology, the global trajectory formulated through the A* algorithm exhibits inherent kinematic infeasibility for ASV navigation. The resultant polygonal chains connecting grid centroids introduce sharp angular discontinuities at turning nodes (Figure 2d), creating significant trajectory-tracking challenges. This geometric incompatibility necessitates smoothing optimization prior to control subsystem implementation. While Bézier curves [29] conventionally address such path regularization, their global control characteristics impose critical limitations: (1) exponential growth of polynomial order with increasing control points; and (2) non-local deformation propagation during curve adjustment. To overcome these constraints, we implement B-spline interpolation [34] that enables local shape modulation through strategically weighted control vertices. The spline is a flexible band that generates a smooth curve through a specified set of points, and B-spline curves control the shape locally through control points. The B-spline basis function B i k ( u ) is expressed as
B i 0 ( u ) = 1 u i u < u i + 1 0 o t h e r w i s e
B i k ( u ) = ( u u i u i + k u i ) B i k 1 ( u ) + ( u i + k + 1 u u i + k + 1 u i + 1 ) B i + 1 k 1 ( u ) , u i u < u i + 1 , i Z +
where k denotes the degree of the basis function, i denotes the index of the coordinates, u i denotes the knots, and u denotes the parameter that corresponds to the location of the newly generated curve points. The spline curve C ( u ) is the linear sum of n basis functions, which can be expressed as
C ( u ) = i = 1 n B i k ( u ) P i , i Z +
where P i is the control point. The path calculated by the A* algorithm in the previous subsection is processed by the B-spline method, and the smoothed navigation path is obtained. However, the curve generated by the B-spline method does not go through the start and end points, which does not satisfy the requirements of the automatic berthing. Therefore, it is necessary to continuously connect the start and end control points of the B-spline. In this case, a quasi-uniform B-spline is employed, allowing the start and end nodes to be repeated k + 1 times:
u 0 = u i , i = 1 , 2 , , k
u n + 1 = u n + 1 + i , i = 1 , 2 , , k
u i = i k n k + 1 , i = k , k + 1 , , n + 1
Figure 4a and Figure 4b show the schematic of the B-spline and quasi-uniform B-spline (yellow curves), respectively. In detail, it can be seen that the yellow trajectory is smoother and more in line with the navigation characteristics of the ASV than the blue trajectory planned by the A* algorithm. The optimized performance of the B-spline can also be seen in Choi et al. [35]’s work. In addition, in order for the ASV to follow the desired trajectory as uniformly as possible, path points of equal or approximately equal distance need to be selected. Following the generation of quasi-equidistant waypoints, the reference trajectory is computationally constructed through temporal increment optimization aligned with the ASV’s longitudinal velocity profile. Further, the path obtained by the A* algorithm is optimized using the B-spline to obtain the path shown in Figure 2d, where the blue line indicates the initial path obtained by the A* algorithm and the red line indicates the path obtained by the A*QB approach. As illustrated in Figure 2d, the path generated by the A*QB approach is smoother in the corners, which satisfies the dynamic steering characteristics of the ASV better.

3.4. Quadratic Interpolation Method

As mentioned previously, the planned waypoints are approximately equidistant. Obviously, the velocity of the ASV cannot be reduced to zero at the berth, which does not satisfy the requirement of automatic berthing. Therefore, further optimization of the trajectory is required. As introduced in our previous work [36], the last 200 waypoints were divided into four parts and interpolated with different densities to gradually reduce the speed of the ASV. However, this method also has the disadvantage that it does not guarantee a linear reduction in the velocity of the ASV. To overcome this difficulty, a novel quadratic interpolation method is proposed to reduce the distance of waypoints. At the end of the berth, the displacement corresponding to each time interval of the ASV is reduced quadratically to ensure a linear reduction of the velocity. The quadratic interpolation method is shown in the following equation.
x i n t = x f 1 0.02 i 2 x f x r , i = 1 , 2 , , 50
y i n t = y f 1 0.02 i 2 y f y r , i = 1 , 2 , , 50
where x i n t and y i n t denote the coordinate of interpolated points, while x r and y r denote the coordinates of the start point of the inserted segment. Eventually, the berthing trajectory of the ASV is obtained by the proposed A*QB approach.

4. Navigation Control Subsystem

The purpose of the trajectory planning subsystem is to plan the initial trajectory of the ASV navigation offline. However, it may be challenging for the ASV to navigate along the established trajectory due to several factors, such as environmental disturbances [37], model uncertainties, static and dynamic obstacles, etc. Therefore, it is essential to investigate the ASV’s trajectory tracking and collision avoidance control from the dynamics level. Thus, we propose a novel trajectory tracking and COLREGs-based collision avoidance (TTCCA) scheme, which allows the ASV to navigate along the desired trajectory, avoid static and dynamic obstacles and finally reach the berth under model uncertainty, environmental disturbances and input saturation.

4.1. Cost Function

The discrete mathematical model of the ASV is obtained based on Section 2.2. In order for the ASV to reach the berth following the given trajectory, NMPC is employed to solve the optimal control inputs. NMPC can solve control inputs for constrained nonlinear systems utilizing the idea of rolling optimization with robustness, which is suitable for the automatic berthing problems of an ASV. The cost function is usually established for the ASV trajectory-tracking problem based on the state cost and the input cost. Considering the berthing and reducing the actuator fluctuations, the state cost, the input smoothness cost and the terminal cost are considered in the cost function, which is constructed as follows:
( x ( k ) , u ( k ) ) = i = 0 N P y ( k ) y r e f ( k ) Q 2 + x ( k ) x f P 2 + j = 1 N C u ( k ) u k 1 ( k ) R 2
where y r e f is the reference output, x f is the final state at berth, Q is the weight matrix of the state errors, R is the weight matrix of the input rates, and P is the weight matrix of the terminal cost. Additionally, static obstacles and dynamic obstacles may be encountered during ASV berthing. Collision avoidance for static and dynamic obstacles will be discussed in Section 4.2 and Section 4.3, respectively.

4.2. Static Obstacle Avoidance Function

In Section 3, the global trajectory of the ASV is planned offline based on the map information. However, some obstacles are not considered because of the un-updated map information, incomplete information, etc., which may lead to the collision of ASVs. Therefore, updating obstacle information and collision avoidance based on the sensors equipped in the ASV is necessary. However, the obstacles detected by sensors are usually irregularly shaped, which is not easily represented. There are various ways to describe obstacle information, such as circular, elliptical or other convex polygons, and in this study, the obstacle is described as circular. Therefore, the cost function for the static cost should be designed according to the distance to the center of the obstacle circle. The static cost function can be expressed as
C s = ( x x o ) 2 a + ( y y o ) 2 b + e d 2 / ( 2 σ 2 )
where ( x 0 , y 0 ) denote the coordinates of the ASV, a and b denote the semi-major and semi-minor axes of the elliptical safety boundary around static obstacles, d denotes the distance between the ASV and the static obstacle, and σ = a b denotes the Gaussian decay coefficient for spatial risk attenuation, ensuring smooth gradient transitions near obstacle boundaries.

4.3. Dynamic Obstacle Avoidance Function

In addition to the static obstacles, ASV berths in a port may also encounter other sailing vessels. The vessel that encounters the ASV is called the target vessel. In contrast to the collision avoidance rules for vehicles, ASVs are required to comply with the International Regulations for Preventing Collisions at Sea (COLREGs). Thus, whether ASVs’ collision avoidance method complies with the COLREGs rules should be considered. The rules relevant to this study are given in [38].
The evaluation of COLREGs for different encounter scenarios is illustrated in Figure 5.
Safe distances must also be considered in addition to the COLREGs regulation for target vessel collision avoidance. To assess the collision risk, the distance to the closest point of approach (DCPA) and the time to the closest point of approach (TCPA) are employed for the collision risk estimation of ASVs [30], which can be expressed as
D C P A = d L O S s i n ( θ T α π )
T C P A = d L O S s i n ( θ T α π ) / u R
where d L O S , θ T , and α denote the current distance between the ASV and the target vessel, the relative heading angle between the ASV and the target vessel, and the azimuth angle of the target ship relative to the ASV. The physical interpretation of D C P A is geometrically illustrated in Figure 6 to clarify its physical meaning, where u R denotes the relative velocity between the ASV u and the target vessel u T .
A real-time comparison between D C P A and D S A F E is performed over the whole course. When D C P A D S A F E , the collision avoidance strategy is implemented, and the trajectory is replanned; when D C P A > D S A F E , the ASV keeps tracking the original trajectory. In addition, the CRI (Collision Risk Index) [39,40] is a quantitative index that combines spatial and temporal factors to evaluate the collision risk of vessels during navigation with other target vessels. In this study, the CRI is defined as follows:
CRI = 1 1 + e k α · D SAFE DCPA + β · T react TCPA
where D SAFE is the safe distance, T SAFE is the safe time, α is the space weight coefficient, β is the time weight coefficient, and k is the sensitivity regulator. In detail, immediate action will be triggered at C R I > 0.7 , and preparatory action will be triggered at C R I > 0.4 , which aligns with Rule 8b in COLREGs.
Specifically, ASV and the target vessels are all simplified as a prime point with safety distance in this study. Taking COLREGs into account, the cost function of dynamic obstacles can be expressed as shown in Equation (28).
C d = ( x x 0 ) 2 ( a + v r T ) 2 + ( y y 0 ) 2 ( b + 0.1 ψ e r r ) 2 + λ ( θ C P A )
where a and b represent the constant value, v r denotes the relative velocity between their own vessel and the dynamic obstacle, T denotes the reaction time constant for emergency maneuvering, ψ e r r denotes the heading deviation angle between the vessel’s current course and the desired collision-free trajectory, and λ ( θ C P A ) denotes the rule-based weight function for COLREGs compliance, which is defined as
λ ( θ C P A ) = 2.0 , H e a d o n 1.5 · Δ y / Δ x , C r o s s i n g 0.5 , O v e r t a k i n g
Specifically, ASV and the target vessels are all simplified as a point mass with a safety radius in this study. Taking COLREGs into account, the cost function of dynamic obstacles can be expressed as Equation (28). The dynamic obstacle avoidance cost function is designed to ensure the ASV’s compliance with COLREGs Rule 8 when the ASV is encountering the dynamic obstacles in a regular situation, as shown below [41]:
(1)
Actions should be taken promptly as soon as collision risks are identified.
(2)
Actions must be clear enough for other vessels to readily perceive.
Moreover, Equation (28) takes into account COLREGs by punishing the target vessel when it is ahead or on the right side of the ASV, thus making the target vessel prefer to pass from the left or rear of the ASV.
This study focuses solely on ASV berthing control, where the target vessel (obstacle) lacks autonomous collision avoidance capability and acts as a stand-on vessel in crossing scenarios. Based on Assumption 3 (Section 2.2), the obstacle vessel’s position and velocity data are measurable. Its discrete kinematic model is expressed as
x T ( k + 1 ) = x T ( k ) + u T cos ψ T T S v T sin ψ T T S
y T ( k + 1 ) = y T ( k ) + u T sin ψ T T S + v T cos ψ T T S
ψ T ( k + 1 ) = ψ T ( k ) + r T T S
where x T and y T represent the horizontal and vertical coordinate of the target vessel, respectively, and r t represents the radius of the target vessel, ψ T represents the heading angle of the target vessel, u T and v T represent the longitudinal and lateral velocities of the target vessel, r T represents the angular velocity of the target vessel. By iterating Equations (30)–(32), the coordinates and heading angle of the target ship in the future can be predicted, which is more favorable for NMPC to re-plan the trajectory.

4.4. Optimal Problem

The NMPC problem is solved by the fmincon function in the matrix simulation software, where the penalty method is applied in a TTCCA scheme. Considering the static and dynamic obstacle avoidance, the optimal problem of ASV automatic berthing can be represented as shown in Equations (33) and (34).
min u k J ( y ( k ) , u ( k ) ) s . t . x ( x + i + 1 ) = f ( x ( k + i ) , u ( k + 1 ) , k + i ) , i = 0 , 1 , , N P u m i n ( k ) u ( k ) u m a x ( k ) y ( k ) = Cx ( k )
J ( y ( k ) , u ( k ) ) = ( x ( k ) , u ( k ) ) + c 1 · C s + c 2 · ( 1 + CRI ) · C d
It should be noted in Equation (34) that the Collision Risk Index (CRI) is incorporated into the dynamic obstacle function, which reduces the ASV’s response time for collision avoidance maneuvers and ensures compliance with COLREGs Rule 8 (Action to Avoid Collision).
Within the penalty method framework, the optimal solution sequence is computed iteratively under time-step constraints. This process adaptively refines the solution space with updates triggered dynamically upon the identification of a superior extremum in the optimization problem. Subsequently, the solution sequence gradually converges toward the minimum value of the optimal problem until maximum iterations are exceeded or a specified tolerance threshold is met. At each time step, only the first control input from the sequence is applied. The optimization problem is then resolved iteratively, repeating this process until the ASV successfully reaches the berth. Model uncertainties and environmental disturbances are effectively mitigated through the feedback correction and rolling optimization mechanisms inherent to the NMPC algorithm.

5. Simulation Results

Simulations in multiple scenarios validate the effectiveness of the proposed scheme. The CyberShip II, a 1:70 scale model (parameters sourced from [26], Section 13.3.12), is simulated in a scaled environment of 53.6 m × 35.7 m. The 1:70 scale CyberShip II model is widely adopted in marine control research due to its validated hydrodynamic similarity to full-scale vessels. All computations use a 12-core AMD 3900X processor (3.8 GHz), and MATLAB 2021a was used in this paper.

5.1. Control Parameters

In all the scenarios, the model uncertainties are assumed to be Δ M = 0.1 M 0 , Δ C = 0.1 C 0 , and Δ D = 0.1 D 0 , which is randomly generated at each time step within the boundary. Moreover, the time interval T S is selected to be 0.1 s and the predictive horizon N P is selected to be 30. These choices result in a 3 s prediction period beyond the current time step, allowing sufficient computational time for each step. In addition, the control horizon N C and the static predictive horizon N S are selected to be 3 and 10, respectively, to balance the control and the computational performance.
In the static and dynamic cost functions, a is set as 30, b is set as 20, and T is set as 10. c 1 is set as 1000, and c 2 is set as 1000. Also, it is worth noting that the position tracking performance plays a more important role in the trajectory tracking. Therefore, the position weighting coefficient is increased compared to other weighting coefficients. The control parameters Q , P , and R are given in Table 1.
Furthermore, the first-order Markov process is employed to describe the unknown disturbances, which can be expressed as
d = J T ( ψ ) b b ˙ = T c 1 b + ρ n
where b R 3 represents the unknown disturbances, T c = d i a g ( 10 3 , 10 3 , 10 3 ) represents the diagonal matrix of the time constant, n represents zero-mean Gaussian white noise, and ρ = d i a g ( 1 , 1 , 1 ) represents the amplitude matrix of n .
The proposed TTCCA scheme’s robustness to environmental disturbances is validated through two aspects:
(1)
The ±10% parametric variations in Δ M , Δ C , and Δ D emulate unmodeled hydrodynamic effects and low-frequency current disturbances.
(2)
The first-order Markov process approximates wind/wave disturbances as bounded time-varying forces.

5.2. Experimental Results

To evaluate the effectiveness of the proposed scheme, ref. [19]’s approach is employed in the experimental results. It is noted that [19] proposed a trajectory tracking and collision avoidance scheme. Therefore, the focus of the simulation experiment is to compare the obstacle avoidance performance of the two schemes. Given the initial point (2.9, 27.2) and berth 1 (10.3, 10), berthing trajectories are generated according to the proposed scheme.

5.2.1. Scenario 1 (Heading On)

In this scenario, a simulation experiment is carried out to evaluate the proposed scheme’s berthing performance with static obstacles and headings on dynamic obstacles (target vessel). Three static obstacles are placed at ( x 1 , y 1 ) = [ 7.5 , 25.3 ] , ( x 2 , y 2 ) = [ 7.5 , 22 ] , and ( x 3 , y 3 ) = [ 7.4 , 15 ] , respectively. In this scenario, the surge velocity of the target vessel is set as 0.25 m/s. In addition, considering the ASV’s maximum speed, the map’s scaled ratio, and the model uncertainties, the safety distance of the static obstacle is set as 0.2 m [42]. Figure 7 shows the berthing performance with dynamic and static obstacles in head-on scenarios. Both schemes can achieve the ASV’s berthing and reach the berth without collision. As shown in Figure 8, the heading angle demonstrates a decisive rightward turn upon detecting the head-on target vessel, aligning with COLREGs Rule 14(a) requiring reciprocal starboard maneuvers to establish port-side passage. This proactive adjustment ensures safe DCPA expansion. Figure 9 demonstrates safe berthing with the surge velocity, sway velocity and yaw rate converging to zero, confirming stable arrival. The surge velocity’s linear decrease, attributed to quadratic interpolation, ensures controlled deceleration. Feasible actuator demands are validated by the control inputs in Figure 10.

5.2.2. Scenario 2 (Crossing)

This scenario evaluates the two schemes’ performance during ASV–target vessel crossing. The target vessel’s surge velocity is set to 0.25 m/s. Figure 11 illustrates berthing trajectories with dynamic and static obstacles. The heading angle profiles in Figure 12 reveal that the ASV executes a controlled 15° port turn during crossings, complying with COLREGs Rule 15 by yielding to the stand-on vessel. The maneuver achieves a clearance of 0.26 m, satisfying Rule 8’s "early and substantial action" mandate. The velocity convergence in Figure 13 confirms trajectory stabilization, while the control inputs in Figure 14 highlight control chattering in the [19]’s approach at 20 s and 45 s, which is detrimental to the system’s stability.
Furthermore, the velocity profiles in Figure 13 demonstrate the asymptotic convergence of the surge velocity, sway velocity, and yaw angular velocity to zero, confirming stable trajectory stabilization. The control inputs are presented in Figure 14. It should be noted that the chattering occurs for [19]’s approach at around 20 and 45 s, which is very disadvantageous to the stability of the control system.

5.2.3. Scenario 3 (Overtaking)

This scenario examines the overtaking performance with a target vessel surge velocity of 0.15 m/s. Figure 15 shows trajectories during overtaking, and Figure 16 depicts heading angles adhering to COLREGs Rule 13(c) through longitudinal separation prioritization. The proposed scheme maintains safety distances, while velocity profiles (Figure 17) exhibit convergence to zero during final docking. The actuation dynamics in Figure 18 reveal persistent chattering in the [19]’s method, which is attributed to conflicting trajectory tracking and collision avoidance objectives. The TTCCA framework resolves this via decoupled cost functions (Equations (24) and (28)) and velocity-dependent safety boundaries (Equation (28)).
As a comparison, the proposed scheme can satisfy the requirement of safety distance during berthing. The velocity profiles shown in Figure 17 demonstrate asymptotic convergence of the surge velocity, sway velocity, and yaw angular velocity to zero during final berthing alignment, which is consistent with the stabilization behavior analyzed in the preceding subsection. The actuation dynamics are further detailed in Figure 18, which provides full transparency into the control inputs governing the maneuver. Also, the chattering occurs in the [19]’s approach. The control input chattering observed in [19]’s approach (Figure 18) arises from conflicting objectives between trajectory tracking and emergency collision avoidance. TTCCA resolves this through separated cost functions (Equations (24) and (28)) and velocity-dependent safety boundaries in Equation (28).

5.2.4. Scenario 4 (Complex Cases)

This scenario evaluates Han et al.’s and the proposed scheme in complex environments, where random static obstacles simulate crowded conditions. In the crowded scenario, head-on, crossing, overtaking, and multi-vessel interactions are tested from scenarios 4.1 to 4.4, separately. Another final position is added ( 12 , 15.2 ) as berth 2, and similar cases as in berth 1 are performed from scenarios 4.5 to 4.8. The simulation results are shown from Figure 19, Figure 20, Figure 21, Figure 22, Figure 23, Figure 24, Figure 25 and Figure 26, corresponding to scenarios 4.1 to 4.8.
For berth 1 (Figure 19, Figure 20, Figure 21 and Figure 22), the proposed TTCCA scheme consistently adheres to COLREGs across encounter types. In head-on scenarios (Figure 19), TTCCA executes a decisive starboard turn (Rule 14), achieving 0.24 m clearance, while [19]’s method narrowly breaches the 0.2 m safety threshold (0.18 m). During crossing encounters (Figure 20), TTCCA maintains a smooth port-side deviation (Rule 15) with 0.22 m clearance, whereas [19]’s approach exhibits oscillatory maneuvers (0.18 m). For overtaking (Figure 21), TTCCA prioritizes longitudinal separation (0.37 m, Rule 13) through velocity modulation, contrasting with [19]’s unsafe lateral proximity (0.28 m). Multi-vessel scenarios (Figure 22) demonstrate TTCCA’s hierarchical risk management (0.23–0.38 m margins), while [19]’s method struggles with overlapping constraints (0.18–0.24 m).
For berth 2 (Figure 23, Figure 24, Figure 25 and Figure 26), TTCCA maintains robustness under spatial challenges. Head-on cases (Figure 23) achieve 0.28 m clearance via early replanning, outperforming [19]’s delayed response. Crossing scenarios (Figure 24) highlight TTCCA’s adaptive weighting (Rule 8, 0.25 m clearance) versus [19]’s marginal 0.23 m. Overtaking tests (Figure 25) reveal TTCCA’s velocity-centric compliance (0.42 m clearance), contrasting with [19]’s erratic heading adjustments (0.38 m). Multi-vessel navigation (Figure 26) underscores TTCCA’s rule-based prioritization (0.22–0.25 m), while [19]’s method fails to coordinate dynamic obstacles (0.23–0.27 m). The quantitative comparisons in Table 2 validate TTCCA’s superior safety margins (15–32% improvement) and computational efficiency, confirming its COLREGs-compliant reliability in congested ports.
Table 3 indicate the average cost time for both schemes in different scenarios. Table 4, Table 5 and Table 6 indicate the CRI performance of both scheme in all scenarios, where CRI1 means the CRI of the proposed scheme and CRI2 means the CRI of Han et al.’s [19] scheme. The proposed algorithm (CRI1) exhibits systematically lower collision risk indices compared to that of Han et al. [19] (CRI2) across all scenarios. For instance, in Scenario 3 (overtaking), CRI1 registers 0.40–0.69, while CRI2 peaks at 0.62–0.72, indicating heightened collision risks due to delayed maneuvers. The proposed method’s adherence to COLREGs Rule 8(b)—triggering actions at CRI > 0.4—ensures proactive risk mitigation, whereas Han et al. [19]’s elevated CRI2 values (0.62–0.72) reflect delayed responses, breaching safe thresholds.
In complex multi-obstacle environments (Scenarios 4.1–4.4), CRI1 maintains a mean value of 0.25–0.42, which is significantly below Han et al. [19]’s CRI2 (0.33–0.72). The divergence stems from the proposed algorithm’s dynamic weighting, where adaptive α and β coefficients prioritize spatial separation over temporal constraints. Notably, Han et al. [19]’s CRI2 exceeds 0.7 in Scenario 4.2 ( CRI 2 = 0.72 ), violating COLREGs Rule 8(a) by failing to execute "early and substantial" course changes. The proposed method’s integration of hierarchical risk assessment ensures compliance with CRI1 consistently below 0.4 in preparatory phases.
Extended validation under heterogeneous berthing conditions (Scenarios 4.5–4.8) further underscores the proposed algorithm’s superiority. CRI1 values stabilize at 0.20–0.46, while CRI2 fluctuates between 0.38 and 0.90, particularly spiking in overtaking (Scenario 4.8: CRI 2 = 0.90 ). The velocity-dependent safety boundaries ( a + v r T ) in CRI1 enable anticipatory deceleration, reducing α · D SAFE / DCPA penalties. Conversely, Han et al. [19]’s static obstacle modeling fails to account for relative velocity ( v r ), resulting in underestimated risks (e.g., Scenario 4.6: CRI 2 = 0.90 ). The proposed method’s COLREGs-compliant weight function λ ( θ CPA ) ensures scenario-specific prioritization, achieving 25–40% lower CRI values in congested operations.

5.3. Analysis

As evidenced by the simulation results in the preceding subsection, the ASV successfully achieves berthing under concurrent environmental disturbances and model uncertainties by tracking the prescribed trajectory generated via the proposed TTCCA scheme. Furthermore, the ASV demonstrates robust collision avoidance by navigating both static and dynamic obstacles across diverse operational scenarios, thereby conclusively validating the robustness and operational superiority of the TTCCA framework.
Moreover, as shown in Figure 10, Figure 14 and Figure 18, the proposed TTCCA scheme exhibits smoother control input profiles, which enhance controller execution stability. This improvement stems from the TTCCA framework’s decoupling of static and dynamic obstacle avoidance functions, enabling the simultaneous and optimized handling of both obstacle types.
In some scenarios, the proposed scheme has better collision avoidance performance than Han et al. [19]’s scheme. The reasons are mainly due to two key innovations.
(1)
Dynamic Obstacle Prediction: Unlike [19], which assumes static obstacle positions during the control horizon, TTCCA integrates the target vessel’s kinematic model into the NMPC optimization. This enables proactive trajectory adjustments based on predicted future obstacle positions, preventing last-minute maneuvers that breach safety margins.
(2)
COLREGs-Compliant Cost Shaping: While [19] employs a unified obstacle penalty function, TTCCA utilizes scenario-specific weighting strategies. For instance, in overtaking scenarios, the longitudinal separation weight λ = 0.5 prioritizes longitudinal separation, forcing the ASV to decelerate early and maintain a safe following distance.
In the complex scenario, the authors increased the number of obstacles and performed simulation experiments with different berths (berth 1 and berth 2). As a result, both schemes can avoid static and dynamic obstacles and reach the berth. According to Table 2, the proposed scheme exhibits superior berthing and obstacle avoidance performance compared to [19]’s method.
Furthermore, the average computation time per step is calculated across all scenarios, as detailed in Table 3. For [19]’s scheme, the average time ranges from 0.043 s to 0.048 s. Notably, the proposed TTCCA scheme achieves a significantly reduced computation time of 0.038 s to 0.039 s, demonstrating enhanced computational efficiency. These results confirm the TTCCA framework’s capability of providing real-time control for ASV automatic berthing.
The collision risk inference mechanism embeds COLREGs Rule 8 through a dual-layer framework combining geometric and behavioral analysis. The CRI employs an exponential penalty on diminishing DCPA/TCPA values, ensuring heightened sensitivity to critical thresholds. This contrasts with prior linear models, enabling earlier responses as mandated by Rule 8(a). The velocity-dependent safety boundary dynamically adapts to relative motion, distinguishing passive obstacles from maneuvering vessels. For instance, overtaking scenarios prioritize longitudinal deceleration (Rule 13), while crossing encounters enforce port turns (Rule 15). Experimental results validate rapid CRI escalation (0.7–0.9) during collision threats. This approach resolves multi-obstacle ambiguities and reduces decision latency by 20–40% compared to static models, integrating Rule 8 compliance as an architectural property rather than an external constraint.

6. Conclusions

This study presents a comprehensive investigation into the automatic berthing problem of ASVs. The automatic berthing task is systematically decomposed into three integral parts: trajectory planning, trajectory tracking, and collision avoidance.
First, focusing on the smoothness of the trajectory and the deceleration requirements near the berth, a novel A* algorithm integrated with quasi-uniform B-spline and quadratic interpolation (AQB) approach is proposed to plan a berthing trajectory from the initial position to the berth. Compared to the conventional A algorithm, the proposed A*QB method proves to be more suitable for the automatic berthing of ASVs, effectively addressing the complexities of low-speed maneuvering and near-shore navigation.
Secondly, to handle model uncertainties, input saturation, and environmental disturbances, nonlinear model predictive control (NMPC) is employed to solve the trajectory-tracking problem of ASVs. This approach ensures precise trajectory tracking through an explicit formulation of system dynamics and constraints.
Moreover, the proposed trajectory-tracking and COLREG-based collision avoidance (TTCCA) scheme is implemented within the NMPC framework. This integration enables the ASV to track the desired trajectory while simultaneously avoiding static and dynamic obstacles during berthing. The incorporation of COLREGs-compliant collision risk evaluation ensures adherence to international maritime regulations.
To validate the proposed scheme, extensive simulation experiments were conducted in four distinct scenarios, each representing various berthing challenges. The results demonstrate that the TTCCA scheme not only successfully accomplishes ASV automatic berthing but also outperforms existing methods in terms of obstacle avoidance success rate, safety margins, and real-time computational efficiency.
While this study provides a comprehensive solution for the automatic berthing of ASVs in harbor environments—encompassing trajectory planning, tracking, and COLREGs-compliant collision avoidance—several limitations remain. Specifically, the framework focuses primarily on open-water berthing scenarios, while the coastal transition phase (i.e., ASVs navigating from near-shore regions to final docking positions) remains unexplored. Future research will focus on refining the coastal transition phase to enhance the overall ASV berthing system. Additionally, while simulation experiments validate the scheme’s theoretical robustness, practical deployment necessitates further verification through extensive hardware-in-the-loop (HIL) simulations and field trials under stochastic environmental conditions. Collaborative efforts with maritime research institutions will be prioritized to bridge this gap, ensuring real-world reliability and regulatory compliance.
In conclusion, this study advances ASV autonomy by introducing a novel integrated framework addressing critical challenges in trajectory planning, tracking, and collision avoidance. The proposed A*QB trajectory planner and TTCCA control scheme collectively represent a paradigm shift in ASV navigation, offering enhanced safety, computational efficiency, and COLREGs adherence. These contributions lay a foundation for future developments in intelligent maritime transportation systems.

Author Contributions

Conceptualization, S.Y.; Methodology, S.Y.; Software, Y.H.; Formal analysis, Y.S.; Resources, H.J.; Writing—original draft, S.Y.; Writing—review & editing, G.S. and W.Z.; Visualization, S.S. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Dataset available on request from the authors.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Zhang, X.; Li, Z.; Wang, J. Impact of COVID-19 pandemic on energy consumption and carbon dioxide emissions in China’s transportation sector. Case Stud. Therm. Eng. 2021, 26, 101091. [Google Scholar] [CrossRef]
  2. Gu, Y.; Chen, Y.; Wang, X.; Chen, Z. Impact of COVID-19 epidemic on port operations: Evidence from Asian ports. Case Stud. Transp. Policy 2023, 12, 101014. [Google Scholar] [CrossRef] [PubMed]
  3. Talley, W.K.; Ng, M. Port multi-service congestion. Transp. Res. Part E: Logist. Transp. Rev. 2016, 94, 66–70. [Google Scholar] [CrossRef]
  4. Zhang, X.; Li, J.; Zhu, S.; Wang, C. Vessel intelligent transportation maritime service portfolios in port areas under e-navigation framework. J. Mar. Sci. Technol. 2020, 25, 1296–1307. [Google Scholar] [CrossRef]
  5. Im, N. A study on ship automatic berthing with assistance of auxiliary devices. Int. J. Nav. Archit. Ocean Eng. 2012, 4, 199–210. [Google Scholar]
  6. Liu, Q.; Li, T.; Shan, Q.; Yu, R.; Gao, X. Virtual guide automatic berthing control of marine ships based on heuristic dynamic programming iteration method. Neurocomputing 2021, 437, 289–299. [Google Scholar] [CrossRef]
  7. Maki, A.; Sakamoto, N.; Akimoto, Y.; Nishikawa, H.; Umeda, N. Application of optimal control theory based on the evolution strategy (CMA-ES) to automatic berthing. J. Mar. Sci. Technol. 2020, 25, 221–233. [Google Scholar] [CrossRef]
  8. Shuai, Y.; Li, G.; Cheng, X.; Skulstad, R.; Xu, J.; Liu, H.; Zhang, H. An efficient neural-network based approach to automatic ship docking. Ocean Eng. 2019, 191, 106514. [Google Scholar] [CrossRef]
  9. Skulstad, R.; Li, G.; Fossen, T.I.; Vik, B.; Zhang, H. A hybrid approach to motion prediction for ship docking—integration of a neural network model into the ship dynamic model. IEEE Trans. Instrum. Meas. 2020, 70, 2501311. [Google Scholar] [CrossRef]
  10. Johansen, T.A.; Perez, T.; Cristofaro, A. Ship collision avoidance and COLREGS compliance using simulation-based control behavior selection with predictive hazard assessment. IEEE Trans. Intell. Transp. Syst. 2016, 17, 3407–3422. [Google Scholar] [CrossRef]
  11. Yamato, H. Automatic berthing by the neural controller. In Proc. of Ninth Ship Control Systems Symposium; Department of the Navy: Washington, DC, USA, 1990; Volume 3, pp. 3183–3201. [Google Scholar]
  12. Im, N.; Hasegawa, K. Automatic ship berthing using parallel neural controller. IFAC Proc. Vol. 2001, 34, 51–57. [Google Scholar] [CrossRef]
  13. Ahmed, Y.A.; Hasegawa, K. Automatic ship berthing using artificial neural network trained by consistent teaching data using nonlinear programming method. Eng. Appl. Artif. Intell. 2013, 26, 2287–2304. [Google Scholar] [CrossRef]
  14. Qiang, Z.; Guibing, Z.; Xin, H.; Renming, Y. Adaptive neural network auto-berthing control of marine ships. Ocean Eng. 2019, 177, 40–48. [Google Scholar] [CrossRef]
  15. Xiong, Y.; Yu, J.; Tu, Y.; Pan, L.; Zhu, Q.; Mou, J. Research on data driven adaptive berthing method and technology. Ocean Eng. 2021, 222, 108620. [Google Scholar] [CrossRef]
  16. Self-tuning iterative learning control for an USV: Application to an autonomous berthing operation with an avoidance obstacle mechanism. Ocean Eng. 2024, 301, 117548. [CrossRef]
  17. Zhang, Y.; Zhao, H.; Zhang, Z.; Wang, H. Research on Ship Automatic Berthing Algorithm Based on Flow Matching and Velocity Matching. J. Mar. Sci. Eng. 2024, 12, 511. [Google Scholar] [CrossRef]
  18. Liao, Y.; Jia, Z.; Zhang, W.; Jia, Q.; Li, Y. Layered berthing method and experiment of unmanned surface vehicle based on multiple constraints analysis. Appl. Ocean Res. 2019, 86, 47–60. [Google Scholar] [CrossRef]
  19. 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]
  20. Woo, J.; Kim, N. Vision-based target motion analysis and collision avoidance of unmanned surface vehicles. Proc. Inst. Mech. Eng. Part M: J. Eng. Marit. Environ. 2016, 230, 566–578. [Google Scholar] [CrossRef]
  21. Li, S.; Liu, J.; Negenborn, R.R.; Wu, Q. Automatic docking for underactuated ships based on multi-objective nonlinear model predictive control. IEEE Access 2020, 8, 70044–70057. [Google Scholar] [CrossRef]
  22. Yuan, S.; Liu, Z.; Zheng, L.; Sun, Y.; Wang, Z. Event-based adaptive horizon nonlinear model predictive control for trajectory tracking of marine surface vessel. Ocean Eng. 2022, 258, 111082. [Google Scholar] [CrossRef]
  23. Zaccone, R. Colreg-compliant optimal path planning for real-time guidance and control of autonomous ships. J. Mar. Sci. Eng. 2021, 9, 405. [Google Scholar] [CrossRef]
  24. Eriksen, B.O.H.; Breivik, M.; Wilthil, E.F.; Flåten, A.L.; Brekke, E.F. The branching-course model predictive control algorithm for maritime collision avoidance. J. Field Robot. 2019, 36, 1222–1249. [Google Scholar] [CrossRef]
  25. Yuan, S.; Liu, Z.; Sun, Y.; Song, S.; Wang, Z.; Zheng, L. EMPMR berthing scheme: A novel event-triggered motion planning and motion replanning scheme for unmanned surface vessels. Ocean Eng. 2023, 286, 115666. [Google Scholar] [CrossRef]
  26. Fossen, T.I. Handbook of Marine Craft Hydrodynamics and Motion Control; John Wiley & Sons: Hoboken, NJ, USA, 2011. [Google Scholar]
  27. Mizuno, N.; Uchida, Y.; Okazaki, T. Quasi real-time optimal control scheme for automatic berthing. IFAC-PapersOnLine 2015, 48, 305–312. [Google Scholar] [CrossRef]
  28. Bitar, G.; Martinsen, A.B.; Lekkas, A.M.; Breivik, M. Two-stage optimized trajectory planning for asvs under polygonal obstacle constraints: Theory and experiments. IEEE Access 2020, 8, 199953–199969. [Google Scholar] [CrossRef]
  29. Sawada, R.; Hirata, K.; Kitagawa, Y.; Saito, E.; Ueno, M.; Tanizawa, K.; Fukuto, J. Path following algorithm application to automatic berthing control. J. Mar. Sci. Technol. 2021, 26, 541–554. [Google Scholar] [CrossRef]
  30. Hu, L.; Naeem, W.; Rajabally, E.; Watson, G.; Mills, T.; Bhuiyan, Z.; Salter, I. Colregs-compliant path planning for autonomous surface vehicles: A multiobjective optimization approach. IFAC-PapersOnLine 2017, 50, 13662–13667. [Google Scholar] [CrossRef]
  31. Yang, J.M.; Tseng, C.M.; Tseng, P. Path planning on satellite images for unmanned surface vehicles. Int. J. Nav. Archit. Ocean Eng. 2015, 7, 87–99. [Google Scholar] [CrossRef]
  32. Singh, Y.; Sharma, S.; Sutton, R.; Hatton, D.; Khan, A. A constrained A* approach towards optimal path planning for an unmanned surface vehicle in a maritime environment containing dynamic obstacles and ocean currents. Ocean Eng. 2018, 169, 187–201. [Google Scholar] [CrossRef]
  33. Chen, X.; Hu, R.; Luo, K.; Wu, H.; Biancardo, S.A.; Zheng, Y.; Xian, J. Intelligent ship route planning via an A* search model enhanced double-deep Q-network. Ocean Eng. 2025, 327, 120956. [Google Scholar] [CrossRef]
  34. Chen, X.; Riesenfeld, R.F.; Cohen, E. An algorithm for direct multiplication of B-splines. IEEE Trans. Autom. Sci. Eng. 2009, 6, 433–442. [Google Scholar] [CrossRef]
  35. Choi, Y.; Kim, D.; Hwang, S.; Kim, H.; Kim, N.; Han, C. Dual-arm robot motion planning for collision avoidance using B-spline curve. Int. J. Precis. Eng. Manuf. 2017, 18, 835–843. [Google Scholar] [CrossRef]
  36. Yuan, S.; Liu, Z.; Sun, Y.; Wang, Z.; Zheng, L. An event-triggered trajectory planning and tracking scheme for automatic berthing of unmanned surface vessel. Ocean Eng. 2023, 273, 113964. [Google Scholar] [CrossRef]
  37. Wang, Q.; Zhang, Q.; Wang, Y.; Hu, Y.; Guo, S. Event-triggered adaptive finite time trajectory tracking control for an underactuated vessel considering unknown time-varying disturbances. Transp. Saf. Environ. 2023, 5, tdac078. [Google Scholar] [CrossRef]
  38. Bakdi, A.; Vanem, E. Fullest COLREGs Evaluation Using Fuzzy Logic for Collaborative Decision-Making Analysis of Autonomous Ships in Complex Situations. IEEE Trans. Intell. Transp. Syst. 2022, 23, 18433–18445. [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 2022, 14, 198. [Google Scholar] [CrossRef]
  41. Vagale, A.; Bye, R.T.; Oucheikh, R.; Osen, O.L.; Fossen, T.I. Path Planning and Collision Avoidance for Autonomous Surface Vehicles II: A Comparative Study of Algorithms. J. Mar. Sci. Technol. 2021, 26, 1307–1323. [Google Scholar] [CrossRef]
  42. Gil, M. A concept of critical safety area applicable for an obstacle-avoidance process for manned and autonomous ships. Reliab. Eng. Syst. Saf. 2021, 214, 107806. [Google Scholar] [CrossRef]
Figure 1. Flow chart of the automatic berthing system.
Figure 1. Flow chart of the automatic berthing system.
Jmse 13 00903 g001
Figure 2. The process of generating smooth paths from the initial map.
Figure 2. The process of generating smooth paths from the initial map.
Jmse 13 00903 g002
Figure 3. Schematic diagram of four-connectivity and eight-connectivity A* algorithms. (a) 4-connectivity A* algorithm. (b) 8-connectivity A* algorithm.
Figure 3. Schematic diagram of four-connectivity and eight-connectivity A* algorithms. (a) 4-connectivity A* algorithm. (b) 8-connectivity A* algorithm.
Jmse 13 00903 g003
Figure 4. Schematic diagram of B-spline and quasi-uniform B-spline curves. (a) Conventional B-spline. (b) Quasi-uniform B-spline.
Figure 4. Schematic diagram of B-spline and quasi-uniform B-spline curves. (a) Conventional B-spline. (b) Quasi-uniform B-spline.
Jmse 13 00903 g004
Figure 5. Schematic diagram of different encounter scenarios based on COLREGs.
Figure 5. Schematic diagram of different encounter scenarios based on COLREGs.
Jmse 13 00903 g005
Figure 6. Schematic diagram of DCPA.
Figure 6. Schematic diagram of DCPA.
Jmse 13 00903 g006
Figure 7. Berthing and collision avoidance performance under different schemes (heading on) [19].
Figure 7. Berthing and collision avoidance performance under different schemes (heading on) [19].
Jmse 13 00903 g007
Figure 8. Heading angle under different schemes (heading on) [19].
Figure 8. Heading angle under different schemes (heading on) [19].
Jmse 13 00903 g008
Figure 9. Velocities under different schemes (heading on) [19].
Figure 9. Velocities under different schemes (heading on) [19].
Jmse 13 00903 g009
Figure 10. Control inputs under different schemes (heading on) [19].
Figure 10. Control inputs under different schemes (heading on) [19].
Jmse 13 00903 g010
Figure 11. Berthing and collision avoidance performance under different schemes (crossing) [19].
Figure 11. Berthing and collision avoidance performance under different schemes (crossing) [19].
Jmse 13 00903 g011
Figure 12. Heading angle under different schemes (crossing) [19].
Figure 12. Heading angle under different schemes (crossing) [19].
Jmse 13 00903 g012
Figure 13. Velocities under different schemes (crossing) [19].
Figure 13. Velocities under different schemes (crossing) [19].
Jmse 13 00903 g013
Figure 14. Control inputs under different schemes (crossing) [19].
Figure 14. Control inputs under different schemes (crossing) [19].
Jmse 13 00903 g014
Figure 15. Berthing and collision avoidance performance (overtaking) [19].
Figure 15. Berthing and collision avoidance performance (overtaking) [19].
Jmse 13 00903 g015
Figure 16. Heading angle under different schemes (overtaking) [19].
Figure 16. Heading angle under different schemes (overtaking) [19].
Jmse 13 00903 g016
Figure 17. Velocities under different schemes (overtaking) [19].
Figure 17. Velocities under different schemes (overtaking) [19].
Jmse 13 00903 g017
Figure 18. Control inputs under different schemes (overtaking) [19].
Figure 18. Control inputs under different schemes (overtaking) [19].
Jmse 13 00903 g018
Figure 19. Berthing and collision avoidance performance (heading on, berth 1) [19].
Figure 19. Berthing and collision avoidance performance (heading on, berth 1) [19].
Jmse 13 00903 g019
Figure 20. Berthing and collision avoidance performance (crossing, berth 1) [19].
Figure 20. Berthing and collision avoidance performance (crossing, berth 1) [19].
Jmse 13 00903 g020
Figure 21. Berthing and collision avoidance performance (overtaking, berth 1) [19].
Figure 21. Berthing and collision avoidance performance (overtaking, berth 1) [19].
Jmse 13 00903 g021
Figure 22. Berthing and collision avoidance performance (multiple vessels, berth 1) [19].
Figure 22. Berthing and collision avoidance performance (multiple vessels, berth 1) [19].
Jmse 13 00903 g022
Figure 23. Berthing and collision avoidance performance (heading on, berth 2) [19].
Figure 23. Berthing and collision avoidance performance (heading on, berth 2) [19].
Jmse 13 00903 g023
Figure 24. Berthing and collision avoidance performance (crossing, berth 2) [19].
Figure 24. Berthing and collision avoidance performance (crossing, berth 2) [19].
Jmse 13 00903 g024
Figure 25. Berthing and collision avoidance performance (overtaking, berth 2) [19].
Figure 25. Berthing and collision avoidance performance (overtaking, berth 2) [19].
Jmse 13 00903 g025
Figure 26. Berthing and collision avoidance performance (multiple vessels, berth 2) [19].
Figure 26. Berthing and collision avoidance performance (multiple vessels, berth 2) [19].
Jmse 13 00903 g026
Table 1. Controller parameters.
Table 1. Controller parameters.
Control Parameters Value
Time interval ( T S / s ) 0.1
Predictive horizon ( N P ) 30
Static predictive horizon ( N S ) 10
Control horizon ( N C ) 3
State error weight matrix ( Q ) d i a g ( 10 , 10 , 0.1 )
Control input weight matrix ( R ) d i a g ( 1 , 1 , 1 )
Terminal weight matrix ( P ) d i a g ( 1 , 1 , 1 )
Maximum input ( u m a x / [ N , N , N · m ] ) [ 1.5 , 1.5 , 2 ] T
Minimum input ( u m i n / [ N , N , N · m ] ) [− 1.5 , 1.5 , 2 ] T
Table 2. Minimum distance for both schemes in different scenarios.
Table 2. Minimum distance for both schemes in different scenarios.
ScenarioStatic DistanceDynamic Distance
Han et al. [19] (m) Proposed Scheme (m) Han et al. [19] (m) Proposed Scheme (m)
10.220.240.240.35
20.220.220.230.26
30.230.240.280.37
4.10.180.240.250.38
4.20.180.240.230.25
4.30.190.240.270.37
4.40.180.160.240.23
4.50.320.280.330.40
4.60.240.250.230.26
4.70.260.200.380.42
4.80.270.220.230.25
Table 3. Average cost time for both schemes in different scenarios.
Table 3. Average cost time for both schemes in different scenarios.
ScenarioHan et al. [19] (s)Proposed Scheme (s)
10.0480.039
20.0470.039
30.0480.039
4.10.0460.039
4.20.0450.039
4.30.0460.039
4.40.0450.039
4.50.0430.038
4.60.0430.038
4.70.0450.039
4.80.0440.038
Table 4. Collision Risk Index for Scenarios 1 to 3.
Table 4. Collision Risk Index for Scenarios 1 to 3.
Time (s)Scenario 1Scenario 2Scenario 3
CR11 CR12 CR11 CR12 CR11 CR12
100.400.400.400.400.410.40
200.400.400.380.400.400.40
300.410.410.410.410.400.69
400.360.390.450.410.400.39
500.290.430.370.430.400.39
600.390.370.390.410.440.44
700.370.380.390.400.430.62
800.170.260.400.400.460.33
900.400.400.400.400.410.41
1000.410.410.400.400.400.41
Table 5. Collision Risk Index for Scenarios 4.1 to 4.4.
Table 5. Collision Risk Index for Scenarios 4.1 to 4.4.
Time (s)Scenario 4.1Scenario 4.2Scenario 4.3Scenario 4.4
CR11 CR12 CR11 CR12 CR11 CR12 CR11 CR12
100.410.400.400.400.410.400.410.41
200.400.400.400.410.390.400.400.40
300.400.410.410.410.420.390.400.41
400.420.410.390.410.410.400.390.42
500.450.420.400.720.400.400.410.38
600.420.360.390.400.440.440.410.42
700.600.020.410.400.450.420.390.38
800.750.820.400.400.450.330.400.40
900.400.400.400.400.410.410.400.38
1000.390.410.400.400.400.410.400.40
Table 6. Collision Risk Index for Scenarios 4.5 to 4.8.
Table 6. Collision Risk Index for Scenarios 4.5 to 4.8.
Time (s)Scenario 4.5Scenario 4.6Scenario 4.7Scenario 4.8
CRI1 CRI2 CRI1 CRI2 CRI1 CRI2 CRI1 CRI2
100.400.400.410.400.410.400.410.40
200.400.400.400.400.390.410.400.40
300.400.400.400.400.390.400.400.40
400.530.410.400.410.530.020.410.41
500.470.420.400.420.430.390.450.44
600.420.370.440.380.430.380.430.41
700.410.410.410.370.410.410.420.54
800.410.410.470.900.410.410.440.56
900.410.410.410.410.410.410.410.41
1000.390.410.410.410.400.410.310.46
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

Yuan, S.; Sun, G.; He, Y.; Sun, Y.; Song, S.; Zhang, W.; Jiao, H. A Novel COLREGs-Based Automatic Berthing Scheme for Autonomous Surface Vessels. J. Mar. Sci. Eng. 2025, 13, 903. https://doi.org/10.3390/jmse13050903

AMA Style

Yuan S, Sun G, He Y, Sun Y, Song S, Zhang W, Jiao H. A Novel COLREGs-Based Automatic Berthing Scheme for Autonomous Surface Vessels. Journal of Marine Science and Engineering. 2025; 13(5):903. https://doi.org/10.3390/jmse13050903

Chicago/Turabian Style

Yuan, Shouzheng, Gongwu Sun, Yunqian He, Yuxin Sun, Simeng Song, Wanyuan Zhang, and Huifeng Jiao. 2025. "A Novel COLREGs-Based Automatic Berthing Scheme for Autonomous Surface Vessels" Journal of Marine Science and Engineering 13, no. 5: 903. https://doi.org/10.3390/jmse13050903

APA Style

Yuan, S., Sun, G., He, Y., Sun, Y., Song, S., Zhang, W., & Jiao, H. (2025). A Novel COLREGs-Based Automatic Berthing Scheme for Autonomous Surface Vessels. Journal of Marine Science and Engineering, 13(5), 903. https://doi.org/10.3390/jmse13050903

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