Next Article in Journal
Estimation of Combustion Parameters from Engine Vibrations Based on Discrete Wavelet Transform and Gradient Boosting
Previous Article in Journal
Useful High-Entropy Source on Spinel Oxides for Gas Detection
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Modeling and Trajectory Tracking Model Predictive Control Novel Method of AUV Based on CFD Data

1
College of Mechanical and Electrical Engineering, Harbin Engineering University, Harbin 150001, China
2
Yantai Research Institute and Graduate School, Harbin Engineering University, Yantai 265501, China
*
Author to whom correspondence should be addressed.
Sensors 2022, 22(11), 4234; https://doi.org/10.3390/s22114234
Submission received: 21 April 2022 / Revised: 28 May 2022 / Accepted: 30 May 2022 / Published: 1 June 2022
(This article belongs to the Section Intelligent Sensors)

Abstract

:
In this paper, a novel model predictive control (MPC) method based on the population normal probability division genetic algorithm and ant colony optimization (GA-ACO) method is proposed to optimally solve the problem of standard MPC with constraints that generally cannot yield global optimal solutions when using quadratic programming (QP). Combined with dynamic sliding mode control (SMC), this model is applied to the dynamic trajectory tracking control of autonomous underwater vehicles (AUVs). First, the computational fluid dynamics (CFD) simulation platform ANSYS Fluent is used to solve for the main hydrodynamic coefficients required to establish the AUV dynamic model. Then, the novel model predictive controller is used to obtain the desired velocity command of the AUV. To reduce the influence of external interference and realize accurate velocity tracking, dynamic SMC is used to obtain the control input command. In addition, stability analysis based on the Lyapunov method proves the asymptotic stability of the controller. Finally, the trajectory tracking performance of the AUV in an underwater, three-dimensional environment is verified by using the MATLAB/Simulink simulation platform. The results verify the effectiveness and robustness of the proposed control method.

1. Introduction

The autonomous underwater vehicle (AUV) is a type of underwater unmanned vehicle (UUV) that has become important to ocean exploration and as a development tool in which artificial intelligence and other advanced computing technologies are integrated [1,2]. Because AUVs operate without an umbilical cord, they are more flexible in underwater operations [3]. In the early stages of deployment, AUVs were mainly used for the development of offshore oil and gas facilities, etc., although later, this technology played an important role in the field of military salvage [4,5]. The AUV has increasingly become of interest to researchers in the marine, oil, industry and military fields of countries around the world [6,7]. So that the AUV can successfully complete its assigned underwater operations, the performance of its control system is critical, especially the design of its trajectory tracking control method [8,9].
Trajectory tracking is limited by time constraints [10]. This technology feature only needs to track the reference path within a certain error allowable range to guide the AUV from the initial state to the final state [11]. For the state error of the system to converge to zero, the selection and optimization of the control method is highly important [11]. At present, many control methods have been successfully applied in the field of AUV trajectory tracking control, including proportional-integral-derivative (PID) control, neural network (NN) control, sliding mode control (SMC) and model predictive control (MPC) [12,13].
PID control is the most widely used control method in engineering, as well as the most stable. Among the various methods, the proportional (P) aspect corrects the deviation so that the process can respond quickly [14,15]. The integral (I) represents information accumulated in the past, which eliminates static errors and improves the static characteristics of the system [16]. The derivative (D) plays a leading control role in signal changes, reduces overshoot, overcomes oscillations and improves system stability [17]. However, an AUV is a high-inertia system. When the expected control command changes suddenly, the output of the AUV cannot be adjusted in time, which results in large system errors [18]. Therefore, PID control is usually combined with adaptive control, fuzzy control or neural network control, among others [19].
NN control is a current frontier in the field of automatic control [20,21]. This method represents a new branch of intelligent control, offering a new way to solve the control problems of complex nonlinear, uncertain and uncertain systems [22,23]. The NN controller is actually a feedforward controller that establishes the inverse model of the controlled object and adjusts the weights between the NN by learning the input and output of the traditional controller as samples to allow the feedback control input to approach zero and replace the traditional controller [24]. The advantage of NN control is that a precise dynamic model of the control target is not needed; additionally, NN can be used to approximate the nonlinear system [25]. The disadvantage is that it is difficult to obtain learning samples. Because the AUV system is highly nonlinear and strongly coupled, these uncertainties challenge the ability of the offline neural network controller in regard to robustness; as a result, the development of an online NN controller should be emphasized [26].
SMC is a special kind of nonlinear control that can, in essence, overcome the uncertainty of the system and has strong robustness in the face of an unknown disturbance, thus it is suitable for the control of AUVs [27]. However, when the state trajectory of the SMC reaches the sliding mode surface, it is difficult to slide strictly along the sliding mode toward the equilibrium point and instead passes back and forth on both sides of the SMC to approach the equilibrium point, resulting in chattering [28]. Elmokadem et al. derived an SMC method for the trajectory tracking control of an AUV but did not solve the chattering problem exhibited by the controller [29]. Londhe and Patre proposed an adaptive fuzzy sliding mode controller by deriving fuzzy logic rules using the Lyapunov energy function to reduce the SMC chattering problem [30].
When using the MPC feedback control method, the current control action is obtained by solving a finite time-domain open-loop optimal control problem at each sampling moment [31,32]. The current state of the process is the initial state of the optimal control problem, and the optimal control sequence only implements the first control effect [33,34]. The advantage of MPC is that it is good at dealing with problems with constraints. In traditional MPC, the process of solving the optimal control sequence is usually transformed into a quadratic programming (QP) problem, which solves the minimum value of a positive definite quadratic function with linear equality constraints [35,36]. However, the QP process often cannot obtain the global optimal solution. To solve this problem, the improved particle swarm optimization (PSO) algorithm, genetic algorithm (GA) and ant colony optimization (ACO) algorithm are usually introduced into MPC to replace the QP solution process. Ref. [37] Gan et al. applied quantum particle swarm optimization (QPSO) to model a predictive controller to solve the optimal control quantity. The application of QPSO enhanced the global search ability of traditional PSO and applied the controller to the trajectory tracking control field of AUVs, achieving a good tracking effect. Ref. [38] Zhang et al. proposed an improved GA to optimize the Q and R matrices in the control objective function of the MPC method; unfortunately, the GA easily falls into a local optimal value due to the lack of population diversity. Additionally, it is difficult for the algorithm to converge quickly in the later stage, and it is difficult to obtain the optimal solution within the MPC sampling time. The ACO algorithm can compensate for the slow convergence rate of the GA in the later stage, although the initial convergence rate of the algorithm is slow due to its low initial pheromone concentration.
To solve the above problems, this paper proposes an MPC method optimized by the GA-ACO algorithm based on population normal probability division. The standard GA of the fitness value according to the normal probability interval is divided into the following steps: put forward the internal and external hybrid crossover operator and dynamic hybrid mutation operator to maintain the diversity of the population, and later, using the ACO algorithm to accelerate convergence, make MPC obtain the global optimal control sequence. Finally, combine the process with dynamic SMC, which is used in AUV trajectory tracking control. The controller recalculates the optimal input at the next time according to the systematic error at each sampling time. The hydrodynamic coefficients used in AUV modeling in this paper are computational fluid dynamics (CFD) data based on the actual solution of ANSYS Fluent.
The main content of this paper is as follows: Section 2 introduces the kinematic and dynamical model of the AUV. In Section 3, the solution methods and results for the main hydrodynamic coefficients of the AUV are introduced. Section 4 introduces the formulation of the optimization problem and the control method proposed in this article. Section 5 presents a stability analysis of the proposed control method based on terminal constraints. Section 6 gives the simulation results. Section 7 offers some concluding comments.

2. Modeling of the AUV

This paper focuses on AUV modeling and trajectory tracking control. As shown in Figure 1, the size and mechanical structure of the AUV proposed in this paper are designed using the SOLIDWORKS design platform, with the relevant parameter values shown in Table 1. The arrangement of thrusters supports the movement of the AUV with five degrees of freedom. To avoid the singularity of the Euler angle, the pitch angle θ of the AUV is bounded and satisfies π / 2 θ π / 2 . The AUV roll angle ϕ is also self-stable due to the recovery torque caused by buoyancy and other factors. Therefore, the default expected angle and velocity values of ϕ and θ in this paper are 0. In the forward direction, one main propeller is used to generate the thrust of the surge, two vertical propellers complete the thrust of the heave and the pitch moment, and two lateral propellers complete the thrust of the sway and the yaw moment.

2.1. Kinematic Modeling

To establish the kinematic model of the AUV to study its trajectory tracking control, the body coordinate frame B and the inertial coordinate frame I are introduced, both of which are defined in right-handed Cartesian coordinate systems. The origin of B is the center of gravity of the AUV, which is used to describe the velocity information of the AUV. The velocity vector of the AUV is defined as v = [ u , v , w , q , r ] T , where u, v and w are the velocities in the surge, sway and heave directions, respectively, and q and r are the angular velocities in the pitch and yaw directions. The origin of I may be any point on Earth, which is used to define the position and attitude information of the AUV in B with respect to I. The position and attitude vector of the AUV is defined as η = [ x , y , z , θ , ψ ] T , where the positive direction of the x, y and z axes points in the horizontal north direction, the horizontal east direction and the geocentric direction, respectively, and θ and ψ are the pitch and yaw angle attitudes of the AUV.
The kinematic model can be defined in the following form:
η ˙ = J ( η ) v
Here, J ( η ) is the transition matrix between the two coordinate frames:
J ( η ) = cos θ cos ψ sin ψ sin θ cos ψ 0 0 cos θ sin ψ cos ψ sin θ sin ψ 0 0 sin θ 0 cos θ 0 0 0 0 0 1 0 0 0 0 0 1 / cos θ

2.2. Dynamic Modeling

The dynamic model of the AUV, as proposed by Fossen, is expressed [35]:
M v ˙ + C ( v ) v + D ( v ) v + g ( η ) = τ
Here, M = M RB + M A is defined as the inertia matrix. M RB = d i a g ( m , m , m , I y , I z ) is the rigid-body inertial mass matrix, which is a property of the AUV itself and does not change with time, where m is the mass of the AUV and I y and I z are the inertia tensors of the y B and z B axes. M A = d i a g ( X u ˙ , Y v ˙ , Z w ˙ , M q ˙ , N r ˙ ) is the additional mass matrix, which represents the hydrodynamic force due to the acceleration of the AUV underwater, where X u ˙ , Y v ˙ , Z w ˙ , M q ˙ and N r ˙ are the inertial hydrodynamic coefficients.
C ( v ) = C RB + C A is the Coriolis and centripetal force matrix. C RB is the Coriolis and centripetal force matrix due to the rigid-body inertial mass, and C A is the hydrodynamic Coriolis and centripetal force matrix due to the additional mass.
Specifically:
C RB = 0 0 0 m w m v 0 0 0 0 m u 0 0 0 m u 0 m w 0 m u 0 0 m v m u 0 0 0
C A = 0 0 0 Z w ˙ w Y v ˙ v 0 0 0 0 X u ˙ u 0 0 0 X u ˙ u 0 Z w ˙ w 0 X u ˙ u 0 0 Y v ˙ v X u ˙ u 0 0 0
D ( v ) = D L ( v ) + D N ( v ) is the fluid damping matrix, including the linear damping matrix D L ( v ) and the quadratic damping matrix D N ( v ) , where D L ( v ) = d i a g ( X u , Y v , Z w , M q , N r ) and D N ( v ) = d i a g ( X u u u , Y v v v , Z w w w , M q q q , N r r r ) . Here, X u , Y v , Z w , N r , X u u , Y v v , Z w w , M q q q and N r r are measurable viscous hydrodynamic coefficients.
g ( η ) = [ 0 , 0 , 0 , b Z g sin θ , 0 ] T is a vector representing the restoring forces and moments due to the forces of gravity and buoyancy, b. In this paper, the force of gravity of the AUV is set equal to its buoyancy. Z g is the vertical coordinate of the center of gravity.
τ = [ τ u , τ v , τ w , τ q , τ r ] T is the vector of the input forces and moments for each DOF.

3. Solution for the Hydrodynamic Coefficients

3.1. Solution Method and Fluid Area Division

To realize the accurate modeling of the AUV as proposed in this paper, it is necessary to analyze its hydrodynamic performance and solve the main viscous hydrodynamic parameters and inertial hydrodynamic parameters. This part is based on the solution method of [39]. The solution process of this method is shown in Figure 2. Using the CFD solution ANSYS Fluent platform, the AUV simulates the corresponding translational motion and rotational motion in the seawater environment. Figure 3 shows the division of the solution domain for the translational motion, and Figure 4 shows the solution domain division of the rotational motion. The control method and parameter settings of the mesh divisions are shown in Table 2.

3.2. Simulation Process

As shown in Equation (3), through the analysis of each component in the dynamic model of the AUV, it can be concluded that the hydrodynamic force of the AUV when moving in the fluid includes the inertial hydrodynamic force or moment τ A caused by the additional mass and the viscous drag or moment τ D caused by the viscosity of the fluid. The expression is as follows:
τ D = D L ( v ) v + D N ( v ) v v
τ A = M A v ˙
D L is the linear damping matrix, and D N is the nonlinear damping matrix. From Equation (6), it can be concluded that the viscous drag and moment of the AUV are related to velocity via a quadratic function. By simulating the translational and rotational motion of each degree of freedom of the AUV under different velocities, the values of drag and moment under different velocities can be solved, and the viscous hydrodynamic coefficients can be identified by curve fitting with the least squares method.
In all simulations, the fluid is seawater with a density of 1025 kg / m 3 and viscosity of 8.8871 × 10 4 Pa · s . The turbulence model is K-epsilon.
The uniform translational and rotational motions of the AUV are simulated. Each simulation only gives the velocity value of one degree of freedom to the AUV, while the velocity value of any other degrees of freedom is zero.
The velocity cloud diagrams of the AUV at a uniform velocity of 1 m / s in the surge, sway and heave directions are shown in Figure 5. Table 3 shows the calculated viscous drag on the AUV at different velocities. The least square method was used to fit the velocity values of translational motion and the corresponding viscous resistance data to a quadratic curve through the origin, and the fitting results are shown in Figure 6.
The velocity cloud diagrams of the AUV moving around the z axis with a uniform rotational velocity of 0.5 rad / s are shown in Figure 7. The calculated damping moments of the AUV at different angular velocities are given in Table 4. The least square method was used to fit the rotational velocity values and the corresponding viscous moment data to a quadratic curve through the origin, and the fitting results are shown in Figure 8.
The approximate viscous hydrodynamic coefficients obtained by fitting the results are shown in Table 5.
According to Equation (7), it can be clearly seen that the inertial hydrodynamic force on the AUV has a linear relationship with its acceleration. The next simulation considers the uniform acceleration of the AUV to 2 m / s at different linear accelerations and to 1 rad / s at different angular accelerations, because the results obtained by solving for the state of the AUV at different accelerations contain the drag force and moment caused by the viscous hydrodynamic force. Therefore, the inertial hydrodynamic force due to the additional mass should be the difference between the results for the uniform-acceleration and uniform-velocity motion solutions. By fitting this difference to a linear relationship, the approximate inertial hydrodynamic coefficients can be obtained. The user-defined function (udf) is used to write programs to achieve uniform acceleration of the AUV translational motion and uniform acceleration of its rotational motion.
Figure 9 shows the velocity cloud diagrams of the AUV with a uniform acceleration of 0.1 m / s 2 in the surge, sway and heave directions. Table 6 shows the calculated results for the drag force on the AUV at different accelerations. The least square method was used to fit the acceleration values and drag data to a straight line through the origin, and the fitting results are shown in Figure 10.
The velocity cloud diagrams of the AUV in uniform rotational motion around the z axis with an angular acceleration of 0.01 rad / s 2 are shown in Figure 11. The calculated results for the moments of the AUV at different angular accelerations are given in Table 7. The least square method was used to fit the angular acceleration values and moment data to a straight line through the origin, and the fitting results are shown in Figure 12.
The approximate inertial hydrodynamic coefficients obtained by fitting the results are given in Table 8.

4. Design of the Controller

In this part, the AUV controller used to perform trajectory tracking tasks is designed in detail. The controller is composed of two cascaded controllers. The outer loop controller uses the novel GA-ACO algorithm based on the population division of the normal probability interval, combined with the constraints of velocity and position and the system output feedback, to solve the optimal control sequence of the model predictive controller, that is, the expected velocity command of the AUV, which is transmitted to the inner loop controller. The inner loop controller is a sliding mode controller that can obtain the control input instructions of the AUV and ensure tracking of the AUV along its entire trajectory. The control strategy block diagram is shown in Figure 13.

4.1. MPC Based on Novel GA-ACO

It is assumed that the trajectory is given in advance and is smooth and bounded. The expected trajectory is described as follows:
Y d = [ x d , y d , z d , θ d , ψ d ] T
The expected velocity command is obtained by inputting the error between the actual position of the AUV and the expected position. T s is the sampling time, and the motion model of the system is obtained after discretization as follows:
η ( k + 1 ) = η ( k ) + J ( k ) v ( k ) T s
To ensure stable motion of the AUV, the velocity increment is given as an input, and the state-space model of the AUV is expressed as follows:
X ( k + 1 ) = [ η ( k + 1 ) , v ( k ) ] T
The velocity increment is defined as follows:
Δ v ( k ) = v ( k ) v ( k 1 )
Y ( k ) is defined as the output. By defining matrices Q A ( k ) and Q B ( k ) in the form given below, the equation of state can be rewritten as follows:
X ( k + 1 ) = Q A ( k ) X ( k ) + Q B ( k ) Δ v ( k )
Y ( k ) = C X ( k )
with
Q A ( k ) = I 5 J ( k ) T s 0 5 × 5 I 5 , Q B ( k ) = J ( k ) T s I 5 , C = I 5 0 5 × 5
where I 5 is a 5 × 5 identity matrix and 0 5 is a 5 × 5 zero matrix. Equations (10) and (11) are the model prediction equations for the AUV, from which the future state of the system can be inferred. The prediction horizon is denoted by N p , and the control horizon is denoted by N c ; these horizons must satisfy N c N p . The control value is held constant outside the control horizon. The controller output sequences are as follows:
X N p = X ( k + 1 | k ) X ( k + 2 | k ) X ( k + N p | k ) , Y N p = Y ( k + 1 | k ) Y ( k + 2 | k ) Y ( k + N p | k )
The system input sequence is as follows:
Δ v ( k ) = Δ v ( k + 1 | k ) Δ v ( k + 2 | k ) Δ v ( k + N p 1 | k )
Based on the principle of MPC, the model prediction equations can be further expressed as
X ¯ ( k + 1 ) = Q ¯ A ( k ) X ¯ ( k ) + Q ¯ B ( k ) Δ v ( k )
where
Q ¯ A ( k ) = [ Q A ( k ) , Q A ( k ) 2 , , Q A ( k ) N p ] T
Q ¯ B ( k ) = Q B ( k ) 0 0 Q A ( k ) Q B ( k ) Q B ( k ) 0 Q A ( k ) N p 1 Q B ( k ) Q A ( k ) N p 2 Q B ( k ) Q B ( k )
Constraints: The upper and lower bounds on the AUV state and the velocity increment are set as follows:
u min Δ v ( k ) u max
X min X ( k ) X max
By adjusting the current and future inputs to the system, the predicted performance cost function is defined as follows:
E ( t ) = 0 T [ Y ( t ) Y d ( t ) Q y 2 + Δ v ( t ) Q Δ v 2 ] d t
where
y Q y 2 = y T Q y y , Δ v s . Q Δ v 2 = Δ v T Q Δ v Δ v
Q y and Q Δ v are symmetric positive-definite weight matrices. Within the sampling time T s , the cost function E ( t ) is discretized as follows:
E ( k ) = i = 1 N p [ Y ( k + i | k ) Y d ( k + i | k ) Q y 2 + Δ v ( k + i 1 | k ) Q Δ v 2 ]
According to Equation (13), the above equation can be transformed into
E ( k ) = i = 1 N p [ X ( k + i | k ) X d ( k + i | k ) Q x 2 + Δ v ( k + i 1 | k ) Q Δ v 2 ]
where
X ( k + i ) = C Y ( k + i ) , Q x = C Q y C
C is the pseudoinverse of the matrix C. According to Equation (17), the simplified equation can be expressed as follows:
E ( k ) = X ¯ ( k ) X ¯ d ( k ) Q ¯ x 2 + Δ v ( k ) Q ¯ Δ v 2
where
Q ¯ x = Q x 0 0 0 Q x 0 0 0 Q x
Q ¯ Δ v = Q Δ v 0 0 0 Q Δ v 0 0 0 Q Δ v
It can be seen from Equations (27)–(29) that E ( k ) is a function of Δ v ( k ) ; thus, the optimization problem can be transformed into the following problem of finding the minimum value of the cost function with constraints (20) and (21):
Δ v * ( k ) = argmin Δ v ( k ) E ( k )

4.2. Novel GA-ACO for Solving the Cost Function

In this section, we introduce a novel GA-ACO method to replace the QP method in the standard MPC to solve the extreme value of the cost function and obtain the optimal control variable Δ v ( k ) . The proposed population normal probability division method is helpful to maintain the diversity of the GA population, to avoid falling into the local optimal solution and to improve the global search ability of the algorithm. To improve the convergence speed in the later stage of the algorithm, the initial optimization result of the GA is used as the initial pheromone of the ACO algorithm, and the global optimal solution is obtained by the rapid convergence of the ACO algorithm.
1.
Chromosome coding and fitness function setting.
Chromosomes are encoded in real numbers. As shown in Figure 14, the length of the chromosomes is consistent with the control horizon of MPC, where each locus corresponds to the predicted control amount in each sampling period of MPC. Taking Equation (27) as the fitness function of the algorithm, through continuous iteration, the optimal control sequence for each sampling period is obtained.
2.
Population normal probability division.
To reasonably improve the diversity of the population in the GA algorithm, a method of dividing the population normal probability interval is proposed. Equation (31) is a one-dimensional normal distribution function, with a probability density function given as Equation (32), where σ is the standard deviation and μ is the mean value. According to the 3 σ criterion, the probability that the value is distributed in ( μ σ , μ + σ ) is 68.26 % , the probability of being distributed in ( μ 2 σ , μ + 2 σ ) is 95.44 % , and the probability of being distributed in ( μ 3 σ , μ + 3 σ ) is 99.74 % , which basically represents the entire probability space. The initial population is sorted according to the fitness value from greatest to least, and the population is divided into six families according to the above method. In this paper, the initial population number is set to 200, giving the division results shown in Table 9.
f ( x ) = 1 2 π σ e x p ( x μ ) 2 2 σ 2
a b 1 2 π σ e x p ( x μ ) 2 2 σ 2 d x
3.
Crossover, mutation and convergence.
(1)
Intra-family crossover: The optimal individual within the family is retained without a crossover operation. In the same family, individuals were randomly selected for intrafamily crossover, and the elite retention strategy was adopted. The parents and offspring were sorted according to the fitness function value, and the optimal retention was selected.
(2)
Cross between families: Set the maximum and minimum number of iterations, when the number of iterations is less than the maximum number of iterations, and update the optimum population fitness values that are either not changed or for which the rate of change is small. For the crossover operation between families, randomly select the best individual in the families of two different crossover operations, and take the elite reserved strategy after the cross. The idea of interfamily crossover controls the hemming distance of crossover individuals, avoids inbreeding, helps to maintain population diversity and prevents the algorithm from falling into a local minimum.
(3)
Mixed mutation operator: Hybrid mutation integrates the advantages of Gaussian mutation, Cauchy mutation, Levy mutation and single point mutation to make all of the mutation types work together. In the initial state, the selection probability of the four mutation operators is the same, where all are 0.25. The elite retention strategy is implemented after the mutation operation. If the offspring fitness of the individual after mutation is better than that of the parent, then the probability of the individual type occurring with the corresponding mutation strategy is increased; if the offspring fitness value of the individual is lower than that of the parent after mutation, then the probability of the individual type occurring in the corresponding mutation strategy is reduced. Finally, the probability of updating the four mutation modes after each population mutation operation is determined.
(4)
Algorithm convergence: In the proposed algorithm, by combining the advantages of the GA and ACO algorithms, the ant colony algorithm adopts the maximum-minimum ant algorithm. The preliminary optimal solution obtained by the GA is used as the initial pheromone of the ACO algorithm, allowing the algorithm to quickly converge to the global optimal control sequence Δ v * ( k ) , which makes up for the disadvantage of the slow convergence of the GA algorithm in the later stage. Take the first predicted value Δ v * ( k + 1 | k ) of the optimal control sequence as the expected velocity control command.
4.
Population normal probability judgment.
Due to crossover and mutation within the population, it is necessary to monitor the normality of the population fitness value during the iteration process. It is proposed to use the absolute value difference of the median, mode and mean of the population fitness value of each iteration as the threshold for monitoring normality. According to the observations of several simulation results in the later period, the threshold value is set as 0.05. When the data normality quality is low and the minimum value of the difference value is greater than 0.05, the normal probability interval family is terminated. If convergence to the optimal solution has been achieved, then the optimal path is output and executed. Otherwise, the random crossover and mutation algorithm is adopted, and the elite retention strategy is implemented. As shown in Figure 15, using the simulation tool Quantile-Quantile Plots, the initial population number is 200, the maximum number of iterations is 50, and the 5th to 50th and the normality monitoring results of the population fitness value at the 50th generation. Excluding the special values, the results show that the sample points all fall near the red standard normal distribution line, which conforms to the normal probability distribution.

4.3. Dynamic Sliding Mode Velocity Controller

In this part, we design a dynamic sliding mode velocity controller. The conventional SMC control law is usually designed as a discontinuous function, which leads to chattering in the whole system. To overcome the chattering problem of SMC, we put the discontinuous function into the first derivative of the control input, so that the derivative of the control input is discontinuous, but the control input becomes a continuous function after integration, which can effectively suppress or eliminate the chattering problem of SMC.
The dynamic sliding mode controller is designed to overcome the external interference of THE AUV in the offshore environment and improve the robustness of the whole AUV control system. The force and torque required to drive the AUV are designed according to the input velocity error.
The difference between the expected velocity of the system according to Equation (33) and the actual velocity of the AUV is used as the input to the velocity controller. This error is defined as follows:
e v = v d v = [ e u , e v , e w , e q , e r ] T
where v d = [ v d u , v d v , v d w , v d q , v d r ] T . According to the velocity error e v , the dynamic sliding surface is designed as follows:
S = δ ( e ˙ v + e v ) = 0
where δ is the sliding surface coefficient. The following form can be obtained by deriving the sliding surface:
S ˙ = δ ( e ¨ v + e ˙ v ) = δ ( v ¨ d v ¨ ) + δ ( v ˙ d v ˙ )
We take the sliding mode surface s as the system state, design the sliding mode surface again as follows:
σ = S ˙ + S = δ ( e ¨ v + 2 e ˙ v + e v )
The derivative of sliding mode surface in Equation (36) is obtained and is equal to the exponential asymptotic law:
σ ˙ = S ¨ + S ˙ = δ ( e ¨ v + 2 e ˙ v + e v ) = σ s g n σ
Here, s g n is a discontinuous symbolic function, denotes the velocity at which the moving point of the system approaches the switching surface σ = 0 .
It can be concluded from Equations (36) and (37) that the discontinuous function causing SMC chattering only appears in sliding mode surface σ , that is, the discontinuous function only appears in the derivative of control input. After integrating the sliding mode surface σ , the control input is a continuous function, which eliminates the chattering problem of dynamic SMC. According to Equation (3), we obtain
v ˙ = M 1 ( τ C ( v ) v D ( v ) v g ( η ) )
According to Equations (3)–(5), by combining Equations (34) and (35), the amount of control for each degree of freedom of the AUV can be obtained:
τ u = ( m X u ˙ ) ( v ˙ d u 1 2 ( u v d u v ¨ d u + u ¨ σ s g n σ d σ δ ) + m w ( q r ) Z w ˙ w q Y v ˙ v r + ( X u + X u u u ) u
τ v = ( m Y v ˙ ) ( v ˙ d v 1 2 ( v v d u v ¨ d v + v ¨ σ s g n σ d σ δ ) + u r ( m X u ˙ ) + ( Y v + Y v v v ) v
τ w = ( m Z w ˙ ) ( v ˙ d w 1 2 ( w v d w v ¨ d w + w ¨ σ s g n σ d σ δ ) u q ( m + X u ˙ ) + ( Z w + Z w w w ) w
τ q = ( I y M q ˙ ) ( v ˙ d q 1 2 ( q v d q v ¨ d q + q ¨ σ s g n σ d σ δ ) + u w ( Z w ˙ X u ˙ ) + ( M q + M r q q ) q + b Z g s i n ( θ )
τ r = ( I z N r ˙ ) ( v ˙ d r 1 2 ( r v d r v ¨ d r + r ¨ σ s g n σ d σ δ ) + u v ( X u ˙ Y v ˙ ) + ( N r + N r r r ) r
At each sampling time k, Δ v * ( k ) is recalculated. Then, the optimal control forces and moments are repeatedly computed and executed by the AUV to achieve rolling optimization. The optimization process iterates until the AUV completes the trajectory tracking task.

5. Stability Analysis

The stability of the controller proposed in this paper is analyzed in this section.
Lemma 1.
The stability of the controller is proven using the traditional method of proving Lyapunov stability in control theory, i.e., by finding a Lyapunov function of the system that is positive definite and whose its derivative is negative definite.
Theorem 1.
Suppose that the following statements are true: (1) When k = 0 , the constrained optimization problem (30) has a solution Δ v ( k | k ) . (2) The zero state of the system output is measurable. For the nominal system (without considering external disturbances or system uncertainty), the following can be concluded: (a) For any k > 0 , the constrained optimization problem (30) updated with the state measurement X ( k ) has a solution. (b) The closed-loop system described by Equations (12) and (13) are nominally stable.
Lemma 2.
If the continuous differentiable function f(t), when t approaches infinity, has a finite limit value, and the derivative of f(t) is uniformly continuous, then
lim x + ( f ( t ) ˙ ) = 0
Proof of Lemmas 1 and 2 and Theorem 1. 
Suppose that the solution to the optimization problem at time k is expressed as follows:
Δ v * ( k ) = Δ v * ( k | k ) Δ v * ( k + 1 | k ) Δ v * ( k + N p 1 | k )
This approach satisfies the control constraints (20) and (21). The terminal constraint of the model predictive controller is set as follows:
X ( k + N p | k ) = 0
The predicted optimal state sequence and output sequence are as follows:
X k * ( k + 1 | k ) , X k * ( k + 2 | k ) , , X k * ( k + N p 1 | k ) , 0 Y k * ( k + 1 | k ) , Y k * ( k + 2 | k ) , , Y k * ( k + N p 1 | k ) , 0
These sequences satisfy the output constraints (20) and (21) and the terminal constraint (45).
The optimal value of the cost function is:
E * ( k ) = i = 0 N p 1 [ X * ( k + i | k ) X d ( k + i | k ) Q y 2 + Δ v * ( k + i | k ) Q Δ v 2 ]
For the model predictive controller based on MPC-GA-ACO, the optimal cost function E * ( k ) is selected as the Lyapunov function L m * ( k ) :
L m * ( k ) = i = 0 N p 1 [ X * ( k + i | k ) X d ( k + i | k ) Q y 2 + Δ v * ( k + i | k ) Q Δ v 2 ]
Clearly, Equation (48) satisfies L m * ( 0 ) = 0 with k = 0 and L m * ( k ) > 0 with arbitrary k 0 .
In Equations (44) and (46), X * ( k | k ) = X ( k ) and Δ v * ( k | k ) = Δ v ( k ) . By substituting into Equation (12), we obtain:
X ( k + 1 ) = Q A ( k ) X ( k ) + Q B ( k ) Δ v * ( k | k ) = X * ( k + 1 )
At time k + 1 , a predictive control sequence is selected as follows:
Δ v ( k + 1 ) = Δ v ( k + 1 | k + 1 ) Δ v ( k + 2 | k + 1 ) Δ v ( k + N p 1 | k + 1 ) Δ v ( k + N p | k + 1 ) = Δ v * ( k + 1 | k ) Δ v ( k + 2 | k ) Δ v ( k + N p 1 | k ) 0
Due to the terminal constraint given in Equation (45), the last element of the preselected control sequence is zero, and the control constraint is satisfied. The corresponding state sequence is as follows:
X ( k + i + 1 | k + 1 ) = X * ( k + i + 1 | k ) , i = 0 , , N p 1 0 , i = N p
By substituting Equations (50) and (51) into Equation (25), we obtain:
E ( k + 1 ) = i = 0 N p 1 [ X ( k + i + 1 | k + 1 ) X d ( k + i + 1 | k + 1 ) Q x 2 + Δ v ( k + i + 1 | k + 1 ) Q Δ v 2 ] = i = 0 N p 2 [ X * ( k + i + 1 | k ) X d ( k + i + 1 | k ) Q x 2 + Δ v * ( k + i + 1 | k ) Q Δ v 2 ] = i = 1 N p 1 [ X * ( k + i | k ) X d ( k + i | k ) Q x 2 + Δ v * ( k + i | k ) Q Δ v 2 ] = i = 0 N p 1 [ X * ( k + i | k ) X d ( k + i | k ) Q x 2 + Δ v * ( k + i | k ) Q Δ v 2 ] X * ( k | k ) X d ( k | k ) Q x 2 Δ v * ( k | k ) Q Δ v 2 = E * ( k ) X * ( k | k ) X d ( k | k ) Q x 2 Δ v * ( k | k ) Q Δ v 2
Obviously,
E * ( k + 1 ) E ( k + 1 ) = E * ( k ) X * ( k | k ) X d ( k | k ) Q x 2 Δ v * ( k | k ) Q Δ v 2
L m * ( k + 1 ) L m * ( k )
Equation (48) satisfies L m * ( 0 ) = 0 with k = 0 and L m * ( k ) < 0 with arbitrary k 0 . The Lyapunov function in (46) is monotonically decreasing, i.e., L m * ( k + 1 ) L m * ( k ) . Thus, system (17) is nominally stable.
For the dynamic sliding mode velocity controller, Since the expected trajectories of AUV designed in this paper are all functions of time t, the system is a nonautonomous system, and its stability can be proved according to Lemma 2. the Lyapunov function L s * ( k ) is defined as follows:
L s * ( k ) = 1 2 σ 2
L ˙ s * ( k ) = σ ˙ σ = ( σ s g n σ ) σ = σ 2 σ
From Equations (55) and (56), It can be readily shown that L s * ( k ) 0 and L ˙ s * ( k ) < 0 . Since σ and σ ˙ are bounded, L ¨ s * ( k ) is bounded and L ˙ s * ( k ) is uniformly continuous. From Lemma 2, we can get that when t approaches infinity, L ˙ s * ( k ) , σ   a n d   S approaches zero. It can be obtained from Equations (34)–(36) that e ˙ v = e v . So we can get that as follows:
e v = ε e t
It can be obtained from Equations (57) that when time t approaches infinity, e v approaches zero, that is, the output of the system can track the expected signal, so the system is asymptotically stable. Lyapunov function L s * ( k ) still satisfies Theorem 1, that is, L s * ( k ) is positive definite and its derivative is negative definite. It can also prove the asymptotic stability of the dynamic sliding mode controller designed in this paper. The asymptotic stability of the inner loop controller and the outer loop controller ensures the overall stability of the AUV control system. □

6. Simulation Results

In this section, the effectiveness and robustness of the controller proposed in this paper (MPC-GA-ACO) are verified using the MATLAB/Simulink simulation platform, and the simulation results for the proposed controller are compared with those for a GA model predictive controller (MPC-GA) [35] and a standard model predictive controller (MPC) [38]. The above three controllers all form a cascade control with dynamic SMC. The main hydrodynamic parameters of the AUV used in the simulations are shown in Table 5 and Table 8.
The parameter settings for the controller proposed in this paper are as follows: The sampling period is Ts = 0.1 s. The prediction horizon is N p = 10 , the control horizon is N c = 6 , the weighted factors are Q x = d i a g ( 0.05 , 0.05 , 0.05 , 0.05 , 0.05 ) and Q Δ v = d i a g ( 1 , 1 , 1 , 1 , 1 ) , the amplitudes of the input constraints are u max = [ 2 , 2 , 2 , 0.2 , 0.2 ] T and u min = [ 2 , 2 , 2 , 0.2 , 0.2 ] T , and the state constraints are X max = [ + , + , 0.1 , 2 π , 2 π , 2 , 2 , 2 , π / 6 , π / 6 ] T and X min = [ , , 0.1 , 2 π , 2 π , 2 , 2 , 2 , π / 6 , π / 6 ] T . In the novel MPC-GA-ACO, the number of populations is set to p = 200 , and the maximum number of iterations is 50. The sliding surface coefficient δ is set to 2.
Random disturbances are also introduced in the simulation as follows:
u r = 0.2 × rand ( 1 ) , ( m / s ) v r = 0.2 × rand ( 1 ) , ( m / s ) w r = 0.2 × rand ( 1 ) , ( m / s )
where rand(1) is a normally distributed noise signal with mean 0 and variance 1.
The initial position and pose vector of the AUV is η ( 0 ) = [ 0 , 5 , 0 , 0 , 0 ] T . Expected trajectory 1 of the AUV in the simulation is as follows:
x d = 7 cos ( 0.1 t ) y d = 7 sin ( 0.1 t ) z d = 0.2 t
The expected trajectory 2 of the AUV in the simulation is as follows:
x d = 5 sin ( 0.2 t ) + 10 sin ( 0.05 t ) y d = 5 sin ( 0.1 t ) + 10 sin ( 0.025 t ) z d = 0.1 t
Figure 16 shows the trajectory 1 tracking performance of the AUV without disturbance. The simulation results show that the three controllers can give the AUV good trajectory tracking performance. Obviously, the controller designed in this paper is the best of the three controllers in the initial speed of tracking the expected trajectory and the final tracking performance (red curve).
Figure 17 shows a comparison of the tracking error results of each degree of freedom of the AUV and the tracking errors of the three control methods are bounded. Although the tracking error of the controller designed in this paper is lower than that of the standard model predictive controller in the initial stage, its overall tracking error result is better than that of the other two controllers (red curve). Table 10 shows the average position error of the three control methods in tracking the desired trajectory. It can be clearly seen from the table that the average error of the controller designed in this paper in five degrees of freedom is the smallest. The average position error data of surge, sway, heave, pitch and yaw are, respectively, 0.1431 m, 0.1654 m, 0.0999 m, 0.1178 m, 0.0987 m.
As shown in Figure 18, the control input stability of the controller proposed in this paper is the best in the comparison of the control input of the three controllers without disturbance (red curve).
Figure 19 shows the simulation results of trajectory 1 tracking performance with the random disturbance. Compared with the simulation results without disturbance, the random disturbance interferes with the motion of AUV in the three degrees of freedom of surge, sway and heave. Obviously, the tracking performance of the three control methods is slightly reduced. However, compared with the other two controllers, the controller proposed in this paper still has the best tracking performance (red curve).
Figure 20 shows the comparison of the tracking error results of each degree of freedom of AUV, and the tracking error of the three control methods is bounded. The error fluctuates with the random disturbance, and the error fluctuation of standard MPC controller is the largest (green curve). However, the controller proposed in this paper has the minimum tracking error and the error fluctuation is stable (red curve). Table 11 shows the average position error of the three control methods when tracking the expected trajectory. It can be clearly seen from the table that the average position error of the controller designed in this paper is the smallest under five degrees of freedom. The average position error data of surge, sway, heave, pitch and yaw are 0.1893 m, 0.1867 m, 0.1445 m, 0.1498 m and 0.1612 m, respectively.
Figure 21 shows the control input fluctuation of the three controllers in the case of random disturbance. The control input stability of the proposed controller is still the best among the controllers and the fluctuation is the smallest (red curve).
To further verify the performance of the controller, the trajectory tracking the performance of AUV is simulated again in aperiodic function trajectory 2. Figure 22 shows the trajectory 2 tracking performance of AUV without disturbance. The overall tracking effect of the standard MPC controller is poor (green curve). Although the overall tracking effect of the MPC-GA controller is improved compared with the standard MPC controller, the tracking speed is the slowest in the initial stage of trajectory tracking (blue curve). Because the new GA-ACO algorithm can reasonably maintain the diversity of the population, and ensure the local search and global search ability of the algorithm at the same time, so that the optimal control sequence can be obtained in each sampling period of MPC, the simulation results show that the controller proposed in this paper not only ensures the tracking speed of AUV in the initial stage of trajectory tracking but also the overall tracking effect is the best of the three (red curve).
Figure 23 shows the comparison of the tracking error results of each degree of freedom of AUV, and the tracking errors of the three control methods are bounded. Among them, the standard MPC controller error fluctuates greatly when the AUV bow direction change rate is large (green curve), but the controller proposed in this paper has the smallest tracking error (red curve). Table 12 shows the average position error of the three control methods when tracking the desired trajectory. It can be seen from the table that the average error of the controller designed in this paper is the smallest under five degrees of freedom. The average position error data of surge, sway, heave, pitch and yaw are 0.1881 m, 0.1825 m, 0.1110 m, 0.0915 m, and 0.0873 m, respectively.
Figure 24 shows the control input fluctuation of the three controllers without disturbance. The control input stability of the proposed controller is still the best and the fluctuation is the smallest (red curve).
Figure 25, Figure 26 and Figure 27 show the trajectory 2 tracking performance of the AUV with random disturbance. Compared with the other two controllers, the controller achieves the optimal trajectory tracking performance under the condition of minimum error and smooth control intput under random disturbance. The random disturbance leads to a high-frequency variation of the desired speed command, but the proposed controller can still track the desired speed perfectly, which proves its effectiveness and robustness (red curve).
Table 13 shows the average position error of the three control methods in tracking the desired trajectory. It can be clearly seen from the table that the average error of the controller designed in this paper in five degrees of freedom is the smallest. The average position error data of surge, sway, heave, pitch and yaw are, respectively, 0.1932 m, 0.1894 m, 0.1777 m, 0.0998 m, 0.1221 m.

7. Conclusions

In this paper, a novel AUV double closed-loop trajectory tracking method based on model prediction and sliding mode cascade control is designed. First, a kinematics analysis of the fully driven AUV is carried out, and the kinematics and dynamics equations of five degrees of freedom are established. Second, the CFD software ANSYS Fluent is used to simulate the uniform velocity and uniform acceleration of AUV in surge, sway, heave, pitch and yaw degrees of freedom, and solve the main hydrodynamic coefficients required to establish the dynamic model. Then, a novel GA-ACO algorithm based on normal probability interval population division is proposed is proposed. Combined with the constraints of actual control input and state, the algorithm is applied to the outer loop MPC to solve the optimal velocity control sequence, generate the expected velocity command, which is passed to the inner loop. Compared with standard MPC and MPC-GA, this method can reasonably increase the diversity of GA population, improve the local and global search ability of the algorithm, and avoid the problem of falling into local optimal solution caused by QP or GA. Then combined with ACO algorithm, the convergence speed of the algorithm can be accelerated and the global optimal speed control sequence can be obtained for each sampling period. The inner loop uses dynamic SMC to generate the available control input of AUV to ensure the closed-loop tracking along the whole trajectory. A rolling time-domain implementation can be used to recalculate the optimal control input at each sampling instant, compensating for system uncertainties caused by modeling and external disturbances. Finally, two different types of reference desired trajectories are simulated to verify the effectiveness and robustness of the proposed controller under uncertain disturbances in the simulated marine environment. It is improved in reducing the position error of trajectory tracking and increasing the input stability of the controller. In the future research, we will further solve the adverse impact of SMC chattering on the controller, and strengthen the analysis of the impact of the actual marine environment on the control disturbance of AUV and the research on practical problems such as thruster output saturation.

Author Contributions

Conceptualization, H.B. and H.Z.; methodology, H.B.; software, H.B.; formal analysis, H.B. and H.Z.; investigation, H.B. and H.Z.; data curation, H.B.; writing—original draft preparation, H.B.; writing—review and editing, H.B. and H.Z.; visualization, H.B.; supervision, H.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the university-local integration category project “Underwater Vehicles Key Technology R&D Center” and China Scholarship Council (Grant No. 202006680065).

Data Availability Statement

Not applicable.

Acknowledgments

This work was supported by the university-local integration category project “Underwater Vehicles Key Technology R&D Center” and China Scholarship Council (Grant No. 202006680065).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kaya, K.D.; Goren, A.; Yilmaz, S.; Bayramoğlu, K. Determination of operating parameters of an AUV following a preplanned trajectory using hydrodynamic analysis data. Ocean Eng. 2020, 217, 107708. [Google Scholar] [CrossRef]
  2. Yin, J.; Wang, N. Predictive Trajectory Tracking Control of Autonomous Underwater Vehicles Based on Variable Fuzzy Predictor. Int. J. Fuzzy Syst. 2020, 23, 1809–1822. [Google Scholar] [CrossRef]
  3. Gong, P.; Yan, Z.; Zhang, W.; Tang, J. Lyapunov-based model predictive control trajectory tracking for an autonomous underwater vehicle with external disturbances. Ocean Eng. 2021, 232, 109010. [Google Scholar] [CrossRef]
  4. Zhu, C.; Huang, B.; Su, Y.; Zheng, Y.; Zheng, S. Finite-time rotation-matrix-based tracking control for autonomous underwater vehicle with input saturation and actuator faults. Int. Robust Nonlinear Control. 2022, 32, 2925–2949. [Google Scholar] [CrossRef]
  5. Mao, Y.; Gao, F.; Zhang, Q.; Yang, Z. An AUV Target-Tracking Method Combining Imitation Learning and Deep Reinforcement Learning. J. Mar. Sci. Eng. 2022, 10, 383. [Google Scholar] [CrossRef]
  6. Liu, X.; Zhang, M.; Chen, Z. Trajectory tracking control based on a virtual closed-loop system for autonomous underwater vehicles. Int. J. Control. 2020, 93, 2789–2803. [Google Scholar] [CrossRef]
  7. Cook, G.; Zhang, F. Mobile Robots: Navigation, Control and Sensing, Surface Robots and AUVs; John Wiley & Sons: Hoboken, NJ, USA, 2020. [Google Scholar]
  8. Thanh, P.N.N.; Tam, P.M.; Anh, H.P.H. A new approach for three-dimensional trajectory tracking control of under-actuated AUVs with model uncertainties. Ocean Eng. 2021, 228, 108951. [Google Scholar] [CrossRef]
  9. Li, H.; Xie, P.; Yan, W. Receding horizon formation tracking control of constrained underactuated autonomous underwater vehicles. IEEE Trans. Ind. Electron. 2016, 64, 5004–5013. [Google Scholar] [CrossRef]
  10. Fang, Y.; Huang, Z.; Pu, J.; Zhang, J. AUV position tracking and trajectory control based on fast-deployed deep reinforcement learning method. Ocean Eng. 2022, 245, 110452. [Google Scholar] [CrossRef]
  11. Min, F.; Pan, G.; Xu, X. Modeling of autonomous underwater vehicles with multi-propellers based on maximum likelihood method. J. Mar. Sci. Eng. 2020, 8, 407. [Google Scholar] [CrossRef]
  12. Wan, J.; Zheng, Y.; Li, Y.; He, B.; Li, H.; Lv, B.; Wang, Y. Multi-strategy fusion based on sea state codes for AUV motion control. Ocean Eng. 2022, 248, 110600. [Google Scholar] [CrossRef]
  13. Guo, L.; Liu, W.; Li, L.; Lou, Y.; Wang, X.; Liu, Z. Neural Network Non-Singular Terminal Sliding Mode Control for Target Tracking of Underactuated Underwater Robots with Prescribed Performance. J. Mar. Sci. Eng. 2022, 10, 252. [Google Scholar] [CrossRef]
  14. Lyu, D.; Su, H.; Li, Y.; Zhang, Z.; Long, H.; Zhao, J. An Embedded Linear Model Three-Dimensional Fuzzy PID Control System for a Bionic AUV under Wave Disturbance. Math. Probl. Eng. 2022, 2022, 4126595. [Google Scholar] [CrossRef]
  15. Sarhadi, P.; Noei, A.R.; Khosravi, A. Model reference adaptive PID control with anti-windup compensator for an autonomous underwater vehicle. Robot. Auton. Syst. 2016, 83, 87–93. [Google Scholar] [CrossRef]
  16. Han, L.; Tang, G.; Cheng, M.; Huang, H.; Xie, D. Adaptive Nonsingular Fast Terminal Sliding Mode Tracking Control for an Underwater Vehicle-Manipulator System with Extended State Observer. J. Mar. Sci. Eng. 2021, 9, 501. [Google Scholar] [CrossRef]
  17. Khodayari, M.H.; Balochian, S. Modeling and control of autonomous underwater vehicle (AUV) in heading and depth attitude via self-adaptive fuzzy PID controller. J. Mar. Sci. Technol. 2015, 20, 559–578. [Google Scholar] [CrossRef]
  18. Petritoli, E.; Cagnetti, M.; Leccese, F. Simulation of autonomous underwater vehicles (auvs) swarm diffusion. Sensors 2020, 20, 4950. [Google Scholar] [CrossRef]
  19. Li, Y.; Jiang, Y.Q.; Wang, L.F.; Cao, J.; Zhang, G.C. Intelligent PID guidance control for AUV path tracking. J. Cent. South Univ. 2015, 22, 3440–3449. [Google Scholar] [CrossRef]
  20. Li, J.; Du, J.; Chen, C.P. Command-Filtered Robust Adaptive NN Control With the Prescribed Performance for the 3-D Trajectory Tracking of Underactuated AUVs. In IEEE Transactions on Neural Networks and Learning Systems; IEEE: Piscataway, NJ, USA, 2021. [Google Scholar]
  21. Zhang, Y.; Gao, J.; Chen, Y.; Bian, C.; Zhang, F.; Liang, Q. Adaptive neural network control for visual docking of an autonomous underwater vehicle using command filtered backstepping. Int. J. Robust Nonlinear Control. 2022, 32, 4716–4738. [Google Scholar] [CrossRef]
  22. Dincmen, E. A Cooperative Neural Network Control Structure and Its Application for Systems Having Dead-Zone Nonlinearities. Iran. J. Sci. Technol. Trans. Electr. Eng. 2022, 46, 187–203. [Google Scholar] [CrossRef]
  23. Mohammadi, M.; Arefi, M.M.; Vafamand, N.; Kaynak, O. Control of an AUV with completely unknown dynamics and multi-asymmetric input constraints via off-policy reinforcement learning. Neural Comput. Appl. 2021, 34, 5255–5265. [Google Scholar] [CrossRef]
  24. Guo, X.; Yan, W.; Cui, R. Integral reinforcement learning-based adaptive NN control for continuous-time nonlinear MIMO systems with unknown control directions. IEEE Trans. Syst. Man Cybern. Syst. 2019, 50, 4068–4077. [Google Scholar] [CrossRef]
  25. Zhang, J.; Xiang, X.; Zhang, Q.; Li, W. Neural network-based adaptive trajectory tracking control of underactuated AUVs with unknown asymmetrical actuator saturation and unknown dynamics. Ocean Eng. 2020, 218, 108193. [Google Scholar] [CrossRef]
  26. González-García, J.; Narcizo-Nuci, N.A.; García-Valdovinos, L.G.; Salgado-Jiménez, T.; Gómez-Espinosa, A.; Cuan-Urquizo, E.; Cabello, J.A.E. Model-free high order sliding mode control with finite-time tracking for unmanned underwater vehicles. Appl. Sci. 2021, 11, 1836. [Google Scholar] [CrossRef]
  27. Yan, Y.; Yu, S. Sliding mode tracking control of autonomous underwater vehicles with the effect of quantization. Ocean Eng. 2018, 151, 322–328. [Google Scholar] [CrossRef]
  28. Zang, W.; Yao, P.; Song, D. Standoff tracking control of underwater glider to moving target. Appl. Math. Model. 2022, 102, 1–20. [Google Scholar] [CrossRef]
  29. Elmokadem, T.; Zribi, M.; Youcef-Toumi, K. Trajectory tracking sliding mode control of underactuated AUVs. Nonlinear Dyn. 2016, 84, 1079–1091. [Google Scholar] [CrossRef] [Green Version]
  30. Londhe, P.; Patre, B. Adaptive fuzzy sliding mode control for robust trajectory tracking control of an autonomous underwater vehicle. Intell. Serv. Robot. 2019, 12, 87–102. [Google Scholar] [CrossRef]
  31. Zhang, H.; Zhu, D.; Liu, C.; Hu, Z. Tracking fault-tolerant control based on model predictive control for human occupied vehicle in three-dimensional underwater workspace. Ocean Eng. 2022, 249, 110845. [Google Scholar] [CrossRef]
  32. Li, X.; Zhu, D. An adaptive SOM neural network method for distributed formation control of a group of AUVs. IEEE Trans. Ind. Electron. 2018, 65, 8260–8270. [Google Scholar] [CrossRef]
  33. Shen, C.; Shi, Y.; Buckham, B. Integrated path planning and tracking control of an AUV: A unified receding horizon optimization approach. IEEE/ASME Trans. Mechatron. 2016, 22, 1163–1173. [Google Scholar] [CrossRef]
  34. Shen, C.; Buckham, B.; Shi, Y. Modified C/GMRES algorithm for fast nonlinear model predictive tracking control of AUVs. IEEE Trans. Control. Syst. Technol. 2016, 25, 1896–1904. [Google Scholar] [CrossRef]
  35. Zhang, Y.; Liu, X.; Luo, M.; Yang, C. MPC-based 3-D trajectory tracking for an autonomous underwater vehicle with constraints in complex ocean environments. Ocean Eng. 2019, 189, 106309. [Google Scholar] [CrossRef]
  36. Yan, Z.; Gong, P.; Zhang, W.; Wu, W. Model predictive control of autonomous underwater vehicles for trajectory tracking with external disturbances. Ocean Eng. 2020, 217, 107884. [Google Scholar] [CrossRef]
  37. Gan, W.; Zhu, D.; Ji, D. QPSO-model predictive control-based approach to dynamic trajectory tracking control for unmanned underwater vehicles. Ocean Eng. 2018, 158, 208–220. [Google Scholar] [CrossRef]
  38. Zhang, L.; Zhuan, X. Model predictive control method of a parallel electromagnetic isolation system based on the improved genetic algorithm. J. Vib. Control 2020, 26, 2001–2012. [Google Scholar] [CrossRef]
  39. Ji, D.; Wang, R.; Zhai, Y.; Gu, H. Dynamic modeling of quadrotor AUV using a novel CFD simulation. Ocean Eng. 2021, 237, 109651. [Google Scholar] [CrossRef]
Figure 1. Reference frames.
Figure 1. Reference frames.
Sensors 22 04234 g001
Figure 2. Solving method.
Figure 2. Solving method.
Sensors 22 04234 g002
Figure 3. Solution area settings of translational motion.
Figure 3. Solution area settings of translational motion.
Sensors 22 04234 g003
Figure 4. Solution area settings of rotation motion.
Figure 4. Solution area settings of rotation motion.
Sensors 22 04234 g004
Figure 5. Velocity cloud diagrams of the AUV in uniform translational motion.
Figure 5. Velocity cloud diagrams of the AUV in uniform translational motion.
Sensors 22 04234 g005
Figure 6. Curve fitting of uniform translational motion.
Figure 6. Curve fitting of uniform translational motion.
Sensors 22 04234 g006
Figure 7. Velocity cloud diagrams of the AUV in uniform rotational motion.
Figure 7. Velocity cloud diagrams of the AUV in uniform rotational motion.
Sensors 22 04234 g007
Figure 8. Curve fitting of uniform rotational motion.
Figure 8. Curve fitting of uniform rotational motion.
Sensors 22 04234 g008
Figure 9. Velocity cloud diagrams of the AUV in uniformly accelerating translational motion.
Figure 9. Velocity cloud diagrams of the AUV in uniformly accelerating translational motion.
Sensors 22 04234 g009
Figure 10. Curve fitting of uniform accelerating translational motion.
Figure 10. Curve fitting of uniform accelerating translational motion.
Sensors 22 04234 g010aSensors 22 04234 g010b
Figure 11. Velocity cloud diagrams of the AUV in uniformly accelerating rotational motion.
Figure 11. Velocity cloud diagrams of the AUV in uniformly accelerating rotational motion.
Sensors 22 04234 g011
Figure 12. Curve fitting of uniform accelerating rotational motion.
Figure 12. Curve fitting of uniform accelerating rotational motion.
Sensors 22 04234 g012
Figure 13. Diagram of the AUV control framework.
Figure 13. Diagram of the AUV control framework.
Sensors 22 04234 g013
Figure 14. Chromosome coding.
Figure 14. Chromosome coding.
Sensors 22 04234 g014
Figure 15. Results of the normal monitoring of population fitness values.
Figure 15. Results of the normal monitoring of population fitness values.
Sensors 22 04234 g015
Figure 16. AUV trajectory 1 tracking without disturbance.
Figure 16. AUV trajectory 1 tracking without disturbance.
Sensors 22 04234 g016
Figure 17. AUV trajectory 1 tracking error without disturbance.
Figure 17. AUV trajectory 1 tracking error without disturbance.
Sensors 22 04234 g017
Figure 18. Control input of AUV without disturbance for trajectory 1.
Figure 18. Control input of AUV without disturbance for trajectory 1.
Sensors 22 04234 g018
Figure 19. AUV trajectory 1 tracking with random disturbance.
Figure 19. AUV trajectory 1 tracking with random disturbance.
Sensors 22 04234 g019
Figure 20. AUV trajectory 1 tracking error with random disturbance.
Figure 20. AUV trajectory 1 tracking error with random disturbance.
Sensors 22 04234 g020
Figure 21. Control input of AUV with random disturbance for trajectory 1.
Figure 21. Control input of AUV with random disturbance for trajectory 1.
Sensors 22 04234 g021
Figure 22. AUV trajectory 2 tracking without disturbance.
Figure 22. AUV trajectory 2 tracking without disturbance.
Sensors 22 04234 g022
Figure 23. AUV trajectory 2 tracking error without disturbance.
Figure 23. AUV trajectory 2 tracking error without disturbance.
Sensors 22 04234 g023
Figure 24. Control input of AUV without disturbance for trajectory 2.
Figure 24. Control input of AUV without disturbance for trajectory 2.
Sensors 22 04234 g024
Figure 25. AUV trajectory 2 tracking with random disturbance.
Figure 25. AUV trajectory 2 tracking with random disturbance.
Sensors 22 04234 g025
Figure 26. AUV trajectory 2 tracking error with random disturbance.
Figure 26. AUV trajectory 2 tracking error with random disturbance.
Sensors 22 04234 g026
Figure 27. Control input of AUV with random disturbance for trajectory 2.
Figure 27. Control input of AUV with random disturbance for trajectory 2.
Sensors 22 04234 g027
Table 1. AUV parameters.
Table 1. AUV parameters.
ParameterValueParameterValue
Mass84.615 kgDiameter0.3 m
Length1.85 m I y ; I z 24.235 kgm2
Table 2. Values of ANSYS fluent parameters.
Table 2. Values of ANSYS fluent parameters.
Parameter of Translational MotionValue
Fluid area size 8.5 m × 4 m × 4 m
Overall grid controlCurvature control function
Growth rate1.2
Curvature normal angle 18
Number of mesh nodes747,048
Number of mesh elements4,112,607
Parameter of Rotational MotionValue
Fluid area size 5 m × 5 m × 5 m
Rotation area sizeDiameter: 3 m Height: 5 m
Overall grid controlCurvature control function
Growth rate1.2
Curvature normal angle 18
Number of mesh nodes698,224
Number of mesh elements3,348,218
Table 3. Data for uniform translational motion.
Table 3. Data for uniform translational motion.
Velocity (m/s)Force (x) (N)Force (y) (N)Force (z) (N)
0.10.05370.87730.8727
0.20.10815.60445.7074
0.30.42637.83907.9125
0.40.886716.509616.3312
0.51.058321.890022.0917
0.72.216042.306041.9060
1.04.009683.966084.0191
1.37.0015138.3200138.1212
1.58.8106189.7001182.4700
2.015.3730388.4032385.8816
2.524.2423510.7725511.2045
3.034.6884734.2678735.6437
Table 4. Data for uniform rotational motion.
Table 4. Data for uniform rotational motion.
Angular Velocity (Rad/s)Moment (y) (N·m)Moment (z) (N·m)
0.10.34560.3563
0.20.59070.6809
0.31.59081.6358
0.42.50042.5417
0.53.11563.0756
0.65.21035.1967
0.76.66786.7621
0.87.21117.3007
0.98.60178.9889
1.012.445112.5146
Table 5. Viscous hydrodynamic coefficients.
Table 5. Viscous hydrodynamic coefficients.
ParameterValue
X u 0.35 kg / s
Y v 15.11 kg / s
Z w 12.32 kg / s
M q 2.08 kgm 2 / ( s · rad )
N r 2.06 kgm 2 / ( s · rad )
X u u 3.73 kg / s
Y v v 77.45 kg / s
Z w w 78.48 kg / s
M q q 9.57 kgm 2 / rad 2
N r r 9.78 kgm 2 / rad 2
Table 6. Data for uniformly accelerating translational motion.
Table 6. Data for uniformly accelerating translational motion.
Acceleration (m/s2)Force (x) (N)Force (y) (N)Force (z) (N)
0.010.06060.86540.8359
0.020.35611.83642.4069
0.050.91676.54826.9586
0.15.987811.884212.9393
0.28.570319.371119.9455
0.518.916348.511148.9941
1.033.304374.032775.7163
Table 7. Data for uniformly accelerating rotational motion.
Table 7. Data for uniformly accelerating rotational motion.
Angular Acceleration (m/s2)Moment (y) (N·m)Moment (z) (N·m)
0.011.22921.1818
0.021.48771.4067
0.052.23152.1993
0.18.41148.3320
0.211.119111.2121
0.513.122413.5543
Table 8. Inertial hydrodynamic coefficients.
Table 8. Inertial hydrodynamic coefficients.
ParameterValue
X u ˙ 34.63 kg / s
Y v ˙ 79.60 kg / s
Z w ˙ 81.27 kg / s
M q ˙ 32.28 kgm 2 / ( s · rad )
N r ˙ 33.01 kgm 2 / ( s · rad )
Table 9. Population interval division.
Table 9. Population interval division.
Interval123456
Probability families ( 3 σ , 2 σ ) ( 2 σ , σ ) ( σ , 0 ) ( 0 , σ ) ( σ , 2 σ ) ( 2 σ , 3 σ )
Probability2.5%13.5%34%34%13.5%2.5%
Population number5276868275
Table 10. Average position error without disturbance in trajectory 1.
Table 10. Average position error without disturbance in trajectory 1.
Methods (m/s)x (m)y (m)z (m) θ (rad) ψ (rad)
MPC0.20050.19320.23430.12570.1282
MPC-GA0.20110.18810.18810.13310.1016
MPC-GA-ACO0.14310.16540.09990.11780.0987
Table 11. Average position error with random disturbance in trajectory 1.
Table 11. Average position error with random disturbance in trajectory 1.
Methods (m/s)x (m)y (m)z (m) θ (rad) ψ (rad)
MPC0.30110.23520.19010.18590.2225
MPC-GA0.24590.22370.17250.18110.1783
MPC-GA-ACO0.18930.18670.14450.14980.1612
Table 12. Average position error without disturbance in trajectory 2.
Table 12. Average position error without disturbance in trajectory 2.
Methods (m/s)x (m)y (m)z (m) θ (rad) ψ (rad)
MPC0.30660.29610.20050.25170.2011
MPC-GA0.33120.21920.18340.15510.1812
MPC-GA-ACO0.18810.18250.11100.09150.0873
Table 13. Average position error with random disturbance in trajectory 2.
Table 13. Average position error with random disturbance in trajectory 2.
Methods (m/s)x (m)y (m)z (m) θ (rad) ψ (rad)
MPC0.32110.27140.24560.21170.2019
MPC-GA0.30290.23210.17640.17700.2231
MPC-GA-ACO0.19320.18940.17770.09980.1221
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Bao, H.; Zhu, H. Modeling and Trajectory Tracking Model Predictive Control Novel Method of AUV Based on CFD Data. Sensors 2022, 22, 4234. https://doi.org/10.3390/s22114234

AMA Style

Bao H, Zhu H. Modeling and Trajectory Tracking Model Predictive Control Novel Method of AUV Based on CFD Data. Sensors. 2022; 22(11):4234. https://doi.org/10.3390/s22114234

Chicago/Turabian Style

Bao, Han, and Haitao Zhu. 2022. "Modeling and Trajectory Tracking Model Predictive Control Novel Method of AUV Based on CFD Data" Sensors 22, no. 11: 4234. https://doi.org/10.3390/s22114234

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