Next Article in Journal
Review of Evolution and Rising Significance of Wafer-Level Electroplating Equipment in Semiconductor Manufacturing
Previous Article in Journal
Improved Droop Control Strategy for Islanded Microgrids Based on the Adaptive Weight Particle Swarm Optimization Algorithm
Previous Article in Special Issue
High-Precision Main Shaft Displacement Measurement for Wind Turbines Using an Optimized Position-Sensitive Detector
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Finite Time ESO-Based Line-of-Sight Following Method with Multi-Objective Path Planning Applied on an Autonomous Marine Surface Vehicle

1
School of Information Science and Engineering, Fudan University, Shanghai 200433, China
2
Department of Electrical and Electronic Engineering, The Hong Kong Polytechnic University, Kowloon 999077, Hong Kong
*
Author to whom correspondence should be addressed.
Electronics 2025, 14(5), 896; https://doi.org/10.3390/electronics14050896
Submission received: 3 January 2025 / Revised: 11 February 2025 / Accepted: 21 February 2025 / Published: 24 February 2025

Abstract

:
The multi-objective path planning and robust continuous path-following method for the autonomous marine surface vehicle (AMSV) is employed. By incorporating the position and direction constraints into the optimization cost function, the spiral path planner obtains a continuous path with smooth path tangency and curvature and ensures strict adherence to the desired multi-objective points. An improved A* and optimization algorithm are combined with the global path planning to avoid obstacles in real-time. For the path-following controller, the unknown sideslip angle and uncertainties are added to build the system model, based on which observation technique is adopted to estimate all the uncertainties online. Based on the kinematic system, a finite time extended state observer (ESO) is put forward to estimate the sideslip angle accurately. The nonlinear line-of-sight (LOS) guidance scheme is designed for the model, effectively compensating for the observed values and achieving convergence in a finite time. The finite-time ESO is adopted to estimate the uncertainty for the surge and heading controller design, and the terminal sliding mode technique is introduced to achieve the final finite-time convergence. Through extensive experiments, the proposed approach demonstrates its effectiveness, feasibility, and the advantage of fast convergence and accurate control.

1. Introduction

Many path-planning and path-following methods of the autonomous driving system (ADS) have been developed for the under-actuated-based marine surface vehicle (MSV). For the AMSV, having a continuous reference path that can achieve smooth control without overshooting is essential [1]. The AMSV needs to pass through each intermediate point precisely in the multiple-objective navigation path (MONP), where the multi-objective refers to the intermediate points (including position and orientation) that are used to generate the global path. A simple way to plan a MONP is to connect all the objective waypoints with straight lines, but this causes discontinuity in the path-tangential angle at the junctions, which may lead to cross-track error or instability. To solve this problem, the Dubins proposed a path generator that uses straight lines and inscribed circle arcs [2]. However, this method still has a discontinuity in the curvature, which causes a sudden change in the desired yaw angle velocity at straight line and circle arc transitions. In [3], a cubic Hermite spline-based path planner algorithm was developed to generate a smooth path, but it cannot exactly pass through the target waypoint. To pass through all the objective points smoothly, especially when facing obstacles, the optimization scheme based on the critical constraints was mentioned in [4]. The kinematic controller uses the guidance law (GDL) to follow the reference path in this method. Then, the dynamics controller uses the GDL to make the vehicle track the command velocity and course angle. LOS-GDL was first introduced in [5] and has been widely used in vehicle path-following control [6]. These methods assume that the sideslip angle is measurable, but in practice, it should be calculated by the sway speed. To improve system performance, the integral LOS and adaptive LOS [7] are used to deal with the drift force and wave disturbance, but the stability characteristics of the guidance system still need further study. The active disturbance rejection control (ADRC) was first mentioned in [8] and has been extensively applied in practical applications [9]. The ESO, which is the essential part of ADRC, can estimate the system’s unmeasured state and total disturbance and form the corresponding feedback controller [10]. In [11], the unknown nonlinear function with sideslip angle was reconstructed as a system state, and then ESO was used to estimate and compensate for this unknown nonlinear term in the GDL. The extended state of this method also contains a known nonlinear factor, which increases the uncertainty to be estimated and limits the bandwidth of the ESO.
After planning the global path, a local path modifier method must be considered to adjust the global path according to the dynamic environment and the obstacle motion [12]. It involves detecting and avoiding potential collisions with other vessels or static obstacles in a dynamic environment while complying with the rules and regulations of navigation. The authors of [13] proposed an automatic MSV control system that can navigate and steer in a narrow environment using the camera, radar, ultrasound, and a deep learning-based segmentation method. This method can identify the area where the vessel can sail safely. The system also used an MPC-based algorithm to generate and follow a collision-free real-time path. An improved A-star algorithm and an improved dynamic window method for MSV path planning and collision avoidance in crowded and highly uncertain sea areas were proposed by [14]. These methods enabled the vessel to sail autonomously by planning and updating the real-time path and avoiding obstacles effectively. Using a partial minimum consensus method in a layered structure, the MSV navigation system in [15] could navigate quickly to the target point while avoiding and distancing from obstacles. Meanwhile, ocean current interference was only considered in path planning, ignoring its influence on the control stage, resulting in a discontinuous curvature scene of the planned path, which affects path-following accuracy. By combining global and local path planning in [16], discrete optimal paths were generated globally, surge and yaw velocity were generated locally according to fuzzy decision-making and precisely adjusted dynamic window modules, which could generate the shortest path and handle some unknown and uncertain scenes. However, this scheme did not consider the intermediate point constraint during planning, it is unsuitable for continuous navigation between multi-objective paths. Besides, this method based on accurate adjustment of dynamic windows would be easy to fall into local optimal in complex scenes, affecting the navigation efficiency. Ref. [17] introduced a Gaussian process motion planning 2-star controller that can handle complex environments with multiple environmental characteristics, such as the ocean. This controller extended the essential motion planning based on the Gaussian process, which only works for environments with obstacles. In [18], obstacle information was directly put into the model-free reinforcement learning control, which avoided complex modeling by optimizing the physical constraints of the AMSV itself and simultaneously greatly reduced the amount of computation. However, the generated path did not consider the influence of obstacles, and the path following based on reinforcement learning requires a large amount of training data and did not involve the changes in the external environment (ocean currents) and internal factors (such as mass).
Various vehicle motion control algorithms based on the GDL have been proposed to make the AMSV track the command velocity and course angle. The neural network algorithm was used to estimate the uncertainties [19] but is hard to apply in practice due to the high dependence on initial values. The backstepping algorithm was used [20,21] but could not achieve finite-time convergence. In [22,23], the sliding mode control (SMC) method was used to design the motion controller, but it suffered from the chattering phenomenon. To overcome this problem, a high-order SMC was proposed [24,25] to sacrifice the high calculation burden. An adaptive robust control method was used to improve the control performance under uncertainties [26]; however, it is very conservative. Recently, the disturbance–observer (DOB)-based method has been studied extensively in the motion controller design to enhance robustness and performance [27].
The multi-objective following task solved here involves path planning and robust controller design. The path planner generates a smooth path that can pass through all the objective waypoints. When obstacles exist, the real-time obstacle avoidance planning algorithm will generate paths that avoid the obstacles based on the orientation of these intermediate points to ensure that the AMSV can reach the target position safely and stably. The robust controller reduces or eliminates the effects of nonlinearity, strong coupling, and uncertainties.
The main contributions are summarized as follows:
  • A multi-objective spiral programming algorithm generates a continuous and sequential path that passes through all target points.
  • An improved A* algorithm and an optimization algorithm are combined to perform global path planning and timely obstacle avoidance near the path.
  • A finite-time ESO is constructed to estimate the time-varying unknown sideslip angle and a nonlinear feedback LOS-GDL is built to achieve finite-time convergence.
  • A terminal sliding mode and a nonlinear DOB are used to build a surge course finite-time controller.
The problem description and MSV model are given in Section 2. Section 3 presents a multi-objective spiral path planner and path smoothing. Section 4 introduces a finite-time ESO to estimate the unknown and time-varying sideslip angle and uses a nonlinear feedback LOS-GDL to achieve finite-time convergence. Section 5 designs a finite-time surge and heading controller. Section 6 gives the results and its analysis. Section 7 concludes the proposed work.

2. System Statement

2.1. Problem Formulation

Figure 1 illustrates the framework of the AMSV system, while Figure 2 shows the structure of the proposed method. By integrating these two figures, we can provide a detailed description of the entire control system as follows:
(1). In the Multi-Objective Global Planner shown in Figure 1a, a smooth reference path that goes through all the target points without overshooting so that the AMSV can follow the path accurately;
(2). In Figure 1b, the obstacle avoidance algorithm that uses global path planning with improved A* and optimization to avoid obstacles near the route in time;
(3). A path-following controller that consists of the LOS guidance algorithm for horizontal kinematics is shown in Figure 1d, and a robust motion controller is given in Figure 1e for surge and heading kinematics, which stabilizes the error system and makes the AMSV track the reference path quickly and precisely.
(4). Figure 1c shows the geometric relationship between LOS-GDL and the expected track based on forward-looking distance. The current position coordinate is defined as ( x , y ) and the pedal point as ( x p , y p ) ; thus, y e is the orthogonal disturbance from the current location to ( x p , y p ) and similarly to the longitudinal error x e .
Since this method is designed for multi-target paths, the kinematic constraints of the AMSV must be followed at each intermediate point, which significantly increases the amount of computation as the number of target points increases. However, for the autonomous driving process, the global path planning algorithm can be calculated offline, so it will not have a big impact on the actual performance of autonomous driving. In addition, the local obstacle avoidance path of this solution generated by Figure 1b adopts real-time planning.
The path-tangential angle γ p and the cross-track error y e can be obtained according to the waypoints of the reference path, while the sideslip angle β s is usually unmeasured. β s is caused by drift forces, which is usually less than 5 ° , but it affects the path-following control for the AMSV and needs to be estimated and compensated in the guidance algorithm. And its time-derivative β ˙ s is obtained in (1), where v s u , v s w are the speed of surge and sway. Obviously, β s and β ˙ s are bounded and defined as: β s β 1 , | β ˙ s | β 2 .
β ˙ s = v ˙ s w v s u v ˙ s u v s w v s u 2 + v s w 2

2.2. Description of the AMSV Model

The 3-DOF kinematics of the AMSV is presented in (2) based on the paper [28], where ψ , and v y a represent the yaw angle and the yaw speed.
x ˙ = v s u cos ψ v s w sin ψ y ˙ = v s u sin ψ + v s w cos ψ ψ ˙ = v y a
Assume that the rotation angle of the path tangent reference system is γ p , then the trajectory tangent reference system can be described by γ p and the rotation matrix R ( γ p ) [29]. By rotating γ p , and using the attitude transition matrix R ( γ p ) , x e and y e are given in (3).
x e y e = R ( γ p ) T x x p y y p R ( γ p ) T = cos ( γ p ) sin ( γ p ) sin ( γ p ) cos ( γ p )
x ˙ e = v cos ψ γ p + β s + γ ˙ p y e v s u y ˙ e = v sin ψ γ p + β s γ ˙ p y e
According to (3), the first-order time derivative of x e and y e can be given. Considering that the sideslip angles caused by the drift effect are small (<5°), x ˙ e and y ˙ e can be approximated by trigonometric functions and are shown in (4), where the amplitude v = v s u 2 + v s w 2 > 0 and the phase β s = arctan ( v s w , v s u ) are the speed and sideslip angle, respectively.
The 3-DOF AMSV dynamics is given in (5), where m i i and d i i , ( i = 1,2 , 3 ) denote the nominal values of the AMSV inertial and damping, τ s u and τ y a stand for the surge force and yaw moment, respectively. τ i , ( i = 1,2 , 3 ) is the total disturbances of the three axes. v s u = v cos ( β ^ s ) and v s w = v sin ( β ^ s ) are used, where β ^ s denotes the estimation of β s .
m 11 v ˙ s u = m 22 v s w v y a d 11 v s u + τ s u + τ 1 m 22 v ˙ s w = m 22 v s u v y a d 22 v s w + τ 2 m 33 v ˙ y a = m 11 m 22 v s u v s w d 33 v y a + τ y a + τ 3

3. Path Planning and Smoothing

3.1. Spiral Path Planner

The proposed method for the LOS guidance algorithm assumes that the AMSV can follow a reference path perfectly with y ˙ e = 0 and y e = 0 , which implies (6). When there exists y e and yaw angle tracking error ψ ~ = ψ ψ d , by substituting the control output ψ d of the proposed GDL in Section 4.2, (7) is obtained, where β ~ s = β s β ^ s is the estimation error of β s , and Δ L is the look-ahead distance, s i g n ϱ x = x x ϱ 1 [30]. As β s is relatively small, thus, if y e , ψ ~ and β ~ s are bounded, ψ γ p is also bounded.
ψ γ p = β s
ψ γ p = tan 1 sign ϱ 1 y e Δ L β s + β ~ s + ψ ~
A spiral path is defined as (8), where n is the order of a spiral path, s ( 0 , s f ) and s f is the length of the path, θ is the initial position path angle, κ and γ denote the curvature and orientation of the path, respectively. The state vector is given as p s = [ x s y s θ s κ s ] , and its parameters can be expressed as q = [ a 0 a 1 a n s f ] . The planned path should satisfy these conditions:
y e should be below a certain threshold, and the path should switch to a continuous mode when the lateral error exceeds that threshold.
The reference path should have the same orientation as the marine vessel near the pedal point so that the initial value of ψ ~ is small enough.
The path should end at the same position and orientation as the target point and have a low curvature near the end.
κ s = i = 0 n a i s i , γ s = i = 0 n a i i + 1 s i + 1 x s = 0 s cos ( θ ( s ) ) ds , y s = 0 s sin ( θ ( s ) ) ds
min : J q = 1 2 0 s f [ κ q ] 2 ds c o n s t r a i n t s : p 0 p s t a r t = 0 , p s f p e n d = 0
| ψ γ p | δ < π 2
The path planning problem is expressed as the optimization cost function in (9), which considers the start and target point constraints and is a constrained nonlinear convex optimization problem that numerical methods can solve. The first constraint ensures that the y e is very small. For β ~ s and ψ ~ , they will be bounded if the desired ESO and dynamics controller can converge asymptotically, with a proper choice of the origin point. As (7) bounded, ψ γ p in (10) is reasonable, which indicates that cos ( ψ γ p ) > 0 and 1 < 1 cos ( ψ γ p ) < 1 cos δ . If the vessel’s course deviates too much from the tracked path, either by being orthogonal or opposite to it, then (10) does not hold. In this case, the path needs to be replanned by generating a smooth curve that starts from the current position and orientation of the vessel.

3.2. Path Smoothing

If y e is larger than the setting upper bounded, the proposed Algorithm 1 can be applied directly to replan a smooth path without overshot. Thus, y e can be constrained into an upper bound defined as y ¯ e .
Algorithm 1 Spiral Path Generator
Input:Target point sequence ( x i , y i ) , i = 0 ~ n , where i = 0 denotes the current position of the AMSV
Output:A smooth reference path denoted by r ( x , y )
1.Assign target orientation from 1 s t to n 1 t h target point
2.for k = 0 n 1 do
3.    θ k = arctan 2 y k + 1 y k , x k + 1 x k , p k = [ x k y k θ k 0 ]
4.end for
5.for k = 0 n 1 do
6.Connect p k 1 and p k to acquire a straight line
7.  Calculate the coordinate of p j o i n t 1 according to the yaw error from p k 3 to θ k :
   p k j o i n t 1 1,2 = p k 1,2 + c o s ( θ k ) sin ( θ k ) K ( p k 3 θ k )
                                 p k j o i n t 1 3 = p k 3 , p k j o i n t 1 4 = 0
8.  Generate spiral path q 0 from p s t a r t to p k j o i n t 1
9.  Calculate the coordinate of p j o i n t 2 according to the yaw error from θ k to p k + 1 3 :
   p k j o i n t 2 1,2 = p k + 1 1,2 cos ( θ k ) sin ( θ k ) K ( θ k p k + 1 3 )
                                 p k j o i n t 2 3 = p k + 1 3 , p k j o i n t 2 4 = 0
10.  Generate spiral path q k from p k j o i n t 2 to p k + 1
11.Exert straight path from p k j o i n t 1 to p k j o i n t 2 , the spiral path p k to p k j o i n t 1 , and p k j o i n t 2 to p k + 1 , then, the track point coordinates: r ( x , y , θ , k )
12.end for
The path-smoothing with obstacle avoidance details are given in Figure 1b, where objective points are r i r x _ i , r y _ i and the corresponding point in the smooth path is p i p x _ i , p y _ i . After connecting these objective points, a rough path ( r 0 r 1 r 2 r i ) is generated. For the path-smooth control that used the local path plan method, the improved A algorithm is applied to avoid obstacles in real time shown in Algorithm 2. Based on this, a smooth trajectory is generated by updating and connecting these points { p 0 , p 1 , , p i } . The improved A* algorithm proposed here performs uniform point sampling along the global reference path while considering kinematic constraints. There is no need to establish a local grid map, which reduces the number of search points and can optimize the search path in real-time. While ensuring smoothness, it greatly reduces the time required to generate an obstacle avoidance path, improves search efficiency, and greatly improves driving safety performance.
Algorithm 2 Improved A algorithm with rough path generation
Input: τ u : Current velocity of AMSV
D s a f e : Safe distance between AMSV to obstacles
L max : Max sampling length      L min : Min sampling length
S n : Obstacle information(1……n)
S : Start vertex     E : End vertex     C : Current vertex
Output:Path: Rough path with free-obstacle
1.vertexs SamplePoints (τ_u, L_(min,) L_max)
2.vertexs.obstacle_cost ObstacleCostCaculate (vertexs, D_safe S_1,S_2……S_n)
3. E ← GetEndPoint(τ_u, s_1,s_2……s_n)
4.ℂ=S;
5.While ℂ≠E
6. v n e i g h b o r GetNeighborVertexs(ℂ,”vertexs”)
7. g NeighborCurrentCostCaculate (v_neighbor)
8. h NeighborHeuristicValueCaculate (v_neighbor)
9. f NeighborFinalCostUpdate (v_neighbor, g , h , obstacle_cost)
10. c UpdateCurrentVertexWithLowestCost(v_neighbor)
11.EndWhile
12.Build Path rooted at S
13.Return Path
To make the path smoother and save energy, we defined three cost functions: cos t 1 is the smooth factor that should be kept in a reasonably small range, cos t 2 is the safety factor that keeps the path away from the obstacles, and cos t 3 indicates the cost principle of energy consumption. Besides, the cost function J is set as the minimum of the sum of cos t 1 , cos t 2 , and cos t 3 . Finally, J can be converted into a quadratic programming (QP) problem and solved with an operator-splitting QP optimizer [31] with a perfect application programming interface.
cos t 1 = i = 0 N 2 ( p x _ i + p x _ i + 2 2 p x _ i + 1 ) 2 + ( p y _ i + p y _ i + 2 2 p y _ i + 1 ) 2
cos t 2 = i = 0 N ( p x _ i r x _ i ) 2 + ( p y _ i r y _ i ) 2
cos t 3 = i = 0 N 1 ( p x _ i p x _ i 1 ) 2 + ( p y _ i p y _ i 1 ) 2
J = min ( cos t 1 + cos t 2 + cos t 3 )

4. Path-Following Control Based on ESO-Based Finite-Time LOS Guidance

4.1. Finite-Time Sideslip Angle Observation

A finite-time ESO is designed to estimate the time-varying of β s . The unknown system, uncertainly estimated, should be reconstructed as an additive system state to formulate a new system model. Expanding (4) to (11) and using the approximations cos β s 1 , and sin β s β s , (12) is achieved.
y ˙ e = v sin ψ γ p cos β s + v cos ψ γ p sin β s
y ˙ e = v sin ψ γ p + v cos ψ γ p β s
By introducing x 1 = y e , x 2 = β s , h t = β ˙ s , the dynamic of y e can be reconstructed as (13), ψ γ p = N . To estimate β s , a finite-time ESO is designed as (14), where ϱ 1 is a positive constant that satisfies 0.5 < ϱ 1 < 1 , z 2 equals to β ^ s .
x ˙ 1 = v sin N + v cos N x 2 x ˙ 2 = h ( t )
z ˙ 1 = v sin N + v cos N z 2 + λ 1 sign ϱ 1 ( y e z 1 ) z ˙ 2 = λ 2 sign ϱ 1 ( y e z 1 )
Theorem 1.
Using the ESO,  β ~ s  is globally uniform and asymptotically stable and can reach a tiny neighborhood near 0 in a finite time with the appropriate control parameters.
ϵ ˙ 1 = v cos ψ γ p ϵ 2 λ 1 sign ϱ 1 ( ϵ 1 ) ϵ ˙ 2 = λ 2 sign ϱ 1 ϵ 1 + β ˙ s
Proof. 
Define the error variables ϵ 1 = y e z 1 , ϵ 2 = β s z 2 , and its dynamics are given in (15). □
The Lyapunov function L 1 of the ESO is built as (16), which satisfies: σ min ( E 0 ) ϑ 2 L 1 σ max ( E 0 ) ϑ 2 , where operator σ min ( ) and σ max ( ) are the minimum and maximum singular values of the matrix.
L 1 = ϑ T E 0 ϑ ,   ϑ = [ sign ϱ 1 ϵ 1   ϵ 2 ] T
ϑ ˙ = A 0 ϑ + B 0 h ( t ) A 0 = ϱ 1 μ 1 λ 1 ϱ 1 μ 1 μ 2 λ 2 0 , B 0 = 0 1  
Dynamics of ϑ is given as (17), where μ 1 = ϵ 1 ( ϱ 1 1 ) > 0 , μ 2 = v cos ψ γ p is bounded. If 0.5 < ϱ 1 < 1 is selected and based on the properly defined λ 1 and λ 2 , A 0 is obtained as a Hurwitz matrix. Thus, there has a positive definite matrix P d to meet (18). (19) is the first derivative of L 1 , where | β ˙ s | β 2 .
A 0 T E 0 + E 0 A 0 = P d
L ˙ 1 ( σ min P d ϑ 2 β 2 B 0 T E 0 ) ϑ
Matrix A 0 can be converted into a product of two matrices A 1 and A 2 , thus, (21) is obtained.
A 0 = A 1 A 2 , A 1 = ϱ 1 μ 1 0 0 1 ,   A 2 = λ 1 μ 2 λ 2 0
σ min A 0 = σ min ( A 1 A 2 ) σ min ( A 1 ) σ min ( A 2 )
σ min A 1 = 1 ,   ϵ 1 < 1 ϱ 1 1 ϱ 1 1   ϱ 1 μ 1 ,   ϵ 1 1 ϱ 1 1 ϱ 1 1
Since ϱ 1 μ 1 < μ 1 , there exists (22). Case 1: when ϵ 1 1 ϱ 1 1 ϱ 1 1 , then ϑ 1 ϱ 1 ϱ 1 ϱ 1 1 , and (23) is obtained. Combining (19) and (23) gets (24).
σ min P d 2 ϱ 1 μ 1 σ min ( A 2 ) σ min ( E 0 )
L ˙ 1 2 ϱ 1 μ 1 σ min A 2 σ min E 0 ϵ 1 ϱ 1 2 β 2 B 0 T E 0 ϑ 2 ϱ 1 1 ϱ 1 2 ϱ 1 1 ϱ 1 1 σ min A 2 σ min E 0 2 β 2 B 0 T E 0 ϑ
There is a constant v 1 that satisfy (25) when ϱ 1 ( 0.5 , 1 ) . (26) can be obtained, as λ 1 and λ 2 are defined to ensure v 1 σ min ( A 2 ) σ min ( E 0 ) > β 2 B 0 T E 0 .
ϱ 1 1 ϱ 1 2 ϱ 1 1 ϱ 1 1 v 1
L ˙ 1 Γ 1 L 1 1 2 ,   Γ 1 = ρ 1 σ max E 0 ρ 1 = 2 v 1 σ min A 2 σ min E 0 β 2 B 0 T E 0
Based on the above analysis, ϑ can converge to ϑ 1 ϱ 1 ϱ 1 ϱ 1 1 in a finite time t 1 ,
t 1 2 Γ 1 L 1 1 2 ϑ ( t ) 2 Γ 1 L 1 1 2 ϑ ( t 0 )
Case 2: when ϑ < 1 ϱ 1 ϱ 1 ϱ 1 1 , then ϵ 1 < 1 ϱ 1 ϱ 1 ϱ 1 1 . Substituting (28) into (19), then (29) is obtained.
σ min P d 2 σ min ( A 2 ) σ min ( E 0 )
L ˙ 1 ( 2 σ min ( A 2 ) σ min ( E 0 ) ϑ 2 β 2 B 0 T E 0 ) ϑ
1 ϱ 1 ϱ 1 ϱ 1 1 > ϑ > β 2 B 0 T E 0 σ min ( A 2 ) σ min ( E 0 ) = v 2
L ˙ 1 Γ 2 L 1 1 2 ,   Γ 2 = ρ 2 σ max E 0 ρ 2 > 2 v 2 σ min A 2 σ min E 0 2 β 2 B 0 T E 0 = 0
ϑ β 2 B 0 T E 0 σ min ( A 2 ) σ min ( E 0 )
t 2 2 Γ 2 L 1 1 2 ϑ ( t ) 2 Γ 2 L 1 1 2 ϑ ( t 1 )
Getting (31) from (30), if it holds true. This means that ϑ will reach the region in (32) after a finite time t 1 + t 2 . Using (26) and (31), the observer estimation error has a global uniform asymptotic bound. Since β s changes slowly, β ˙ s is small. Choosing suitable parameters to make σ min A 2 σ min E 0 big enough, thus ϑ will approach 0 very closely in a finite time.

4.2. Finite-Time LOS Guidance

With the estimated sideslip angle β ^ s , the command course angle ψ d is designed as (34), where ϱ 2 is a positive constant satisfying 0 < ϱ 2 < 0.5 . Then, the command virtual velocity can be obtained as (35), and k 1 is a positive constant.
ψ d = γ p + tan 1 sign ϱ 2 ( y e ) Δ L β ^ s
u d = v cos ψ γ p + β ^ s + k 1 sign ϱ 2 x e
After substituting (34), (35) into the kinematics of MSV, (3) can be re-described in (36).
x ˙ e = v cos N + β s cos N + β ^ s + γ ˙ p y e k 1 sign ϱ 2 x e y ˙ e = v sin tan 1 sign ϱ 2 ( y e ) Δ L + β ~ s γ ˙ p x e
sin tan 1 sign ϱ 2 ( y e ) Δ L = sign ϱ 2 ( y e ) Δ L 2 + y e 2 Q 2 cos tan 1 sign ϱ 2 ( y e ) Δ L = Δ L Δ L 2 + y e 2 ϱ 2
x ˙ e = 2 v sin N + β s + β ^ s 2 sin β ~ s 2 + γ ˙ p y e k 1 sign ϱ 2 x e y ˙ e = U sign ϱ 2 y e Δ L 2 + y e 2 ϱ 2 + U Δ L β ~ s Δ L 2 + y e 2 ϱ 2 γ ˙ p x e
Using the trigonometric transformation in (37) and assuming cos β ~ s 1 and sin β ~ s β ~ s , (38) can be finally obtained.
Theorem 2.
The interconnected system is globally uniform asymptotic bounded and has a stable equilibrium point at the origin in a finite time, if using the ESO observer in (14) and the GDL in (34) and (35) and assume that  β ˙ s  has a limit.
Proof. 
L 2  is defined as a Lyapunov function
L 2 = 1 2 2 ϱ 2 x e 2 2 ϱ 2 + y e 2 2 ϱ 2
Considering (38) and the below equation, (40) is obtained.
sin N + β s + β ^ s 2 1 ,   sin β ~ s 2 β ~ s 2
L ˙ 2 k 1 x e 1 ϱ 2 + v x e 1 2 ϱ 2 β ~ s v Δ L 2 + y e 2 ϱ 2 y e 1 ϱ 2 + v Δ L Δ L 2 + y e 2 ϱ 2 1 v cos ψ γ p y e 1 2 ϱ 2 β ~ s
v x e 1 2 ϱ 2 β ~ s v 1 2 ϱ 2 ε 1 1 ϱ 2 1 2 ϱ 2 1 ϱ 2 x e 1 ϱ 2 + 1 ε 1 1 ϱ 2 ϱ 2 α 1 ϑ 1 ϱ 2 ϱ 2
According to Young’s inequality, (41) is achieved.
v Δ L Δ L 2 + y e 2 ϱ 2 1 v cos ψ γ p y e 1 2 ϱ 2 β ~ s v Δ L 2 + y e 2 ϱ 2 1 2 ϱ 2 ε 2 1 ϱ 2 1 2 ϱ 2 1 ϱ 2 y e 1 ϱ 2 + v ϱ 2 λ 1 2 + 1 Δ L 1 ϱ 2 Δ L ε 2 v cos ψ γ p 1 ϱ 2 ϱ 2 α 2 ϑ 1 ϱ 2 ϱ 2
k 1 v 1 2 ϱ 2 ε 1 1 ϱ 2 1 2 ϱ 2 1 ϱ 2 α 3 1 2 ϱ 2 ε 2 1 ϱ 2 1 2 ϱ 2 1 ϱ 2 + α 4 1
L 3 = Θ T E 1 Θ , E 1 = 1 1 2 ϱ 2 0 0 1 × 2 0 1 1 2 ϱ 2 0 1 × 2 0 2 × 1 0 2 × 1 E 0
L ˙ 3 k 1 x e 1 ϱ 2 + v x e 1 2 ϱ 2 β ~ s v Δ L 2 + y e 2 ϱ 2 y e 1 ϱ 2 + v Δ L Δ L 2 + y e 2 ϱ 2 1 v cos ψ γ p y e 1 2 ϱ 2 β ~ s min ρ 1 ,   ρ 2 ϑ α 3 x e 1 ϱ 2 α 4 v 2 + y e 2 ϱ 2 y e 1 ϱ 2 + α 1 + α 2 ϑ 1 ϱ 2 ϱ 2 min ρ 1 ,   ρ 2 ϑ α 1 v Δ L 2 + y e 2 ϱ 2 y e 1 ϱ 2 α 2 ϑ 2 + α 5
ε 1 and ε 2 are chosen and α 3 and α 4 are positive constants. Defining Θ = x e 1 ϱ 2 y e 1 ϱ 2 ϑ T T , then the Lyapunov function L 3 is achieved and described in (42), where 0 1 × 2 and 0 2 × 1 are the zero vector. Using (19) to find the time-derivate of L 3 and shown in (43), when t < t 1 + t 2 . Choosing a suitable variable ε 3 , so that,
1 ϱ 2 ϱ 2 ε 3 1 ϱ 2 ϱ 2 + α 2 > m i n ρ 1 ,   ρ 2 α 5 = ϱ 2 2 ϱ 2 1 α 1 + α 2 ε   3 ϱ 2 2 ϱ 2 1
Then, the system is globally uniformly bounded when t < t 1 + t 2 . If t t 1 + t 2 ; notice from (33) that ϑ v 2 .
L ˙ 2 α 3 x e 1 ϱ 2 α 4 v Δ L 2 + y ¯ e 2 ϱ 2 y e 1 ϱ 2 + α 0 + α 1 v 2 2 ϱ 2 1 ϱ 2 Γ 3 V 2 1 2 + α 0 + α 1 v 2 2 ϱ 2 1 ϱ 2
Γ 3 = 1 2 2 ϱ 2 m i n α 3 ,   α 4 v Δ L 2 + y ¯ e 2 ϱ 2
Overall, the path-following error can converge to the tiny neighborhood of the origin in a finite time.

5. Finite-Time Control System Design in Path Following

After using the finite-time ESO to estimate the unknown system uncertainties for both surge and heading axes, the finite-time high-order sliding mode controllers (SMC) is designed to stabilize these two axes. Defining the auxiliary variables v ^ ˙ s u and v ^ ˙ y a with the dynamics in (45), the equivalent disturbance estimation of the surge and heading axes are given in (46), where λ 3 ~ λ 6 are positive constants that can be chosen, ϱ 3 and ϱ 4 are positive constants that satisfy: 0 < ϱ 3 < 1 , 0 < ϱ 4 < 1 .
m 11 v ^ ˙ s u = m 22 v s w v y a d 11 v s u + τ s u + τ ^ 1 m 33 v ^ ˙ y a = m 11 m 22 v s u v s w d 33 v y a + τ y a + τ ^ 3
τ ^ 1 = λ 3 sign ϱ 3 m 11 v s u v ^ s u + λ 4 0 t sign ϱ 3 m 11 v s u τ v ^ s u τ d τ τ ^ 3 = λ 5 sign ϱ 3 m 11 v y a v ^ y a + λ 6 0 t sign ϱ 3 m 11 v y a τ v ^ y a τ d τ
Theorem 3.
The estimation errors are globally uniform asymptotic bounded and will approach zero very closely in a finite time, using the auxiliary variables dynamics in (45) and the finite-time generalized observer (FGO) designed in (46).
Proof. 
For the surge axis, by introducing the notations as,
ε 3 = m 11 v s u v ^ s u ,     ε 4 = τ 1 τ ^ 1 + λ 3 sign ϱ 3 m 11 v s u v ^ s u
ε ˙ 3 = ε 4 λ 3 sign ϱ 3 ε 3 ε ˙ 4 = λ 4 sign ϱ 3 ε 3 + τ ˙ 1
The dynamics equation in (47) is similar as (15). Theorem 1 shows that the surge axis FGO estimation error is globally uniform asymptotic bounded and will get very close to zero in a finite time. This also applies to the heading axis because they have the same FGO structure.
τ s u = m 22 v s w v y a + d 11 v s u + m 11 u ˙ d m 11 k 2 sign ϱ 5 u ~ k 3 sgn u ~
s ψ ~ = r ~ + a ψ ~ + b ψ ~ p 1 q 1
Define the error of the surge subsystem as u ~ = v s u u d . The finite-time surge controller τ s u can be acquired with the estimation τ ^ 1 as (48), where operator s g n denotes the sign function, k 2 and k 3 are positive constants, k 3 is bigger than the finite-time converge region of surge axis FGO, ϱ 5 satisfies 0 < ϱ 5 < 1 . The yaw subsystem error is ψ ~ = ψ ψ d . The terminal sliding mode technique is used to get a finite-time controller, and the yaw subsystem surface is defined as (49), where β 1 and β 2 are positive constants, p 1 and q 1 are odd positive integers satisfying p 1 < q 1 , r ~ = v y a ψ ˙ d . Thus, the convergence time is obtained below if s ψ = 0 :
t t 0 + q 1 a q 1 p 1 ln a s ψ ~ t 0 q 1 p 1 q 1 + b b
τ y a = m 22 m 11 v s u v s w + m 33 ψ ¨ d k 5 sgn s ψ ~ m 33 a r ~ + b p 1 q 1 ψ ~ p 1 q 1 q 1 r ~ k 4 sign ϱ 6 s ψ ~ + d 33 v y a τ ^ 3
Then, the finite-time terminal SMC is given (50), where k 4 and k 5 are positive constants, k 5 is bigger than the finite-time converge region of the yaw axis, ϱ 6 satisfies 0 < ϱ 6 < 1 . □
Theorem 4.
The closed-loop system can be stabilized in a finite time by the surge and heading controller in (48) and (50), which use the estimates of  τ ^ 1  and  τ ^ 3 .
Proof. 
For the surge subsystem, the Lyapunov function is defined as L s u = u ~ 2 / 2 , and its time-derivative is obtained as,
L ˙ s u = u ~ m 22 m 11 v s w v y a d 11 m 11 v s u + τ s u m 11 + τ 1 m 11 u ˙ d k 2 sign 1 + ϱ 5 u ~ = k 2 L s u 1 + ϱ 5 2
L ˙ s ψ ~ = s ψ ~ m 11 m 22 m 33 v s u v s w d 33 m 33 v y a + τ y a m 33 + τ 3 m 33 ψ ¨ d + a r ~ + b p 1 q 1 ψ ~ p 1 q 1 q 1 r ~ k 4 sign 1 + ϱ 6 s ψ ~ = k 4 L s ψ ~ 1 + ϱ 6 2
Using the proof of convergence in a finite time for the system mentioned in paper [28], u ~ reaches zero in a finite time. For the heading subsystem, choosing a Lyapunov function as L s ψ ~ = s ψ ~ 2 / 2 , and its time-derivative is given by (52), which implies that the sliding surface s ψ ~ will approach zero in finite time. Therefore, based on the terminal sliding surface, ψ ~ converges to zero region can be achieved in finite time.

6. Numerical Simulation

The MSV is 76.2   m long and using five times that length as L in the parameter set. The GDL parameters are selected as λ 1 = 20 , λ 2 = 400 , ϱ 1 = 0.9 , ϱ 2 = 0.45 , k 1 = 0.5 . The control parameters are chosen as λ 3 = λ 5 = 10 , λ 4 = λ 6 = 25 , ϱ 3 = ϱ 4 = 0.9 , β 1 = 5 , β 2 = 0.5 , p 1 = 7 , q 1 = 9 , k 2 = 20 , k 3 = 0.2 , k 4 = 2.5 . The Pierson–Moskowitz spectrum [32] is used to get the standard wave spectrum, and H 1 / 3 = 3.8   m as the significant wave height; thus, the wave interference is achieved and shown in Figure 3.

6.1. Results in Path Planning

In Figure 1a, the AMSV must go through the following points in order: start [ 0 , 0 , 0 ° , 0 ] , point 1 [ 1000 , 1500 , 90 ° , 0 ] , point 2 [ 2500 , 2500 , 0 ° , 0 ] , point 3 [ 4000 , 1500 , 90 ° , 0 ] , and the end [ 5000 , 0 , 0 ° , 0 ] , all marked with the red circle. Applying the methodology of the spiral path generator described in Algorithm 1 to generate the planned path shown in the green line, and the blue arrow shows the waypoint direction for each point. The AMSV can start from the start point and reach all the target navigation points successfully.
The method proposed here places a strong emphasis on optimizing path curvature during both global and local planning, focusing on the continuity of curvature and orientation angles. This approach effectively mitigates issues such as excessive tracking errors and reduced stability that can arise from discontinuities in angles. As illustrated in Figure 4, the results of the orientation and curvature planning demonstrate how the path planning for multiple target points achieves continuity in the path. Each target point’s angle and curvature are distinctly presented, showcasing the effectiveness of this method in ensuring a smooth trajectory. In conclusion, this method can generate a path with a continuous tangential angle that meets the design index constraints.

6.2. Results in Path Following

The AMSV system estimates the disturbance caused by ocean waves and is denoted as d ^ , then compares it with the actual disturbance, denoted by d . The difference between them, denoted by d ~ . Details are demonstrated in Figure 5, d ~ is kept within a reasonable range, further illustrating that the proposed AMSV system’s estimation value matches the actual disturbance.
Figure 6 gives the estimation of sideslip angle and surge velocity. It shows that the initial time has a large error, almost 2 ° . As time goes on, the estimate becomes more precise, and it reaches the exact sideslip angle at 0.2   s . The designed ESO can achieve the estimation of the changing unknown sideslip angle and compensate it in the GDL. This makes the path following more accurate. Additionally, the system can also follow the real angular velocity in a fast and stable way, and keep the error value within a reasonable range.
For AMSV, the external disturbance caused by the waves is the environmental factor interference it has to face. It can be seen from Figure 5 and Figure 6 that the algorithm proposed in this paper can estimate the disturbances in the sideslip angle, yaw, and sway directions of the AMSV, and then eliminate them in the controller design stage. Since the error of the disturbance estimation will gradually converge, the controller can eventually reduce the tracking error to the set range within a limited time and achieve accurate path following.

6.3. Comparison Among Different Methods

The performance of the proposed method, adaptive LOS (ALOS), and integral LOS (ILOS) in path-following control are compared and shown in Figure 7. The path-following controller proposed here performs well under the condition of random wave interference and model uncertainty and obtains good control performance.
For performance comparison, the following path-following controllers are used [33]:
  • Parameters of the proposed controller in this article are given at the beginning of Section 6.
  • For ALOS, it is assumed that the sideslip angle is measurable, so there is no side slip angle estimation module. This paper uses the method shown in reference [34] to compare with the proposed controller.
  • For ILOS, an integral term is introduced to reduce the impact of the side slip angle, so there is no side slip angle estimation module. At the same time, it is an error-based adjustment method and cannot further improve the system tracking accuracy, which is very important for obstacle avoidance. This paper introduces the method shown in paper [7] and compares it with the proposed controller.
Figure 8 shows the details of the x e and y e . These three GDLs can make the nonlinear AMSV track the target with a large initial error ( y 30   m ) and reduce the errors in x e and y e . However, the ILOS-GDL method has excessive overshoots, which affects the control quality. The ALOS-GDL method has large oscillations during convergence. The proposed method outperforms both in terms of settling time and overshoot, as shown in Table 1. Table 2 indicates that the proposed method can improve the stability and accuracy of the AMSV in path following.
Compared with ALOS and ILOS, the control algorithm proposed in this paper has significant improvements in stabilization time and overshoot. The stabilization time is reduced by 6 times and 26 times compared with ALOS and the overshoot is reduced by 14 times and 26 times compared with ILOS. In terms of maximum error, both ALOS and ILOS exceed 4 m, while the method proposed in this paper controls the error within 0.5 m, which is improved by 8 times, greatly improving the safety performance in the autonomous driving process.

6.4. Robustness to Uncertainty

Choosing the MAV mass parameter to test how the control is affected by mass variation is shown in Figure 9. The vessel mass is changed into 5 6   m , and 7 6   m , separately from the original value.
From the analysis in Table 3, we can see that the uncertainty introduced by the mass change leads to a decrease in tracking accuracy. However, when the mass decreases by 1/6, the maximum error increases by 0.0935 m, and the average error increases by 0.0725 m; when the mass increases, the maximum error increases by 0.3521 m, and the average error increases by 0.0827 m. This shows that the disturbance caused by the mass decrease has a much greater impact on the controller than the disturbance caused by the mass increase. The maximum error is more than 3 times (from 0.0935 to 0.3521), while the average error is not much different (from 0.0725 to 0.0827). This shows that even if the mass change exceeds 15%, the tracking error is still stably controlled within 0.1 m, and the average error does not change significantly during the tracking process, ensuring safety during the operation. This shows that the controller can withstand the disturbance caused by the uncertainty of the internal parameters of the AMSV hull, thus confirming its robustness to disturbances.

6.5. Obstacle Avoidance

In Figure 10, the black line is the reference path, the blue line is the obstacle (crossing the reference line), and the green line is the real-time obstacle avoidance path based on global path planning. The green line deviates from the reference path and maintains a safe distance from the obstacle. The brown and yellow lines represent ALOS and ILOS, respectively. During the tracking process, ILOS is far from the green line and very close to the obstacle, reducing driving safety. ALOS is farther from the reference line but also vibrates more than the method proposed in this paper. Since the green line is the optimal path, more vibration means more deviation and longer convergence time. This also wastes more energy and lowers the safety of autonomous driving. Furthermore, ALOS and ILOS may encounter turbulence when they follow a new planned path after meeting an obstacle in the 70 s , which affects their driving safety and control stability, as shown in y e and x e .
Based on the electronic navigational chart (ENC) data, several common navigation scenarios of the ocean environment map have been built in MATLAB 2022, such as coast, island, and reef. In these maps, the white is the navigable area of the ship, the black is the non-navigable area.
Results are given in Figure 11, where the green line is the planned path, the arrow shows the direction of the AMSV, and the red line segment is the actual track. As can be seen from Figure 10, in the actual driving process, The AMSV controlled by our method can accurately track the planned path, control the hull to turn in advance when encountering obstacles, return to the initial planned path immediately after avoiding obstacles, and then approach the original planned path on the premise of safe driving, which conforms to the continuous navigation between multiple points proposed in this paper.

7. Conclusions

This paper studies the multi-target path following task for the AMSV, which faces the challenges of unknown sideslip angle and system uncertainties. The models of the path-following task is proposed, and then a closed-loop structure is developed with three components: a multi-objective path planning algorithm with obstacle avoidance, a finite-time LOS-GDL, and a robust finite-time dynamics controller. The path planning algorithm produces a smooth, continuous path that sequentially passes through all the waypoints. The paper also presents an obstacle avoidance planning algorithm that ensures safety during driving. A finite-time ESO estimates the unknown sideslip angle online and feeds it to the nonlinear feedback LOS guidance, which converges in finite time. A finite-time surge and heading controller is used to make the nonlinear AMSV track the target quickly and accurately. The simulation results demonstrate that the path planning algorithm generates a satisfactory path that meets all the requirements and has less overshoot. The LOS-GDL converges faster, and the controller allows the autopilot system to track the velocity and course angle well. The obstacle avoidance path planning method can create a smooth and energy-efficient obstacle avoidance path based on the reference trajectory in less than 0.1 s, meeting the real-time requirements. The control algorithm proposed in this paper reduces the stabilization time by 6 times compared with ALOS and ILOS and reduces the overshoot by 14 times compared with ALOS and 26 times compared with ILOS. In terms of the maximum error, both ALOS and ILOS exceed 4 m, while the one proposed in this paper is stable within 0.5 m, which is 8 times different, greatly improving the safety performance during autonomous driving. This work comprehensively investigates the multi-target path following task for AMSV. The proposed methods and algorithms show their effectiveness through simulation results, providing improved path planning, guidance, and control capabilities for enhanced marine surface vessel navigation performance.
The main plans for future work are as follows:
(1). Using network learning methods such as deep reinforcement learning, we provide basic data sets and safety assurance.
(2). Deploy autonomous driving systems on multiple MSVs to achieve collaborative driving, thereby saving energy and improving traffic efficiency.
(3). Optimize the solution method to ensure that the calculation time is not limited by the number of target points, to achieve real-time operation.

Author Contributions

Conceptualization, methodology, J.S.; Validation, resources, data curation, B.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Sun, X.; Wang, G.; Fan, Y. Model Identification and Trajectory Tracking Control for Vector Propulsion Unmanned Surface Vehicles. Electronics 2020, 9, 22. [Google Scholar] [CrossRef]
  2. Dubins, L.E. On Curves of Minimal Length with a Constraint on Average Curvature, and with Prescribed Initial and Terminal Positions and Tangents. Am. J. Math. 1957, 79, 497–516. [Google Scholar] [CrossRef]
  3. Lekkas, A.M.; Fossen, T.I. Integral LOS Path Following for Curved Paths Based on a Monotone Cubic Hermite Spline Parametrization. IEEE Trans. Control Syst. Technol. 2014, 22, 2287–2301. [Google Scholar] [CrossRef]
  4. Peng, Z.; Wang, C.; Yin, Y.; Wang, J. Safety-Certified Constrained Control of Maritime Autonomous Surface Ships for Automatic Berthing. IEEE Trans. Veh. Technol. 2023, 72, 8541–8552. [Google Scholar] [CrossRef]
  5. Healey, A.J.; Lienard, D. Multivariable sliding mode control for autonomous diving and steering of unmanned underwater vehicles. IEEE J. Ocean. Eng. 1993, 18, 327–339. [Google Scholar] [CrossRef]
  6. Gu, N.; Wang, D.; Peng, Z.; Wang, J.; Han, Q.L. Advances in Line-of-Sight Guidance for Path Following of Autonomous Marine Vehicles: An Overview. IEEE Trans. Syst. Man Cybern. Syst. 2023, 53, 12–28. [Google Scholar] [CrossRef]
  7. Caharija, W.; Pettersen, K.Y.; Bibuli, M.; Calado, P.; Zereik, E.; Braga, J.; Gravdahl, J.T.; Sorensen, A.J.; Milovanovic, 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]
  8. Han, J. From PID to Active Disturbance Rejection Control. IEEE Trans. Ind. Electron. 2009, 56, 900–906. [Google Scholar] [CrossRef]
  9. Han, Y.; Li, J.; Wang, B. Event-Triggered Active Disturbance Rejection Control for Hybrid Energy Storage System in Electric Vehicle. IEEE Trans. Transp. Electrif. 2023, 9, 75–86. [Google Scholar] [CrossRef]
  10. Gao, S.; He, B.; Zhang, X.; Wan, J.; Mu, X.; Yun, T. Cruise Speed Estimation Strategy Based on Multiple Fuzzy Logic and Extended State Observer for Low-Cost AUV. IEEE Trans. Instrum. Meas. 2021, 70, 1–13. [Google Scholar] [CrossRef]
  11. Liu, L.; Wang, D.; Peng, Z. ESO-Based Line-of-Sight Guidance Law for Path Following of Underactuated Marine Surface Vehicles With Exact Sideslip Compensation. IEEE J. Ocean. Eng. 2017, 42, 477–487. [Google Scholar] [CrossRef]
  12. Li, J.; Sun, J.; Chen, G. A Multi-Switching Tracking Control Scheme for Autonomous Mobile Robot in Unknown Obstacle Environments. Electronics 2020, 9, 42. [Google Scholar] [CrossRef]
  13. Kim, J.; Lee, C.; Chung, D.; Kim, J. Navigable Area Detection and Perception-Guided Model Predictive Control for Autonomous Navigation in Narrow Waterways. IEEE Robot. Autom. Lett. 2023, 8, 5456–5463. [Google Scholar] [CrossRef]
  14. Guan, W.; Wang, K. Autonomous Collision Avoidance of Unmanned Surface Vehicles Based on Improved A-Star and Dynamic Window Approach Algorithms. IEEE Intell. Transp. Syst. Mag. 2023, 15, 36–50. [Google Scholar] [CrossRef]
  15. Yao, P.; Zhao, R.; Zhu, Q. A Hierarchical Architecture Using Biased Min-Consensus for USV Path Planning. IEEE Trans. Veh. Technol. 2020, 69, 9518–9527. [Google Scholar] [CrossRef]
  16. 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]
  17. Meng, J.; Humne, A.; Bucknall, R.; Englot, B.; Liu, Y. A Fully-Autonomous Framework of Unmanned Surface Vehicles in Maritime Environments Using Gaussian Process Motion Planning. IEEE J. Ocean. Eng. 2023, 48, 59–79. [Google Scholar] [CrossRef]
  18. Wang, N.; Zhang, Y.; Ahn, C.K.; Xu, Q. Autonomous Pilot of Unmanned Surface Vehicles: Bridging Path Planning and Tracking. IEEE Trans. Veh. Technol. 2022, 71, 2358–2374. [Google Scholar] [CrossRef]
  19. Yu, Y.; Guo, C.; Yu, H. Finite-Time PLOS-Based Integral Sliding-Mode Adaptive Neural Path Following for Unmanned Surface Vessels With Unknown Dynamics and Disturbances. IEEE Trans. Autom. Sci. Eng. 2019, 16, 1500–1511. [Google Scholar] [CrossRef]
  20. Rout, R.; Chi, R.; Yan, W. Sideslip-Compensated Guidance-Based Adaptive Neural Control of Marine Surface Vessels. IEEE Trans. Cybern. 2022, 52, 2860–2871. [Google Scholar] [CrossRef]
  21. Piao, Z.; Guo, C.; Sun, S. Adaptive Backstepping Sliding Mode Dynamic Positioning System for Pod Driven Unmanned Surface Vessel Based on Cerebellar Model Articulation Controller. IEEE Access 2020, 8, 48314–48324. [Google Scholar] [CrossRef]
  22. Sun, Z.; Zhang, G.; Yi, B.; Zhang, W. Practical proportional integral sliding mode control for underactuated surface ships in the fields of marine practice. Ocean Eng. 2017, 142, 217–223. [Google Scholar] [CrossRef]
  23. Hao, L.; Zhang, H.; Yue, W.; Li, H. Fault-tolerant compensation control based on sliding mode technique of unmanned marine vehicles subject to unknown persistent ocean disturbances. Int. J. Control Autom. Syst. 2020, 18, 739–752. [Google Scholar] [CrossRef]
  24. Tabataba’i-Nasab, F.S.; Moosavian, S.A.A.; Khalaji, A.K. Tracking Control of an Autonomous Underwater Vehicle: Higher-Order Sliding Mode Control Approach. In Proceedings of the 2019 7th International Conference on Robotics and Mechatronics (ICRoM), Tehran, Iran, 20–21 November 2019. [Google Scholar]
  25. Guerrero, J.; Chemori, A.; Torres, J.; Creuze, V. Time-delay high-order sliding mode control for trajectory tracking of autonomous underwater vehicles under disturbances. Ocean Eng. 2023, 268, 113375. [Google Scholar] [CrossRef]
  26. Zwierzewicz, Z. Robust and Adaptive Path-Following Control of an Underactuated Ship. IEEE Access 2020, 8, 120198–120207. [Google Scholar] [CrossRef]
  27. Zhu, Y.; Li, Y.; Zeng, K.; Huang, L.; Huang, G.; Hua, W.; Wang, Y.; Gao, X. Finite-Time Cooperative Control for Vehicle Platoon With Sliding-Mode Controller and Disturbance Observer. IEEE Trans. Intell. Transp. Syst. 2022, 71, 7186–7201. [Google Scholar] [CrossRef]
  28. Bhat, S.P.; Bernstein, D.S. Finite-time stability of continuous autonomous systems. SIAM J. Control Optim. 2020, 38, 751–766. [Google Scholar] [CrossRef]
  29. Yang, C.W.J.; Guo, L.; Li, S. Disturbance-observer-based control and related methods-an overview. IEEE Trans. Ind. Electron. 2016, 63, 1083–1095. [Google Scholar]
  30. Wang, L.; Xu, C.; Cheng, J. Robust Output Path-Following Control of Marine Surface Vessels with Finite-Time LOS Guidance. J. Mar. Sci. Eng. 2020, 8, 275. [Google Scholar] [CrossRef]
  31. Stellato, B.; Banjac, G.; Goulart, P.; Bemporad, A.; Boyd, S. OSQP: An operator splitting solver for quadratic programs. Math. Program. Comput. 2020, 12, 637–672. [Google Scholar] [CrossRef]
  32. Fossen, T.I. Guidance and Control of Ocean Vehicles; Wiley: New York, NY, USA, 1994. [Google Scholar]
  33. Viadero-Monasterio, F.; Nguyen, A.T.; Lauber, J.; Boada, M.J.L.; Boada, B.L. Event-Triggered Robust Path Tracking Control Considering Roll Stability Under Network-Induced Delays for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2023, 24, 14743–14756. [Google Scholar] [CrossRef]
  34. Liu, F.; Shen, Y.; He, B.; Wang, D.; Wan, J.; Sha, Q.; Qin, P. Drift angle compensation-based adaptive line-of-sight path following for autonomous underwater vehicle. Appl. Ocean Res. 2016, 93, 799–808. [Google Scholar] [CrossRef]
Figure 1. The framework of the whole ASMV system, (a) global path planner (b) local path planner (c) LOS guidance geometry (d) finite-time LOS guidance (e) robust controller.
Figure 1. The framework of the whole ASMV system, (a) global path planner (b) local path planner (c) LOS guidance geometry (d) finite-time LOS guidance (e) robust controller.
Electronics 14 00896 g001
Figure 2. Structure of the proposed methodology.
Figure 2. Structure of the proposed methodology.
Electronics 14 00896 g002
Figure 3. The demonstration of the wave interference.
Figure 3. The demonstration of the wave interference.
Electronics 14 00896 g003
Figure 4. The change curve of the reference path (a) Tangent path angle (b) curvature.
Figure 4. The change curve of the reference path (a) Tangent path angle (b) curvature.
Electronics 14 00896 g004
Figure 5. The external disturbance.
Figure 5. The external disturbance.
Electronics 14 00896 g005
Figure 6. The vessel motion estimation.
Figure 6. The vessel motion estimation.
Electronics 14 00896 g006
Figure 7. Comparison results of the path-following control.
Figure 7. Comparison results of the path-following control.
Electronics 14 00896 g007
Figure 8. Control performance.
Figure 8. Control performance.
Electronics 14 00896 g008
Figure 9. The control performance with vessel mass variation.
Figure 9. The control performance with vessel mass variation.
Electronics 14 00896 g009
Figure 10. Control results of the obstacle avoidance.
Figure 10. Control results of the obstacle avoidance.
Electronics 14 00896 g010
Figure 11. Testing ocean maps of common navigation scenarios: (a) coast (b) island (c) reef.
Figure 11. Testing ocean maps of common navigation scenarios: (a) coast (b) island (c) reef.
Electronics 14 00896 g011
Table 1. Comparison results in the transient state.
Table 1. Comparison results in the transient state.
Settling Time (s)Overshot
ALOS38115.8%
ILOS30429.2%
Proposed method45.171.12%
Table 2. Comparison results in a steady state.
Table 2. Comparison results in a steady state.
Maximum ErrorRMS
y e ( m ) ALOS4.76840.6520
ILOS8.75221.2627
Proposed method0.33910.0151
x e ( m ) ALOS0.25870.0266
ILOS0.42670.0440
Proposed method0.11760.0047
Table 3. The maximum and average values of the c t e resulting from changes in quality.
Table 3. The maximum and average values of the c t e resulting from changes in quality.
MassThe Absolute Value of the Maximum ErrorRMS
c t e   ( m ) 5 6   m 0.43260.0876
m 0.33910.0151
7 6   m 0.69120.0978
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

Han, B.; Sun, J. Finite Time ESO-Based Line-of-Sight Following Method with Multi-Objective Path Planning Applied on an Autonomous Marine Surface Vehicle. Electronics 2025, 14, 896. https://doi.org/10.3390/electronics14050896

AMA Style

Han B, Sun J. Finite Time ESO-Based Line-of-Sight Following Method with Multi-Objective Path Planning Applied on an Autonomous Marine Surface Vehicle. Electronics. 2025; 14(5):896. https://doi.org/10.3390/electronics14050896

Chicago/Turabian Style

Han, Bingheng, and Jinhong Sun. 2025. "Finite Time ESO-Based Line-of-Sight Following Method with Multi-Objective Path Planning Applied on an Autonomous Marine Surface Vehicle" Electronics 14, no. 5: 896. https://doi.org/10.3390/electronics14050896

APA Style

Han, B., & Sun, J. (2025). Finite Time ESO-Based Line-of-Sight Following Method with Multi-Objective Path Planning Applied on an Autonomous Marine Surface Vehicle. Electronics, 14(5), 896. https://doi.org/10.3390/electronics14050896

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