2.2. Principle of AFIDLOS Guidance Law
It is assumed that the USV is located at point
with coordinates
with respect to the local coordinate system,
, and the actual heading angle is
(
Figure 2). The USV is planned to move forward along the paths
and
, which are designed with the desired heading angle
in the direction of
. However, the USV indeed derived from the planned path with a sideslip angle
, owing to the distribution of factors such as sea wind, water flow direction, and sea waves.
Therefore, the basic concept of the IDLOS guidance law proposed in this study involves minimizing the influence of the sideslip angle
and correcting the LOS angle
to
by adding the integral and derivative terms
and
, respectively, that is,
where
represents the angle between the north and path
;
represents the cross-track error, which is defined as the vertical distance between the position of the USV and planned path; and
represents the look-ahead distance, which is defined as the distance between the vertical point and point
.
The integral term and derivative terms
, and
, respectively, be expressed as
where
is the constant derivative coefficient;
and
are the integral times; and
is the adaptive factor calculated as
where
is the dynamically adjustable parameter.
Observing Equation (1) and
Figure 2, the added integral and derivative terms (
) change the LOS angle of the USV from
to the corrected angle
, thus, the USV probably track the USV along the direction
to counteract the effect generated by the sideslip angle
.
The traditional fixed value of look-ahead distance in Equation (1) affects the LOS angle, which in turn affects the path-tracking accuracy [
30]. To solve the problem, an adaptive LOS guidance law is developed using a time-vary equation
where
and
are the maximum and minimum look-ahead distances, respectively, which are usually two to four times the length of the USV [
28]; and
is the convergence rate.
A fixed value of the convergence rate in Equation (5) does not satisfy the requirement of the USV to reduce the cross-track error quickly or smoothly if the USV is in a position farther or closer to the planned path [
28]. Thus, AFIDLOS guidance law was proposed to implement the adaptivity of the convergence rate, which is designed using the following steps:
First, if the value of the cross-track error exceeded 1.5 the width of the USV, it was considered to be too far from the planned path; therefore, the domain of the cross-track error
was set within
. Because the velocity of a USV is usually approximately 0.6 m/s while collecting 3D bathymetric point cloud data, the domain of the change rate of the cross-track error
was set as
. To represent the exact value of the domain by a fuzzy value, seven fuzzy subsets of
and
were defined as follows:
where
,
and
represents negative big, medium and small fuzzy values, respectively;
represents 0;
,
and
represents positive small, medium and big fuzzy values, respectively. The magnitude of each subsets represents the degree of magnitude of the value of
and
.
If the USV travels along the planned path, then the look-ahead distance in Equation (5) should take the maximum value
, that is, the convergence rate should be zero. If the USV is away from the planned path, then the look-ahead distance in Equation (5) should take the value closest to
, that, the convergence rate should be one. Based on the above assumptions, the domain of the output
should be within
. Therefore, the five fuzzy subsets of
are defined as follows:
Where
,
and
represents very small, small and medium fuzzy values, respectively; and
and
represents big and very big fuzzy values, respectively. The magnitude of each subset represents the degree of magnitude of the value of
.
Second, to achieve fuzzification of the domains, it is necessary to determine the degree of membership of the domains in Equation (6) and Equation (7). Thus, we divided the range of values of
,
and
into
,
and
, and used the triangular membership function as a membership function of the fuzzy subset for the degree of membership of the values of
,
and
. The results are shown in
Figure 3.
In
Figure 3, each of the values in the domain can be represented by the degree of membership function of the fuzzy subset, which implements the process of fuzzification of the domains into fuzzy subsets. For example, if the value of
is zero, the degree of membership is zero in all fuzzy subsets, except for the fuzzy subset
, where the degree of membership is one. This is because the value of zero is the closest approximation of the fuzzy subset
, and it is not within the range of the values of the other fuzzy subsets.
With the above steps, the next step is fuzzy reasoning for the fuzzy subsets. The basic idea is that if the path of the USV is far from the planned path, the cross-track error is probably large, and the convergence rate should be increased; whereas, if the path of the USV is close to the planned path, the cross-track error is probably small, and the convergence rate should be decreased. Based on this idea, an array of fuzzy control rules was designed, as presented in
Table 1.
Analyzing
Table 1, if the values of
and
are large (PB), the USV must be adjusted to the planned path quickly; thus,
obtains the maximum value (VB). If value of
and
are very small (O), the USV must converge to the planned path smoothly; thus, the
obtains the minimum value (VS). The above analysis shows that the value the fuzzy subset of the
takes is determined by the fuzzy subset of
and
, indicating the fuzzy relationship between the three.
To defuzzy the fuzzy relationships between
,
, and
in
Table 1, it is necessary to convert the fuzzy relationships into exact numerical relationships between the domains. For this purpose, the defuzzification operator was executed based on the fuzzy relationship to obtain the fuzzy input-output 3D surface of the convergence rate, as shown in
Figure 4.
As shown in
Figure 4, the fuzzy subsets of the cross-track error, change rate of the cross-track error, and convergence rate were divided into
,
, and
. The value of the convergence rate is shown in
Figure 4, according to the value of the cross-track error and the change rate of the cross-track error; thus, the USV can obtain a more reasonable value of the look-ahead distance during the path-tracking process.
Finally, combining Equations (1) and (5), the AFIDLOS guidance law is established using
2.3 Control model of LQR
After the AFIDLOS guidance law was developed, the next step was to develop a control model for the USV operation. From
Figure 1, it can be understood that the input to the control model of the LQR was indeed the error of the heading angle
, which can be expressed as [
37]
Derivation of Equation (9), we have
where
is the angular velocity of the USV, whose derivation can be obtained from [
38]
where
is the mass coefficient,
is the damping coefficient, and
represents the rotational moment of the USV, which can be expressed as
where
and
represent the left and right thrusters of the USV, respectively; and
represents the distance between the left and right thrusters.
Because the thrust of the USV thruster cannot be measured directly, it is controlled by varying the time of the high-level pulse width modulation (PWM) signal output from the STM32 chip. Therefore, it is necessary to establish a relationship between the control command and thrust of USV thrusters. Thus, it is assumed that the control command is proportional to the thrust by
where
denotes the proportionality coefficient;
is the initial control command; and
is the variable control command.
By substituting Equation (13) into Equation (12), we obtain
By substituting Equation (14) into Equation (11), the resulting equation for the control model of the USV is expressed as
We rewrite Equation (15) in a state-space form
where
is the state matrix. Simplifying Equation (16) yields
where
can be expressed by
where
is the state feedback matrix. To achieve optimal control,
is calculated as follows [
39]
where
is a positive semi-definite symmetric matrix, that satisfies the following Riccati equation [
40]:
where
is a positive semidefinite matrix; and
is a positive definite symmetric array. The values of the
and
are generally chosen by experience [
41].
After solving for
through Equation (20), the value of
can also be given through Equation (19). Substituting the value of
into Equation (18) yields the final expression of the control command by
Using Equations. (16) and (21), the control command can be obtained by determining the values of and . The control model of the USV and the control law of the LQR for the control command were established, which provided the model and theoretical support for the experiments conducted below.