Content area

Abstract

A new type of path-following method has been developed to steer marine surface vehicles along desired paths. Path-following is achieved by a new hyperbolic guidance law for straight-line paths and a backstepping control law for curved paths. An optimal controller has been improved for heading control, based on linear quadratic regulator (LQR) theory with nonlinear feedback control techniques. The control algorithm performance is validated by simulation and comparison against the requirements of International Standard IEC62065. Deviations are within the allowable range of the standard. In addition, the experimental results show that the proposed method has higher control accuracy.

Full text

Turn on search term navigation

1. Introduction

Autopilot is the main equipment for ship motion control; it controls the ship’s course without the participation of the helmsman [1]. On autopilot, the ship follows the target route automatically, which can effectively reduce ship operating costs [2]. This paper presents a new method for ship track control. The goal of the control system is to follow a preset route with good anti-interference ability [3]. Path-following control systems for marine vehicles are usually constructed as three independent blocks: guidance, navigation and control [4]. Guidance is the action or the system that continuously computes the reference position, velocity and acceleration of the vehicle to be used by the control system [5]. Navigation is the action or the system that directs the vehicle, by which the position, course and traveled distance is determined. The control system determines the necessary forces and moments to achieve a certain objective.

Line of sight (LOS) is the most commonly used guidance algorithm. This algorithm was first applied to track control of surface ships by Mcgookin and Fossen and has been widely studied [6,7,8,9]. The advantage of the LOS guidance algorithm is that it controls the ship’s motion by imitating the behavior of the helmsman to eliminate track deviation from the planned route. However, there are some defects in the LOS guidance algorithm. When the distance between the next target waypoint on the target route and the current position of the ship is large, a large track deviation will be produced when the ship tracks the planned route through the guidance algorithm, in addition, the convergence speed of the algorithm is also very slow. In response to this problem, an integral LOS (ILOS) has been proposed and extensively analyzed. Fossen and Lekkas [10] proposed an ILOS based on adaptive control theory that can compensate for drift forces effectively.

Stability analysis is an important topic for navigation and control systems used in autonomous marine vehicles. Proportional-integral-derivative (PID) controllers or proportional derivative controllers are usually used in ship autopilot design [11,12]. In recent years, improved PID control algorithms have emerged. For example, steering parameters for normal adaptable PID autopilots have been developed during the last decade [13,14]. Dlabac et al. [15] presented a particle swarm optimization (PSO)-based PID controller for ship course-keeping. Recently, nonlinear controllers for autopilot motion control of marine vessels have been reported. Oh and Sun [16] presented a model predictive control for path following of underactuated surface vessels. Guerrero et al. [17] employed an adaptive high- order sliding mode controller for trajectory tracking of autonomous underwater vehicles. Designs based on neural networks [18,19], pole placement technique (PPT) [20], fuzzy logic [21], extended state observer technique (ESO) [22] and some other methods are also used. Wang et al. [23] presented a heading control algorithm based on an H-infinite optimization algorithm to counteract the influence of waves and ensure that ships can turn steadily in rough seas. Sun et al. [24] proposed a feedback linearization optimal heading control algorithm to effectively control a ship’s course. Veremey et al. [25] proposed a new approach for the compensative transformation of reference dynamic output controllers. Du et al. [26,27] used adaptive robust nonlinear control to adjust a ship’s course and track. Xiang et al. [28] improved the fuzzy logic method and tested it on underwater ships and marine surface vehicles. Xu et al. [29] proposed a vector field guidance law to follow the ship’s trajectory. Although most of these methods have good results, there is no standard to verify the control effect of their experiments and the ship model they use is no comprehensive consideration for each type of ship, which cannot effectively verify the results. Liu et al. [30] proposed a nonlinear robust control algorithm based on Backstepping method to control ship straight-path tracking. However, there is no curve path tracking method in this study. Zhao et al. [31] based on Serret-Frenet frame transformation develop a tracking error model and the backstepping controller compensates the nonlinearity of the container ship. Xu et al. [32] proposed an adaptive backstepping controller for path-following control of an underactuated ship based on a nonlinear steering model, which can achieve the effect of path control. But the shortcoming in both two is, they present pretty few control scenarios of the researches to verify the reliability of the algorithm, moreover, the scene of track control is too simple.

This paper presents a new path-following control law. The main innovation of this paper is to propose hyperbolic guidance law and apply it to straight-line path-following control. This design improves the convergence of the straight-line path-following control. For curved path-following in the transition between two adjacent straight-line paths, this paper improved a reverse stepping method to calculate heading rate commands to make the system globally asymptotically stable. Compared with the previous research, the extended state observer (ESO) for the controller model is established to estimate and compensate the state in this paper, which can improve the anti-interference ability of the ship in the path following. In the presence of sea current interference, also gives a correction formula. In this paper, linear quadratic regulator (LQR) and nonlinear feedback control are combined to improve the traditional LQR heading controller to improve the control accuracy of heading and yaw rate of the ship. Finally, the track control effect of three different types of ships is verified in simulations and the control effect is evaluated according to International Standard IEC62065 [33].

Section 2 establishes a mathematical model, including ship motion simulation and control and identifies controller parameters. Section 3 describes the design of the heading controller. Section 4 introduces the new guidance algorithm. Section 5 presents analysis of simulation results. Finally, Section 6 contains the conclusions.

2. Mathematical Model of Ship Motion 2.1. Process Plant Model

We describe the ship motion model in five basic compositions, with three degrees of freedom, shown in Figure 1. The model is derived from Newton’s laws of motion using linear equations to relate hydrodynamic forces to the respective motions in the horizontal plane. The equations are as follows [4]:

m[u˙−vr−xg r2ygr˙]=X,

m[v˙+ur−yg r2+xgr˙]=Y,

Izr˙+m[xg(v˙+ur)−yg(u˙−vr)]=N,

whereX,YandNdenote external forces and moment, while(xg,yg,zg)describe the location of the center of gravity.u,vandrdenote surge velocity, sway velocity and yaw angular velocity, respectively,u˙,v˙andr˙are their derivatives.Izis the yaw moment of inertia,mis the total mass of ship. It is common to let the body frame coordinate origin coincide with the center of gravity; thus, the equations can be rewritten as:

m(u˙−vr)=X,

m(v˙+ur)=Y,

Izr˙=N.

The hydrodynamic forceXis linearized and is assumed to be proportional to the ship linear velocity,uin surge. LetRudenote the linear coefficient of hydrodynamic resistance to forward motion andXthrustdenote the thrust provided by the propeller. Thus Equation (4) becomes:

m(u˙−vr)=XthrustRuu.

Letτudenote the time constant of the linear surge response model,Kudenote the coefficient of thrust,umaxdenote maximum forward speed, andXmaxdenote maximum thrust:

τu=m/Ru,umax=Xmax/Ru,Ku=umax/τu.

Substituting Equation (8) into Equation (7) yields:

u˙=Ku X′+vr−u/τu.

In the same way, for sway response model letτv=m/Rvdenote the linear coefficient of hydrodynamic resistance to sway motion, then Equation (5) becomes:

v˙=−ur−v/τv.

For the yaw response model, Equation (6) becomes:

Izr˙=Kr(δa Ku X′ τu/L+W)+γLRv(v−γLr)−Rrr,

whereKris a constant of proportionality,γis the yaw stability factor,Lis the length of the ship,δais the real rudder deflection,Rvis the linear coefficient of hydrodynamic resistance to lateral motion,Rris the linear coefficient of hydrodynamic resistance to yaw andτr=Iz/Rrdenotes the time constant of the yaw response model. Simplifying by relating the moment of inertia to the mass and length as a uniformly dense rod to its mass and length, then the moment of inertia can be obtained asIz=mL2/12.KrWis the turning moment imparted by wave disturbance, K′ris the normalized coefficient of rudder moment, which can be expressed as K′r=Kr δmax/Iz.

The wave interference model established in this paper consists of a series of square half wave waves. The durationTand heightH of each half wave are random numbers related to the Bretschneider wave spectrum [34]. Finally, a square wave interference signal is generated by the wave model, in which the calculation methods of the durationTand the wave heightHare as follows:

{T=0.5T0(ss)×(1+0.5Randb)H=H0(ss)×(1+Hr×RandbAa,

whereRandbdenotes a random number among [−1, 1]. A value of 0.5 forHris recommended, whileAahas alternating sign (i.e., ±1) to describe wave direction,ssmeans the sea state level,T0(ss)andH0(ss)are the natural period and significant wave height under sea statess , respectively. The range of values is shown in Table 1.

Referring to the modeling method of wave interference in IEC62065, this paper ignores the influence of wave interference on ship surge motion and sway motion, only adds the wave interference torque of ship’s yaw motion to the mathematical model of ship’s motion. Rewrite ship yaw Equation (11) as:

r˙= K′rKu X′ τuL⋅δa +12γ(v−γLr)τrLτv−rτr+0.01 K′r SfH,

whereδa is the normalized rudder position obtained by δ′a=δa/δamax,Sfis a Scaling Factor. A value of 20 for the Scaling Factor is recommended.

2.2. Control Plant Model

We simplify the process plant model described in the previous section to design the autopilot control algorithm. The simplified model contains only the main physical properties of the process. Notomo [35] proposed a linearized model for ship steering equations, which is given by a simple transfer function betweenrandδ.

rδ(s)=K(1+Ts),

whereTandKare the time constant and gain constant, respectively. Neglecting the roll and pitch modes (ϕ=θ=0), such that:

ψ˙=r

finally yields:

ψδ(s)=Ks(1+Ts),

whereψis the heading angle.

The time domain form of Equation (16) is:

Tψ¨+ψ˙=Kδ.

Notomo’s first order model is usually written as:

Tr˙+r=Kδ.

When the straight motion of the ship is unstable or critical stable, nonlinear maneuvering models should be used. A nonlinear term can be added in Equation (18); thus, Notomo’s nonlinear first order model can be obtained as:

Tr˙+r=K(δ+Kvv).

This is the commonly used control plant model for the design of the steering autopilot, in whichKvis the coefficient of the nonlinear term.

2.3. Controller Parameter Identification In the above-mentioned control model, some parameters cannot be obtained directly but need to be obtained by system parameter identification. In control applications, the controller performance is bound to the assumptions and approximations of the model. To obtain the corresponding controller parameters more accurately, we apply the forgetting factor least square algorithm to Notomo’s nonlinear first order model to identify the ship motion model.

The Recursive Least Square (RLS) algorithm with exponential forgetting is given as follows [36]:

θ^(k)=θ^(k−1)+Q(k)[y(k)−ΦΤ(k)θ^(k−1)],

Q(k)=P(k−1)Φ(k)[λI+ΦΤ(k)P(k−1)Φ(k)]−1,

P(k)=1λ[I−Q(k)ΦΤ(k)]P(k−1),

where the forgetting factor value ofλis0.98<λ<0.995,Φ(k)is the data vector andθ^(k)is the estimated value of the parameter vector.Q(k)andP(k)are the intermediate variable help us getθ^(k)we want.

Next, referring to the ship motion simulation model, substituting control Equation (19) into ship motion Equation (13), the values ofT,KandKvare obtained as follows:

{T=τv τrτv+12τr γ2,K=TKr umax X′LδmaxKv=12γTKLτv.,

To facilitate the identification calculation, Equations (11) and (13) are rewritten in the following form:

{Y0=θ0 X0+θ1 X1Y1=θ2 X2

where

{Y0=r˙−12γLτvvw+12γ2τvrY1=v˙g+ugr,

{X0=UL δ′aX1=rX2=vw,

{θ0=KLTUθ1=−1T+12γ2τvθ2=−1τv.

According to the recursive formula of the forgetting factor least squares identification algorithm in Equations (20)–(22), the corresponding identification resultsθ0,θ1andθ2can be obtained. Throughθ0,θ1andθ2, the three controller parametersT^,K^andK^vof the nonlinear first-order Notomo model can be solved:

{T^=1−θ^1+12γ2τv,K^=θ^0T^UL,K^v=12γT^LK^τv.

3. Optimal Heading Controller This section describes the design of the optimal heading controller. The main goal is to calculate the controller parameters in terms of the Notomo constants obtained by the identification algorithm in the previous section and introduce them in the LQR controller law. Then, nonlinear feedback is added to improve LQR controller to achieve nonlinear control and better control accuracy. In addition, to filter out the influence of sea wave interference on the acquisition of ship heading signal, an extended state observer (ESO) is added to this design to obtain the estimated value of the low-frequency heading signal. Thus, the controller can obtain accurate and fast course control. 3.1. LQR Controller

Assume that the heading signalψcan be obtained by a compass and the yaw ratercan be obtained by a rate gyro or by a state observer. Notomo’s first order model in Equation (18) can be written as the state space form:

X˙=AX+Buc,

whereX=(r,ψ,δ)Tis the state vector anducis the controller input, which denotes the desired rudder rate.AandBare the coefficient matrixes with:

A=(−1/T0K/T100000),

B=(001)T,

Xd=(rd,ψd,δ)Tdenotes the objective state vector. The goal of the controller design is to converge the stateXto the objectiveXd:

limt→∞X=Xd,

X˜denotes the error vector:

X˜=X−Xd=(r˜ψ˜δ)T,

wherer˜=r−rd,ψ˜=ψ−ψd. The control performance specification can be measured in terms of:

J=∫0∞(X˜TQX+uc TRuc)dt,

whereQis a 3-dimensional diagonal matrix, in which diagonal elements are the weighting factors.Ris the weighting factor of the input. The LQR problem is to find the optimal controluc(t)such thatJin Equation (34) is minimized,

uc=−R−1 BTPX˜,

whereP is the positive defined solution of the Riccati Equation [37]:

ATP+PA−PBR−1 BTP+Q=0

Let

(k1,k2,k3)T=−R−1 BTP,

wherek1,k2andk3are the controller gains obtained by the LQR law. Thus, the representation of the controller can be written as:

δLQR=∫0t(k1r˜+k2ψ˜+k3δ)dτ.

3.2. Feedback Nonlinearization Compensation

In the controller design here, a nonlinear feedback term is added in the control law for compensating the nonlinear maneuvering of the ship. Notomo’s nonlinear first order model can be rewritten as:

Tr˙+r=K(δ+Kvv).

Comparing with the linear controller law obtained in the previous section, the following equation can be obtained:

δLQR=δcom+Kvv,

whereδcomis the command rudder angle,Kvvcan be treated as the feedback term, such that:

δcom=δLQRδFL,

withδFL=Kvvand the value ofKvis obtained from the identification algorithm in the previous section.

3.3. Extended State Observer

Both surface ships and underwater vehicles need state observers to process signal data from sensors and navigation equipment. The observer in this paper is designed in terms of the nonlinear ship model and the wave disturbance model. The nonlinear ship model and the wave disturbance model are as follows:

{Tr˙+r=K(δ−δn+Kvv)+ωrψ¨ω+2ςω0 ψ˙ω+ω02 ψω=ωω

whereδnis the rudder offset,ωrandωωare the zero-mean Gaussian measurement white noise;ψωrepresents the first-order wave-induced motion, andςis the relative damping ratio, conventionally assigned a value of 0.075.ω0is the wave frequency.

Based on Equation (42), the state space equation of the extended state observer is:

X^˙=AX^+BΓ+G(Y−CX^),

whereX^denotes the estimation of the state,X^=(δ^n,r^,ψ,ξ^ω,ψ^ω)Tandξ^˙ω=ψ^ω.Γis the input of the model andΓ=δ+Kvv;Gis the gain matrix;δ^nis the estimation of the rudder offset;Yis the heading signal obtained by the compass withY=ψ+ψω.A,BandCare the coefficient matrixes with:

A=(00000−KT−1T00001000000−ω02−2ςω0),

B=(0KT000),

C=(00101).

The error of the state vector can be denoted asE=X^−X, of which the differential equation is:

E˙=(A−GC)E.

To keep the asymptotic stability of the error vector, the solution of Equation (47) should beE(t)=E0 e−kt, whereE0is the initial error value andkis a scale factor. Thus, all of the eigenvalues of the matrix(A−GC)have negative real parts. The gain matrixGcan be found by pole placement in terms of the eigenvalues. In this case, the eigenvector of the matrix(A−GC)is chosen as:P=(P0,P1,P2,P3,P4)=(1.5/T,1.5/T,1.5/T,15ςω0,15ςω0)and the gain matrix can be obtained by using the MATLAB function.

4. Guidance Law

Systems for guidance consist of a waypoint generator with human interface. A new hyperbolic guidance method for straight-line path-following control is presented in this paper. A Lyapunov function analysis [38] is used to prove the stability of this method. For curve guidance, based on the Lyapunov stability function, this paper presents a reverse stepping method to calculate heading rate command and make the system globally asymptotically stable, with a correction formula for current interference.

4.1. Error Coordinates

Consider a straight-line path implicitly defined by two waypointspk=(xk,yk)TR2andpk+1=(xk+1,yk+1)TR2, respectively. Also, consider the position of the ship denoted by the pointpt=(xt,yt)TR2. Then the direction of the path can be defined as:

αk:=atan2(xk+1xk,yk+1yk).

Fossen [4] gives the formula to calculate the cross-track error:

P˜(t)=−[xtxk]cos(αk)+[ytyk]sin(αk).

The calculation of the cross-track error in the transition curved path between two adjacent straight-line paths is complicated. Figure 2 shows two adjacent straight-line paths described by the waypointspk,pk+1andpk+2.Rk+1is the radius of the transition curve and the cross-track error of the transition curved path can be obtained by:

First, determine the direction of the curved path (clockwise or counterclockwise). Based on Equation (48), the directionαkof the straight-line pathpk pk+1and the directionαk+1of the straight-line pathpk+1 pk+2can be calculated. Then the direction of the curved path is:

Fk+1=sign(sin(αk+1αk));

here,Fk+1denotes the direction of the curved path, a positive sign means clockwise and a negative sign means counterclockwise.

Second, determine the center point of the curved path. The angle between the two adjacent straight-line paths can be obtained in terms of the directionαk,αk+1andFk+1.

γk+1=π−Fk+1(αk+1αk).

Then the distance between the center point and the waypointpk+1can be determined in terms of the angleγk+1and the radiusRk+1.

Dk+1=Rk+1/sin(γk+12).

The angle between the vector from the center pointOk+1to the waypointpk+1and North can be obtained in terms of the angleγk+1, the directionFk+1andαk.

αOk+1=αkFk+1 γk+1.

Based on the waypointpk+1, the directionαOk+1and the distanceDk+1from the center pointOk+1to the waypointpk+1, the coordinatePOk+1=(xOk+1,yOk+1)of the center pointOk+1can be determined:

pOk+1=pk+1Rk+1(sinαOk+1cosαOk+1).

Finally, the cross-track error can be calculated by:

P˜(t)=Fk+1ptpOk+1‖−Rk+1.

The course angle command is the direction of the vector tangential to the point on the path that is closest to the vehicle. The course angle command can be calculated by:

χ˜(t)=χ(t)−atan2(x(t)−xOk+1,y(t)−yOk+1)+π2Fk+1;

here,χ(t)is the current course.

4.2. Straight-Line Path Guidance

The main goal of straight-line path-following control is to eliminate cross-track and heading errors. Hyperbolic guidance will achieve a more rapid convergence of path-following maneuvering because of its smoothing and transition properties. Thus, a hyperbolic guidance methodology is adopted with a hyperbolic tangent function. As shown in Figure 3, the curve OC denotes a hyperbola, of which the asymptote is the straight-line path. The hyperbola equation is:

y=Rcekcxe−kcxekcx+e−kcx,

whereRcdenotes the distance between the originOand the straight-line andP˜(t)is the distance from the ship to the planned route at timetwithRc>P˜(t).

Then, the position of the shipptcan be denoted by(x0,Rc−P˜(t))and the angleζ shown in Figure 3 can be calculated by:

ζ(t)=sign(P˜(t))arctan[kc(2|P˜(t)|−P˜(t)2Rc)],

wherekcis a constant coefficient withkc>0, denoting the rate of approach to the straight-line path.

Then the course command can be obtained by:

χc=αk+ζ(t)=αk+sign(P˜(t))arctan[kc(2|P˜(t)|−P˜(t)2Rc)],

whereχcis the command course andαkis initial heading angle.

4.3. Curved Path Guidance

For curved path following, a kinematic controller generates the desired states for motion control. The control method can be designed using a dynamic model of the ship by specifying a reference frame that moves along the path. A Serret-Frenet reference frame [39] is usually chosen. Figure 4 shows an inertia reference frame{i}=(xi,yi,zi), a body-fixed reference frame{s}=(xs,ys,zs)and a Serret-Frenet frame{m}=(xm,ym,zm). The originOmof{m}is attached to the point on the path that is closest to the vehicle. R denotes the radius of the curved path.

The notationHa/bcis adopted in this paper, where{a},{b}and{c}denote the three different frames andHdenotes the coordinate of{a}in frame{b}relative to{c}. Such that:

rm/ii+rs/mi=rs/ii,

whererdenotes the distance vector.

Time differentiation of Equation (60) yields:

vm/ii+ddtrs/mi=vs/ii,

wherevdenotes the speed vector. Andddtrs/mican be obtained by:

ddtrs/mi=Rmi ωm/ii×rs/mm+Rmi vs/mm,

whereRmidenotes the transformation matrix from{m}to{i}andωm/ii=(0,0,−α˙)Tdenotes the rotation vector between the{m}and{i}frames.

Substituting Equation (62) into Equation (61) and multiplying byRmion both sides of the equation, yields:

vm/im+ωm/ii×rs/mm+vs/mm=Rsm vs/is.

Then the kinematic equations can be obtained:

{P˜˙=−usinχ˜α˙=ucosχ˜R+FP˜,

whereP˜is the position deviation,χ˜is the course deviation,αis the planned course andFindicates the direction of the transition curve.F=1means turning clockwise,F=−1means turning counterclockwise.

Thus, goal of the curved path-following controller is to calculate the yaw rate commands, forcing the ship to approach the curved path. This paper presents a reverse stepping calculation method based on the Lyapunov function to obtain the yaw rate commands.

First, calculate the course commands. Consider the Lyapunov function candidate as follows:

V1=12P˜2.

Time differentiation of Equation (65) yields:

V˙1=−P˜usin(χ−α).

To satisfy global asymptotic stability (GAS), it is necessary to guarantee thatV1<0asP˜≠0andV˙1=0asP˜=0. Thus, the following equation is adopted:

V˙1=−k1 P˜2≤0,

wherek1is the scaling factor, withk1>0.

Based on Equation (65) and Equation (66), the course commands can be calculated by:

χc=α+arcsin(k1P˜u).

Equation (68) suggests that the course commandχcwill approach the path directionαto eliminate the course errorχ˜, as the cross-track error is decreasing. However, the path directionαis varying with ship motion during the curved path-following control. Thus, it is necessary to calculate the yaw rate commands. Consider the Lyapunov function candidate:

V2=12χ˜2,

withχ˜=χ−χc. Time differentiation of Equation (69) yields:

V˙2=(χ−χc)(χ˙−α˙−P˜˙(u/k1)2P˜2).

To satisfy GAS, it is necessary to guarantee thatV˙2<0asχ=χcandV˙2=0asχ=χc. Thus, the following equation is adopted:

V˙2=−k2 χ˜2,

wherek2is the scaling factor, withk2>0.

Based on Equations (64), (68), (70) and (71), the course commands can be calculated by:

χ˙c=ucosχ˜R+FP˜−−usinχ˜(u/k1)2P˜2k2χ˜,

whereχ˙cis the derivative ofχc, indicating the command track angular rate. We neglect the varying of the drift angleβ, thus the varying rate course command can be treated as the yaw rate command, approximately. However, this does not fit in the presence of wave disturbance. In the presence of sea current interference, the yaw rate commands need to be adjusted as:

rc=χ˙cugugufcos(φgφf),

wherercdenotes the yaw rate command,ugdenotes the ship speed over the ground, with directionφgandufis the current speed through water, with directionφf.

Figure 5 is the three-layer control structure of ship track control proposed in this paper.

The track control module calculates the current planned navigation section of the ship according to the current ship position information and environmental interference information and calculates the track deviation and heading deviation, then modifies the planned heading angle according to the deviation information, calculates the command heading angle and sends it to the heading control module. According to the current compass signal, rudder angle signal and yaw speed signal, the course control module calculates the course deviation after comparing with the command heading and calculates the command rudder angle through the course control algorithm. Finally, the rudder angle control layer drives the rudder to make the actual rudder angle consistent with the command rudder angle, so as to realize the track control of the ship.

Figure 6 shows the path-following control overall flow chart:

5. Simulation Results

International Standard IEC62065 is used to test the performance of the path-following control algorithm presented in this paper. Based on the standard, three classes of ship are adopted: class A fast ferry, class B container and class C tanker. See Table 2 for details.

The heading controller parameters are given in Table 3:

The ships’ initial states for the three test scenarios are as follows: Ship A:(u0, v0, r0, ψ0) = (15.4 m/s, 0 m/s, 0 rad/s, 0 deg); Ship B:(u0, v0, r0, ψ0) = (12.9 m/s, 0 m/s, 0 rad/s, 0 deg); Ship C:(u0, v0, r0, ψ0) = (5.1 m/s, 0 m/s, 0 rad/s, 65 deg);

In control applications, it is important to validate the controller experimentally, this paper takes ship class B as the simulation object and the ship parameters are shown in Table 2. The step steering signal is selected as the input signal and the rotation experiment is used as the experimental method of controller parameter identification. The trajectory is shown in Figure 7 and the simulation data is shown in Table 4.

It can be seen from the experimental results that the control model established in this paper meets the ship’s turning characteristics and the established model is reliable.

Secondly, the course control algorithms of the three types of ships in Table 2 are verified. For ship class A, the initial speed of the ship is 15.4m/s, the command thrust is 0.67, under sea state 3 and the command heading angle is 30 degrees. As for ship class B, the initial speed is 12.9 m/s, the command thrust is 0.8, under sea state 3 and the command heading angle is 30 degrees. For ship class C, the initial speed of the ship is 5.1m/s, the command thrust is 1, under sea state 3 and the command heading angle is 30 degrees. Figure 8, Figure 9 and Figure 10 shows that the improved LQR control algorithm in this paper is compared with the traditional LQR algorithm and the simulation experimental chart of course control is obtained. The simulation data is shown in Table 5.

Based on the above experimental results, the following conclusions can be drawn: the improved algorithm combining LQR with feedback nonlinearization control can achieve the function of ship course control, the overshoot, control accuracy and corresponding time are better than the traditional LQR control method. In addition, by adding a state observer can ensure that the ship can sail according to the expected instructions under sea state 3 without frequent steering.

There are three test scenarios used to evaluate performance of the path-following controller. Details of the scenarios are given in Table 6, Table 7 and Table 8.

Results of testing the three classes of ship are shown in Figure 11, Figure 12 and Figure 13. WPTs in the figure are waypoints.

From Figure 11, we can see that ship class A has a maximum cross-track error of 24.8 m and the maximum course error 11.3°, which satisfies the requirements set by IEC62065 of setting the course deviation limit to 25° and the cross-track deviation to 100 m. The experimental results show that this algorithm has the advantage of less steering time.

Results for ship class B are shown in Figure 12, with a maximum cross-track error of 22 m and maximum course error of 1.6°, which satisfies the requirements of setting the course deviation limit to 15° and the cross-track deviation to 60 m.

Results for ship class C are shown in Figure 13, where the experimental environment is under rough sea state 5, with maximum cross-track error of 27.24 m and maximum course error of 3.9°, which satisfies the requirements of setting the course deviation limit to 15° and the cross-track deviation to 100 m.

Tests of ship class B in the presence of wave disturbance and a simulated current of 5 kn are also performed. The results are shown in Figure 14.

As shown in Figure 14, in the presence of sea state 3 and a simulated current of 5 kn, 30°N and the other requirements for test are the same as those for ship class B listed earlier, the results for ship class B satisfy the IEC62065 requirements with maximum cross-track error of 30.1 m and maximum course error of 3.96°. The experimental result shows that the proposed algorithm has demonstrated good robustness.

To further verify the control effect of the proposed algorithm, additional comparative experiments have been done. For ship class B, the traditional and adaptive PID control algorithms were used for track control, as shown in Figure 15. The experimental results are also compared with traditional LQR controller and the improved LQR control algorithm with nonlinear feedback term proposed in this paper and the track deviations are shown in Figure 16. Specific data are in Table 9. It can be seen from the experimental results that the traditional LQR control method has better tracking effect in the tracking task of direct sail or low speed tracking simple curve. However, it is difficult to guarantee the tracking accuracy in tracking complex task path. The maximum deviation under traditional PID controller, adaptive PID controller, traditional LQR controller and improved LQR controller are as follows: 176.9 m, 48.51 m, 23.32m and 22 m. In terms of stability, the traditional LQR controller performs poorly. And for the improved LQR controller, the deviation is around 0 for more than 3000 s. The performance of the control method proposed in this paper is significantly better than that of the other three control methods.

6. Conclusions A new practical guidance and control algorithm for marine vehicles is introduced in this paper. The main innovation is the hyperbolic guidance law used in straight-line path-following control. For curved path-following in the transition between two adjacent straight-line paths, this paper improves the reverse stepping method for the controller to calculate heading rate command to make the system globally asymptotically stable, with a correction formula for sea current interference. Traditional LQR and feedback nonlinear control are combined to improve the accuracy of course control. Different types of ships are verified in this paper, simulation results based on the International Standard IEC62065 are included to demonstrate system performance. The algorithms satisfy the IEC62065 testing requirements. Three additional experiments verified that the control method has good robustness and good control effect.

View Image - Figure 1. Ship motion mathematical model.

Figure 1. Ship motion mathematical model.

View Image - Figure 2. The transition curved path.

Figure 2. The transition curved path.

View Image - Figure 3. The hyperbolic guidance law.

Figure 3. The hyperbolic guidance law.

View Image - Figure 4. Path-following: reference frame.

Figure 4. Path-following: reference frame.

View Image - Figure 5. Basic composition of track control system.

Figure 5. Basic composition of track control system.

View Image - Figure 6. Path-following control flow chart.

Figure 6. Path-following control flow chart.

View Image - Figure 7. Testing results for ship class B in rotation experiment.

Figure 7. Testing results for ship class B in rotation experiment.

View Image - Figure 8. Comparative experiment of course control for ship class A: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

Figure 8. Comparative experiment of course control for ship class A: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

View Image - Figure 9. Comparative experiment of course control for ship class B: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

Figure 9. Comparative experiment of course control for ship class B: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

View Image - Figure 10. Comparative experiment of course control for ship class C: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

Figure 10. Comparative experiment of course control for ship class C: (a) The course angle changes with time; (b) The actual rudder angle changes with time.

View Image - Figure 11. Testing results for ship class A: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

Figure 11. Testing results for ship class A: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

View Image - Figure 12. Testing results for ship class B: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

Figure 12. Testing results for ship class B: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

View Image - Figure 13. Testing results for ship class C: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

Figure 13. Testing results for ship class C: (a) Ship trajectory; (b) Observation index: rudder angle, track deviation and heading deviation.

View Image - Figure 14. Testing results for ship class B in the presence of disturbance: rudder angle, track deviation and heading deviation.

Figure 14. Testing results for ship class B in the presence of disturbance: rudder angle, track deviation and heading deviation.

View Image - Figure 15. Navigation route for ship class B under different control methods: (a) traditional proportional-integral-derivative (PID) control law; (b) adaptive PID control law.

Figure 15. Navigation route for ship class B under different control methods: (a) traditional proportional-integral-derivative (PID) control law; (b) adaptive PID control law.

View Image - Figure 16. Testing results for ship class B under different control methods.

Figure 16. Testing results for ship class B under different control methods.

Sea State (ss) T0 (ss) H0 (ss)
12.20.1
250.5
37.81.25
4112.5
5144
617.26
721.19
826.314

Parameter Notation Ship A Fast Ferry Ship B Container Ship C Tanker
Ship length(m)L60250350
Thrust lever ramp time(s)Tp203030
Rudder ramp time(s)123030
Rudder follow-up offset(%)δn000
Maximum speed(kn)umax302510
Rudder moment coefficient(deg/s/%)Kr0.0250.010.005
Surge response time constant(s)τu150600800
Sway response time constant (s)τv2436
Yaw response time constant (s)τr42346
Stability coefficientγ−0.0500

K^ T^ K^ v Q R k1 k2 k3
Ship A0.079811.13431.9899diag(100, 0.5, 1)53.02610.14140.2083
Ship B0.079410.87591.9863diag(100, 0.5, 1)52.99360.14140.2090
Ship C0.079410.89661.9913diag(100, 0.5, 1)52.99640.14140.2090

Data Name Experimental Data Actual Data Error
Rotation diameter (nm)0.3370.3360.001
Fixed length rotation speed (deg/min)71710
Steady surge speed (kn)12.912.90
Steady sway speed (kn)−1.03−1.030
Tactical cycle diameter (nm)0.6400.6400
Advance (nm)0.5550.5510.004
Departure (nm)0.3250.3230.002

Types of Ships Control Method Overshoot (°) Steady State Mean Deviation (°) Steady State Maximum Deviation (°) Response Time(s)
Ship class A Fast ferryTraditional LQR1.7000.6250.500253.3
Improved LQR2.6000.3650.200142.5
Ship class B ContainerTraditional LQR4.6000.3950.600215.1
Improved LQR0.1000.0750.100125.7
Ship class C TankerTraditional LQR0.9000.4500.900190.5
Improved LQR0.3000.2750.100459.6

Waypoint No. Latitude Longitude Track [deg] Distance [NM] Radius [NM] Estimated ROT [deg/min]
00100°01.000′ S000°01.000′ W000.02.000.2580
00200°01.000′ N000°01.000′ W090.02.000.2580
00300°01.000′ N000°01.000′ E315.01.410.10200
00400°02.000′ N000°00.000′ E225.01.410.20100
00500°01.000′ N000°01.000′ W135.02.830.6033
00600°01.000′ S000°01.000′ E270.02.000.20100
00700°01.000′ S000°01.000′ W045.02.830.2580
00800°01.000′ N000°01.000′ E180.02.000.4050
00900°01.000′ S000°01.000′ E

Waypoint No. Latitude Longitude Track [deg] Distance [NM] Radius [NM] Estimated ROT [deg/min]
00165°00.000′ N000°20.000′ W040.26.540.5040
00265°05.000′ N000°10.000′ W139.813.091.020
00364°55.000′ N000°10.000′ E040.26.552.010
00465°00.000′ N000°20.000′ E

Waypoint No. Latitude Longitude Track [deg] Distance [NM] Radius [NM] Estimated ROT [deg/min]
00100°03.000′ S179°57.000′ W000.06.001.0010
00200°03.000′ N179°57.000′ W270.06.001.0010
00300°03.000′ N179°57.000′ E045.04.240.5020
00400°06.000′ N180°00.000′ W135.04.241.0010
00500°03.000′ N179°57.000′ W225.08.491.507
00600°03.000′ S179°57.000′ E090.06.001.0010
00700°03.000′ S179°57.000′ W315.08.490.7513
00800°03.000′ N179°57.000′ E180.06.001.258
00900°03.000′ S179°57.000′ E

Parameters Overshoot (m) Peak Time (s) Rising Time (s) Setting Time (s)
Traditional PID176.9532, 13052431650
Adaptive PID48.515271351080
Traditional LQR23.3214061621097
Improved LQR22102494690

Author Contributions

Conceptualization, Z.Z. and H.W.; methodology, Z.Z.; software, Z.Z.; validation, Z.Z., H.W., Y.Z. (Yuhan Zhao) and G.Z.; formal analysis, Z.Z.; investigation, Z.Z.; resources, Z.Z.; data curation, Y.Z. (Yuhan Zhao) and G.Z.; writing-original draft preparation, Z.Z.; writing-review and editing, Z.Z.; visualization, Z.Z.; supervision, H.W. and Y.Z. (Yi Zhao); project administration, H.W. and Y.Z. (Yi Zhao); funding acquisition, H.W. All authors have read and agreed to the published version of the manuscript.

Funding

This study was funded by the Russian Foundation for Basic Research (RFBR) (No. 20-07-00531).

Institutional Review Board Statement

"Not applicable" for studies not involving humans or animals.

Informed Consent Statement

"Not applicable" for studies not involving humans.

Data Availability Statement

Data sharing not applicable. No new data were created or analyzed in this study. Data sharing is not applicable to this article.

Acknowledgments

The authors are grateful to the anonymous reviewers for their valuable comments and suggestions that helped improve the quality of this manuscript.

Conflicts of Interest

The authors declare no conflict of interest.

References

1. Breivik, M.; Fossen, T.I. Path following for marine surface vessels in Oceans. In Proceedings of the MTS/IEEE Techno-Ocean conference, Kobe, Japan, 9-12 November 2004; pp. 2282-2289.

2. Dong, Z.P.; Wan, L.; Li, Y.M.; Zhang, G.C. Trajectory tracking control of underactuated USV based on modified backstepping approach. Int. J. Nav. Archit. Ocean Eng. 2015, 7, 817-832.

3. Filipe, M.B.; Lucas, B.M. Robust path-following control for articulated heavy-duty vehicles. Control Eng. Pract. 2019, 85, 246-256.

4. Fossen, T.I. Guidance and Control of Ocean Vehicles, 1st ed.; Wiley: New York, NY, USA, 1994; pp. 55-122.

5. Breivik, M.; Fossen, T.I. Applying missile guidance concepts to motion control of marine craft. IFAC Proc. Vol. 2007, 40, 349-354.

6. Fossen, T.I.; Pettersen, K.Y.; Galeazzi, R. Line-of-sight path following for dubins paths with adaptive sideslip compensation of drift forces. Control Syst. Technol. IEEE 2015, 23, 820-827.

7. Kelasidi, E.; Liljeback, P.; Pettersen, K.Y.; Gravdahl, J.T. Integral line-of-sight guidance for path following control of underwater snake robots: Theory and experiments. IEEE Trans. Robot. 2017, 33, 610-628.

8. Moe, S.; Pettersen, K.Y. Set-Based line-of-sight (LOS) path following with collision avoidance for underactuated unmanned surface vessels under the influence of ocean currents. In Proceedings of the IEEE Conference on Control Technology and Applications (CCTA), Mauna Lani, HI, USA, 27-30 August 2017; pp. 241-248.

9. Moe, S.; Pettersen, K.Y.; Fossen, T.I.; Gravdahl, J.T. Line-of-sight curved path following for underactuated USVs and AUVs in the horizontal plane under the influence of ocean currents. In Proceedings of the 24th Mediterranean Conference on Control and Automation (MED), Athens, Greece, 21-24 June 2016; pp. 38-45.

10. Fossen, T.I.; Lekkas, A.M. Direct and indirect adaptive integral line-of-sight path following controllers for marine craft exposed to ocean currents. Int. J. Adapt. Control Signal Process. 2017, 31, 445-463.

11. Korkmaz, F.C.; Su, M.E.; Alarcin, F. Control of a ship shaft torsional vibration via modified PID controller. Brodogradnja 2014, 65, 17-27.

12. Samanta, B.; Nataraj, C. Design of intelligent ship autopilots using particle swarm optimization. In Proceedings of the IEEE Swarm Intelligence Symposium, St. Louis, MO, USA, 21-23 September 2008; pp. 1-7.

13. Johansen, T.A.; Fuglseth, T.P.; Tondel, P.; Fossen, T.I. Optimal constrained control allocation in marine surface vessels with rudders. Control Eng. Pract. 2008, 16, 457-464.

14. Lee, S.D.; Tzeng, C.Y.; Huang, W.W. Ship streeing autopilot based on ANFIS framework and conditional turing scheme. Mar. Eng. Front. 2013, 1, 53-62.

15. Dlabac, T.; Calasan, M.; Krcum, M.; Marvucic, N. PSO-Based PID controller design for ship course-keeping autopilot. Brodogradnja/Shipbuilding 2019, 70, 1-15.

16. Oh, S.R.; Sun, J. Path following of underactuated marine surface vessels using line-of-sight based model predictive control. Ocean Eng. 2010, 37, 289-295.

17. Guerrero, J.; Torres, J.; Creuze, A. Trajectory tracking for autonomous underwater vehicle: An adaptive approach. Ocean Eng. 2019, 172, 511-522.

18. Burns, R.S. The use of artificial neural networks for the intelligent optimal control of surface ships. Ocean Eng. 1995, 20, 65-72.

19. Dai, S.; Wang, C.; Luo, F. Identification and learning control of ocean surface ship using neural networks. IEEE Trans. Ind. Inform. 2012, 8, 801-810.

20. Nicolau, V. On PID controller design by combining pole placement technique with symmetrical optimum criterion. Math. Probl. Eng. 2013, 2013, 1024-1231.

21. Rigatos, G.; Tzafestas, S. Adaptive fuzzy control for the ship steering problem. Mechatronics 2006, 16, 479-489.

22. Godbole, A.A.; Libin, T.R.; Talole, S.E. Extended state observer based robust pitch autopilot design for tactical missiles. Mech. Eng. Part G J. Aerosp. Eng. 2011, 226, 1482-1501.

23. Wang, H.B.; Veremey, E.I.; Xue, Y. A method of the guaranteeing of optimization for the dynamics of ship moving in wave. Vestn. Sankt-Peterburgskogo Univ. Ser. 10 Prikl. Mat. Inform. Protsessy Upravieniya 2017, 13, 354-364.

24. Sun, Z.P.; Wu, Q.; Li, X.G.; Wang, H.B. A design of based on the feedback linearization optimal heading control algorithm. Inf. Technol. Res. 2019, 12, 133-148.

25. Veremey, E.I.; Pogozhev, S.V.; Sotnikova, M.V. Marine autopilots' multipurpose control laws synthesis for actuators time delay. J. Mar. Sci. Eng. 2020, 8, 477.

26. Du, J.L.; Hu, X.; Sun, Y.Q. Adaptive robust nonlinear control design for course tracking of ships subject to external disturbances and input saturation. IEEE Trans. Syst. Man Cybern. Syst. 2020, 50, 193-202.

27. Wu, R.; Du, J.L. Adaptive robust course-tracking control of time-varying uncertain ships with disturbances. Int. J. Control Autom. Syst. 2019, 17, 1847-1855.

28. Xiang, X.B.; Yu, C.Y.; Lionel, L.; Zhang, J.L. Survey on fuzzy-logic-based guidance and control of marine surface vehicles and underwater vehicles. Int. J. Fuzzy Syst. 2018, 20, 572-586.

29. Xu, H.T.; Fossen, T.I.; Soares, C.G. Uniformly semiglobally exponential stability of vector field guidance law and autopilot for path-following. Eur. J. Control 2020, 53, 88-97.

30. Liu, Y.; Bu, R.X.; Xu, H.J. Straight-path tracking control of underactuated ship based on backstepping method. In Proceedings of the 2015 Ninth International Conference on Frontier of Computer Science and Technology FCST, Dalian, China, 26-28 August 2015; pp. 223-227.

31. Zhao, Y.; Dong, L.L. Robust path-following control of a container ship based on Serret-Frenet frame transformation. J. Mar. Sci. Technol. 2020, 25, 69-80.

32. Xu, H.T.; Oliveira, P.; Guedes, S.C. L1 adaptive backstepping control for path-following of underactuated marine surface ships. Eur. J. Control 2020.

33. International Electrotechnical Commission. Maritime Navigation and Radiocommunication Equipment and Systems-Track Control Systems-Operational and Performance Requirements, Methods of Testing and Required Test Results, 2nd ed.; 62065:2014; IEC: Geneva, Switzerland, 2014; pp. 1-212.

34. Ramos, R.L. Linear quadratic optimal control of a spar-type floating offshore wind turbine in the presence of turbulent wind and different sea states. J. Mar. Sci. Eng. 2018, 6, 151.

35. Das, S.; Talole, S.E. Robust steering autopilot design for marine surface vessels. IEEE J. Ocean. Eng. 2016, 41, 913-922.

36. Hiadsi, S.; Bouafia, H.; Sahli, B.; Abidri, B.; Bouaza, A.; Akriche, A. Ship course identification model based on recursive least squares algorithm with dynamic forgetting factor. J. Comput. Appl. 2018, 38, 900-904.

37. Aoki, M. Control of large-scale dynamic systems by aggregation. IEEE Trans. Autom. Control 1986, 13, 246-253.

38. Abedi, F.; Leong, W.J.; Abedi, M. Lyapunov characterization for the stability of stochastic control systems. Math. Probl. Eng. 2015, 2015, 1-7.

39. Wang, X.F.; Zou, Z.J.; Li, T.S.; Luo, W.L. Adaptive path following controller of underactuated ships using serret-frenet frame. J. Shanghai Jiaotong Univ. 2010, 15, 334-339.

AuthorAffiliation

Zhanshuo Zhang

1,

Yuhan Zhao

1,

Guang Zhao

2,

Hongbo Wang

1,* and

Yi Zhao

1,*

1State Key Laboratory on Integrated Optoelectronics, College of Electronic Science and Engineering, Jilin University, Changchun 130000, China

2Branch of 707 Institute of China State Shipbuilding Corporation Limited (CSSC), Jiujiang 332007, China

*Authors to whom correspondence should be addressed.

© 2021. This work is licensed under http://creativecommons.org/licenses/by/3.0/ (the “License”). Notwithstanding the ProQuest Terms and Conditions, you may use this content in accordance with the terms of the License.