Next Article in Journal
Feasibility of Observing Cerebrovascular Disease Phenotypes with Smartphone Monitoring: Study Design Considerations for Real-World Studies
Previous Article in Journal
A Wearable Visually Impaired Assistive System Based on Semantic Vision SLAM for Grasping Operation
Previous Article in Special Issue
RU-SLAM: A Robust Deep-Learning Visual Simultaneous Localization and Mapping (SLAM) System for Weakly Textured Underwater Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Under-Actuated Motion Control of Haidou-1 ARV Using Data-Driven, Model-Free Adaptive Sliding Mode Control Method

1
State Key Laboratory of Robotics, Shenyang Institute of Automation, Chinese Academy of Sciences, Shenyang 110016, China
2
Institutes for Robotics and Intelligent Manufacturing, Chinese Academy of Sciences, Shenyang 110169, China
3
Key Laboratory of Marine Robotics, Liaoning Province, Shenyang 110169, China
4
University of Chinese Academy of Sciences, Beijing 100049, China
*
Author to whom correspondence should be addressed.
Sensors 2024, 24(11), 3592; https://doi.org/10.3390/s24113592
Submission received: 9 April 2024 / Revised: 25 May 2024 / Accepted: 31 May 2024 / Published: 2 June 2024
(This article belongs to the Special Issue Sensors, Modeling and Control for Intelligent Marine Robots)

Abstract

:
We propose a data-driven, model-free adaptive sliding mode control (MFASMC) approach to address the Haidou-1 ARV under-actuated motion control problem with uncertainties, including external disturbances and parameter perturbations. Firstly, we analyzed the two main difficulties in the motion control of Haidou-1 ARV. Secondly, in order to address these problems, a MFASMC control method was introduced. It is combined by a model-free adaptive control (MFAC) method and a sliding mode control (SMC) method. The main advantage of the MFAC method is that it relies only on the real-time measurement data of an ARV instead of any mathematical modeling information, and the SMC method guarantees the MFAC method’s fast convergence and low overshooting. The proposed MFASMC control method can maneuver Haidou-1 ARV cruising at the desired forward speed, heading, and depth, even when the dynamic parameters of the ARV vary widely and external disturbances exist. It also addresses the problem of under-actuated motion control for the Haidou-1 ARV. Finally, the simulation results, including comparisons with a PID method and the MFAC method, demonstrate the effectiveness of our proposed method.

1. Introduction

Underwater robotic vehicles (URVs) are widely used in the ocean engineering field. Usually, we can classify them into remotely operated underwater vehicles (ROVs) [1] and autonomous underwater vehicles (AUVs) [2]. Over the last few decades, AUVs have been widely used in various marine activities, such as data collection [3,4], mapping of underwater topography [5], long oil pipe inspection [6], and even naval mine detection [7]. An autonomous and remotely-operated vehicle (ARV) is a new type of hybrid underwater vehicle that combines the characteristics of an autonomous underwater vehicle (AUV) and remotely controlled vehicle (ROV) [8]. In contrast to a regular AUV or ROV, an ARV can not only conduct large-scale underwater surveys but also conduct precise investigations and operations in specific areas without any mechanical structure change. A typical ARV survey usually follows an “autonomously search—land on and sampling—autonomously search” paradigm [9].
Haidou-1 ARV [10] is a full-ocean unmanned underwater vehicle capable of diving to 11,000 m. It was designed by Shenyang Institute of Automation, CAS, and is shown in Figure 1. It has dived up to 10,908 m and completed scientific expeditions to the Challenger Deep in the Mariana Trench in 2020 and 2021.
In order to accomplish particular tasks successfully, motion control technology is a very critical technology for Haidou-1 ARV. However, the motion control of the Haidou-1 ARV is challenging for the following reasons: (1) It is very hard to establish an accurate mathematical model of an ARV. An ARV’s dynamic system is quite complex due to the high nonlinearity, strong coupling, and hydrodynamic coefficients uncertainty. In addition, it is susceptible to unknown disturbances, such as sea currents and waves, resulting in oscillations and overshoots during control. (2) The working mode of the Haidou-1 ARV results in its various residual buoyancy states. The type, weight, and placement of the samples taken by the ARV varies greatly during each sampling session. This leads to changes in the physical parameters, which in turn leads to great changes in the hull hydrodynamic coefficient, affecting the stability and maneuverability of the ARV. (3) In order to conserve energy, extend operation time, and save space for more samples, the Haidou-1 ARV employs rotating propellers and under-actuated control, which undoubtedly increases the difficulty of control.
Therefore, the model-based control (MBC) methods (relying on accurate mathematical models), such as feedback linearization control and adaptive control, are difficult to use for a Haidou-1 ARV motion control system. It is difficult to ensure the stability and robustness of the control system without an accurate mathematical model. To address the above problems, we need a data-driven control method to address the Haidou-1 ARV motion control problem, which does not require any mathematical modeling information of an ARV.
Data-driven control methods are defined as the controller being designed with the direct use of the I/O data of the controlled system and the knowledge gained through data processing but no explicit mathematical model information of the controlled system [11], e.g., PID control [12], model-free adaptive control (MFAC) [13], correlation-based tuning control (CbT) [14], lazy learning control (LL) [15], iterative feedback tuning control (IFT) [16], etc. The PID control method is the simplest and most commonly used data-driven control method [17]. However, as the parameters of the controlled system change, the parameters of the PID controller should also be readjusted, and the adjustment of control parameters is more dependent on engineering experience. In addition, the PID method is more commonly applied to linear systems [18]. It is not suitable for the Haidou-1 ARV control system, which has high nonlinearity, time-varying, and structural changes.
The MFAC [19] method is an effective data-driven control method for nonlinear control systems. The MFAC method is perhaps the best solution to Haidou-1 ARV motion control in that: (1) It does not require any mathematical model information about the ARV, which is crucial for Haidou-1 ARV motion control, whose mathematical model is very hard to establish. (2) The MFAC method does not require any external test signals; it is simple but has a strong robustness [19]. (3) A number of MFAC applications have been reported in many fields, but few applications in robotics [20,21,22,23].
However, the conventional MFAC method suffers from drawbacks such as overshoot, oscillation, and slow convergence, which are caused by inevitable dynamic linearization error. To address the problem, we need to improve the adaptation capabilities of MFAC method. The sliding-mode control (SMC) [24,25] is perhaps the best solution because of the following: (1) Since SMC designs the system’s sliding-mode based on the desired dynamic characteristics of the system instead of system parameters and disturbances, the SMC has the features of insensitivity to parameter variations, fast response, simple physical implementation, etc. [26]. (2) SMC has been successfully applied in multiple different fields [27,28,29,30]. Therefore, SMC is an ideal algorithm that can improve the performance of MFAC method.
Drawing upon the aforementioned research findings, a data-driven, model-free adaptive sliding mode control (MFASMC) approach is proposed in this paper to address the Haidou-1 ARV motion control problem. The specific contributions of this paper are mainly in three aspects:
  • Compared with the traditional MFAC methods used in [20,21,22,23], this paper further incorporates a discrete sliding mode control (SMC) method to enhance the system’s ability to withstand parameter uncertainties and external disturbances. The SMC method also guarantees MFAC method’s fast convergence and low overshooting.
  • This paper analyzes two major difficulties in ARV motion control, i.e., various mathematical model states and the strong coupling effect in depth control. The method in this paper does not rely on any mathematical modeling information and is a data-driven control method. Even if the dynamic parameters of the ARV vary over a wide range and there are external disturbances, the proposed control method can maneuver the Haidou-1 ARV cruising at the desired forward speed, heading, and depth. Simulation outcomes of the proposed approach are contrasted with those of the PID control and MFAC control method. Compared results show that the proposed MFASMC method has better tracking performance for the ARV motion control system in the presence of disturbances.
  • The control method in this paper can be implemented not only on ARVs but can also be extended to AUVs and other types of underwater robotic vehicles.
The rest of this paper is structured as follows: Section 2 builds the dynamical model of Haidou-1 ARV and analyzes two main difficulties in motion control of Haidou-1 ARV. Section 3 designs the MFASMC method. Section 4 provides the simulation studies. Conclusions are given in Section 5.

2. Dynamical Model and Analysis of Haidou-1 ARV Motion Control

The main physical information of the Haidou-1 ARV is shown in Table 1.
The arrangement of Haidou-1 ARV motion control system is shown in Figure 2. Two main thrusters are fixed on the rotating elevators at the stern. The elevators are driven by rudder motors and can be controlled independently, with a rotation angle of ±90 degrees. Two fixed vertical thrusters are located at the front.

2.1. Kinematics

As shown in Figure 3, we define two coordinate frames named North-East-Down coordinate system and body-fixed frame [31,32]. We set the origin of the body-fixed frame at Haidou-1 ARV’s center of buoyancy. The main kinematics parameters of Haidou-1 ARV in six degrees of freedom are shown in Table 2.
We have following vectors:
η 1 = [ x y z ] ,   η 2 = [ ϕ θ ψ ] ,   η = [ η 1 η 2 ] V 1 = [ u v w ] ,   V 2 = [ p q r ] ,   V = [ V 1 V 2 ] F 1 = [ X Y Z ] ,   F 2 = [ K M N ] ,   F = [ F 1 F 2 ]
where η is the position and Euler angle vector, V is the linear and angular velocities vector, and F is the forces and moment vector.
We have the kinematics model as follows:
[ η 1 η 2 ] = [ R 1 ( η 2 ) 0 3 × 3 0 3 × 3 R 2 ( η 2 ) ]
in which
R 1 ( η 2 ) = [ c ψ c θ c ψ s θ s ϕ s ψ c ϕ s ψ s ϕ + c ψ c ϕ s θ s ψ c θ c ψ c ϕ + s ψ s θ s ϕ s θ s ψ c ϕ c ψ s ϕ s θ c θ s ϕ c θ c ϕ ] R 2 ( η 2 ) = [ 1 s ϕ t θ c ϕ t θ 0 c ϕ s ϕ 0 s ϕ / c θ c ϕ / c θ ]
And in which s = sin , c = cos , and t = tan .

2.2. Dynamics

The six-degree-of-freedom dynamics model of the Haidou-1 ARV is as follows [32]:
M T = C ( V ) V D ( V ) V G ( η 2 ) + F t h r u s t + F r u d d e r + F e n v
where M T is the total mass matrix, C ( V ) is the Coriolis–centripetal matrix, D ( V ) is the hydrodynamic damping matrix, G ( η 2 ) is the restoring force matrix, F t h r u s t are the thruster forces, F r u d d e r are the rudder forces, F e n v are the environmental forces including wave forces and wind forces, and V = [ u v w p q r ] T is the linear and angular velocities vector.
F t h r u s t can be expressed as the following equation:
F t h r u s t = [ F s L x + F s R x 0 F s L y F s R y + F b L + F b R 0 F s L x z s t n + F s R x z s t n + F s L y x s t n + F s R y x s t n F b L x b o w F b R x b o w F s L x y s t n F s R x y s t n ]
where F s L x = F s L cos ( d s L ) is the projection of left main thruster force F s L in the x direction, d s L is the angle of left elevator, F s R x = F s R cos ( d s R ) is the projection of right main thruster force F s R in the x direction, d s R is the angle of right elevator, F s L y = F s L sin ( d s L ) is the projection of left main thruster force F s L in the y direction, F s R y = F s R sin ( d s R ) is the projection of right main thruster force F s R in the y direction, x s t n , y s t n , and z s t n are the coordinates of the main thruster in the body-fixed frame, and x b o w is the x-direction coordinates of the vertical thruster in the body-fixed frame.
T s L M a t r i x can be expressed as the following:
T s L M a t r i x = [ J s L 2 J s L 1 ]
J s L is the advance coefficient and can be expressed as the following:
J s L = u cos ( d s L ) / ( D n s L )
where u is the forward speed of the ARV, D is the diameter of the thruster, and n s L is the speed of the left main thruster.
The right main thruster force matrix T s R M a t r i x is similar to the T s L M a t r i x . The T b L M a t r i x can be expressed as follows:
T b L M a t r i x = [ n b L 3 n b L 2 n b L ]
where n b L is the speed of the left vertical thruster.
The right vertical thruster force matrix T b R M a t r i x is similar to the T b L M a t r i x .
F r u d d e r can be expressed as follows:
F r u d d e r = r d M a t r i x r d C o e f f M a t r i x
where r d M a t r i x is the rudder force matrix, which can be expressed as follows:
r d M a t r i x = [ u 2 d s R 2 u 2 d s L 2 u 2 d s R u 2 d s L ]
r d C o e f f M a t r i x is the rudder force coefficient matrix which can be obtained by a CFD simulation.

2.3. Analysis of Haidou-1 ARV Motion Control

The principle of Haidou-1 ARV motion control system is shown in Figure 4. Haidou-1 ARV can cruise at a desired depth, heading, and forward speed near the seabed. We can decouple the ARV motion into a horizontal plane and vertical plane. In the horizontal plane we need to control the heading and forward speed, in the vertical plane we need to control the depth. The heading control and forward speed control are realized by the two main thrusters cooperating differentially, as shown in Figure 5. In Figure 4, the output of heading and forward speed controller in horizontal plane is the desired propeller speed.
Currently, the vertical plane motion control of the Haidou-1 ARV relies on twin fixed vertical thrusters located at the front and two rotated elevators with thrusters fixed on, as shown in Figure 6a. The advantage of this method is its simplicity of implementation. However, the use of vertical thrusters consumes more energy. There are two reasons for this phenomenon: Firstly, the direction of the incoming current is perpendicular to the direction of the vertical thrusters, which results in a lower efficiency of the vertical propellers compared to that of the open-water propeller. Secondly, because the vertical thrusters are tightly attached to the body of Haidou-1 ARV, the rapid rotation of the vertical propellers can cause a great change in the flow field near Haidou-1 ARV, which generates a larger pressure drag, as well as sailing drag, so it will consume more energy for the main thrusters to maintain the ARV’s constant depth and constant forward speed. For the above reasons, this paper mainly focuses on the study of the Haidou-1 ARV, which only uses elevators and rotated main thrusters at the stern to finish under-actuated motion control, as shown in Figure 6b. As shown in Equation 5, we set T b L M a t r i x and T b R M a t r i x to zero. After simulation by CFD, we found that this method can reduce propulsion system energy consumption by 58.3% compared with using the vertical thrusters method.
There are two main difficulties in the motion control of Haidou-1 ARV.
  • The working mode of ARV leads to its various mathematical model states. Haidou-1 ARV has the ability of grabbing up to 30 kg samples. When an ARV grasps objects or takes sediment samples with a manipulator, the collected samples will cause changes in the center of gravity, metacentric height, hydrostatics parameters and residual buoyancy of the ARV, which will lead to corresponding changes in the mathematical model of the ARV and can be seen as a disturbance to ARV motion control. In Figure 3, when the center of buoyancy of Haidou-1 ARV is set to (0, 0, 0), then the coordinates of its center of gravity are 0 mm, 0 mm, and 43.95 mm. When Haidou-1 ARV grasps a 30 kg sample, the coordinates of center of buoyancy change to 5.2 mm, 0.9 mm, and 2.1 mm, and the coordinates of its center of gravity change to 15.5 mm, 2.5 mm, and 38.05 mm. When the metacentric height is reduced by 8 mm, the great change in the metacentric height will greatly increase the difficulty of control.
  • There is coupling between Haidou-1 ARV’s six degrees of freedom. The coupling effect is stronger when we only use rotated thrusters to realize depth control. Because we only use elevators and rotated main thrusters to accomplish depth control, when there is a deviation between the actual depth and the required depth, we need to adjust the elevator angle and main thruster speed to approach the desired depth, which will inevitably cause a change in the forward speed of an ARV. The change in forward speed leads to changes in the surrounding flow velocity, which in turn causes variations in the forces acting on the elevators and changes in the forces of thrusters (Equation (9)). In order to achieve simultaneous depth control and forward speed control, it is inevitable to frequently adjust the angle of the elevators and the speed of the thrusters over a long period of time. This may lead to significant overshooting and even cause oscillations or failure to converge, resulting in instability in ARV motion control.
Considering the difficulties in the motion control of the Haidou-1 ARV mentioned above, we next discuss the data-driven MFASMC method.

3. MFASMC Controller Design

In order to design MFASMC controller, first we need to design MFAC controller. The underlying idea of MFAC method is that we use an equivalent dynamic linearization data model with a novel concept called pseudo-partial derivative (PPD) at each operation point to replace the discrete-time nonlinear system; then we estimate the PPD by only using the I/O information; and finally, we design the one-step-forward controller which is called the MFAC controller [11]. There are three dynamic linearization data models. Reference [33] converted the unmanned surface vehicle (USV) input and output data into a compact form dynamic linearization (CFDL) model. Reference [34] proposed the model-free adaptive fault-tolerant control based on a partial form dynamic linearization (PFDL) model for high-speed trains with traction/braking force constraints and actuator faults. However, the CFDL and PFDL method only considers the relationship between the output change of the system at the next moment and the input change at the current moment. However, the output signal of the ARV motion control system depends not only on the control input at a certain moment. In this paper, we use the full form dynamic linearization (FFDL) method to investigate the ARV motion control problem. In the FFDL method, the influence of the input signal and output signal in a fixed length sliding time on the output signal at the next moment can be taken into account when the data is linearized.
Section 3 is structured as follows: In Section 3.1 we change the ARV motion control system to an equivalent dynamic linearization data model using the FFDL method. In Section 3.2 the FFDL-MFAC scheme design is given based on the FFDL data model in Section 3.1. In Section 3.3, we will introduce the SMC method to form the MFASMC control method.

3.1. Full-Form Dynamic Linearization Method

A SISO discrete-time nonlinear system can be expressed as follows:
y ( k + 1 ) = f ( y ( k ) , , y ( k n y ) , u ( k ) , , u ( k n u ) )
where y ( k ) and u ( k ) , respectively, are the system output and input at time k , n y and n u the unknown orders, and f ( ) is an unknown nonlinear function. Haidou-1 ARV motion system can be expressed by Equation (11).
We define H L y , L u ( k ) R L y + L u , then we have
H L y , L u ( k ) = [ y ( k ) , , y ( k L y + 1 ) , u ( k ) , , u ( k L u + 1 ) ] T
where k 0 , H L y , L u ( k ) = 0 L y , L u , and where L y and L u ( 0 L y n y , 0 L u n u ) are the pseudo-order of the system output and input, respectively.
Before introducing FFDL, we make the following assumptions [31]:
Assumption 1.
The partial derivatives of  f ( ) with respect to every variable are continuous.
Assumption 2.
System (11) is generalized Lipschitz, that is,  | y ( k 1 + 1 ) y ( k 2 + 1 ) | b H L y , L u ( k 1 ) H L y , L u ( k 2 ) , where  y ( k i + 1 ) = f ( y ( k i ) , , y ( k i n y ) , u ( k i ) , , u ( k i n u ) ) , and  i = 1 , 2 ,  b > 0 .
From a practical point of view, the above assumptions are reasonable and acceptable. Assumption 1 is a typical constraint on general nonlinear systems in control system design. Assumption 2 places a limitation on the rate of change of the controller output. The Haidou-1 ARV motion system can meet these assumptions.
For the nonlinear system (11), satisfying Assumption 1 and 2, for L y and L u , there exists a parameter vector, ϕ ( k ) R L y + L u , called the pseudo-gradient (PG), such that system (11) can be transformed into the following equivalent FFDL description:
Δ y ( k + 1 ) = ϕ ( k ) Δ H ( k )
where for any k , ϕ ( k ) = [ ϕ 1 ( k ) , , ϕ L y ( k ) , ϕ L y + 1 ( k ) ϕ L y + L u ( k ) ] is bounded.

3.2. FFDL-MFAC Method

Consider the following control input criterion function:
J ( u ( k ) ) = | y ( k + 1 ) y ( k + 1 ) | 2 + λ | u ( k ) u ( k 1 ) | 2
where y ( k + 1 ) is the desired output signal, and λ > 0 is a weighting factor.
Substituting (13) into (14), differentiating with respect to u ( k ) , and letting it zero, we obtain the following:
u ( k ) = u ( k 1 ) + ρ L y + 1 ϕ L y + 1 ( k ) ( y ( k + 1 ) y ( k ) ) λ + | ϕ L y + 1 ( k ) | 2 ϕ L y + 1 ( k ) ( i = 1 L y ρ i ϕ i ( k ) Δ y ( k i + 1 ) + i = L y + 2 L y + L u ρ i ϕ i ( k ) Δ u ( k L y i + 1 ) ) λ + | ϕ L y + 1 ( k ) | 2
We define the index function for the PG estimation as follows:
J ( ϕ ( k ) ) = | y ( k ) y ( k 1 ) ϕ T ( k ) Δ H ( k 1 ) | 2 + μ ϕ ( k ) ϕ ( k 1 ) 2
where μ > 0 is a weighting factor, and ϕ ( k ) is the estimation value of ϕ ( k ) .
Differentiating (16) with respect to ϕ f , L y , L u ( k ) , and letting it zero, we obtain the following:
ϕ ( k ) = ϕ ( k 1 ) + η Δ H ( k 1 ) ( Δ y ( k ) ϕ ( k 1 ) Δ H ( k 1 ) ) μ + Δ H ( k 1 ) 2
ϕ ( k ) = ϕ ( 1 )   if   ϕ ( k ) ε   or Δ H ( k 1 ) ε   or   s i g n ( ϕ L y + 1 ( k ) ) s i g n ( ϕ L y + 1 ( 1 ) )
where η ( 0 , 2 ] is a step-size constant, μ > 0 is called the weight coefficient, and ϕ ( 1 ) is the initial value of ϕ ( k ) .
Equation (17) is the PG estimation algorithm. Equation (18) is the PG reset algorithm.
Based on Equations (15) and (17), the FFDL-MFAC [35] approach can be expressed as the following:
u M F A ( k ) = u M F A ( k 1 ) + ρ L y + 1 ( k ) ϕ L y + 1 ( k ) ( y ( k + 1 ) y ( k ) ) λ + | ϕ L y + 1 ( k ) | 2 ϕ L y + 1 ( k ) ( i = 1 L y ρ i ϕ i ( k ) Δ y ( k i + 1 ) + i = L y + 2 L y + L u ρ i ϕ i ( k ) Δ u ( k L y i + 1 ) ) λ + | ϕ L y + 1 ( k ) | 2
where λ > 0 is called the weight factor, ρ i ( 0 , 1 ] is a step-size constant and i = 1 , 2 , , L y + L u , ε is a sufficiently small positive number.
Equation (19) is the FFDL-MFAC method control law.
The FFDL-MFAC method only uses the I/O data to estimate the PG value; the estimated PG value and the one-step-forward error are substituted into the control law. The control process is shown in Figure 7.

3.3. MFASMC Method Design

The output of MFAC method is donated as y M F A ( k ) .
For the model (13), we set the discrete sliding surface as the following:
s ( k ) = e ( k )
so,
s ( k + 1 ) = e ( k + 1 )
We can transform Equation (13) into the following:
Δ y ( k + 1 ) = i = 1 L y ϕ i ( k ) Δ y ( k i + 1 ) + i = L y + 2 L y + L u ϕ i ( k ) Δ u ( k + L y i + 1 ) + ϕ L y + 1 ( k ) Δ u ( k )
The reaching law [36] is given as follows:
s ( k + 1 ) = s ( k ) q 1 h s ( k ) q 2 h s i g α ( s ( k ) )
where s i g α ( s ( k ) ) = sgn ( s ( k ) ) | s ( k ) | α and 0 < q 1 h < 1 , 0 < q 2 h < 1 , 0 < α < 1 . T is the discrete-time sample period. Substituting Equations (21) and (22) into Equation (23), gives the following:
Δ u S M C ( k ) = 1 ϕ L y + 1 ( k ) [ ( 1 q 1 h ) s ( k ) q 2 h s i g α ( s ( k ) ) i = 1 L y ϕ i ( k ) Δ y ( k i + 1 ) i = L y + 2 L y + L u ϕ i ( k ) Δ u ( k + L y i + 1 ) ]
The final MFASMC control law is Equation (19) plus Equation (24).
u ( k ) = u M F A ( k ) + u S M C ( k )
A MFASMC motion control block diagram is illustrated in Figure 8.

4. Simulation

To validate the effectiveness of the MFASMC controller proposed in this paper for Haidou-1 ARV motion control, simulation experiments were designed for multiple scenarios. The simulation model adopts the Haidou-1 ARV six-degree-of-freedom hydrodynamic model in [37].

4.1. Horizontal Plane Motion Simulation

The horizontal plane motion includes directional and constant speed navigation. The experimental scenario we designed is that the ARV performs stepwise steering maneuvers of ±20° and ±90° at a speed of 1 knot, corresponding to small-scale and large-scale steering movements, respectively. The time interval for a 20° heading step is 35 s, and the time interval for a 90° heading step is 20 s. The control cycle is selected as 0.5 s, consistent with the actual control cycle of the ARV. The pseudo-order selection for MFASMC is L y = 2 and L u = 1 . The main control parameters of heading control and speed control are shown in Table 3. The heading step response curve and forward speed response curve are shown in Figure 9. The performance index of heading controller step response is shown in Table 4.
From Figure 9 and Table 4, we note that all three methods can achieve the control effect under undisturbed conditions. MFASMC and MFAC exhibit similar response performance, MFASMC has a larger overshoot in the 20° step steering maneuver but has a shorter adjusting time in the 90° step steering maneuver. In contrast, under the action of PID, a larger overshoot and longer adjusting time appear.
In order to further analyze the performance of the three controllers, we consider the conditions of the hydrodynamic coefficients change and environmental disturbances. For example, ARV replaced the installed payload equipment and constant disturbances caused by sea currents. We add a constant disturbance of 20 Nm in the yaw direction. In addition, we choose three hydrodynamic coefficients that have the most significant impact on control effectiveness I z , N r , and N r | r | , reducing the values by 80%. The control performances of the three methods are shown in Figure 10. The performance index of heading controller step response is shown in Table 5.
By analyzing the response curves in Figure 10 and the performance indicators in Table 5, it can be observed that both PID and MFAC exhibit significant overshoot, and the adjustment time is noticeably prolonged, especially the overshoot of PID reaches to 183.1%. It implies that PID does not show a good robustness and adaptability once external disturbances exist. In contrast, despite the constant disturbance and hydrodynamic coefficients change, MFASMC still maintains a consistent control performance. MFASMC maintains less than 2% overshoot and a shorter adjusting time.
From simulation results above, we can find that compared with PID method and MFAC method, the MFASMC control method for ARV heading and forward speed control has better control performance, though the dynamic parameters of an ARV vary over a wide range and external disturbances exist. The proposed MFASMC control method has strong robustness and adaptability.

4.2. Vertical Plane Control Simulation

This section will show the simulations of Haidou-1 ARV under-actuated depth control using the three control methods. The experimental scenario we designed includes the Haidou-1 ARV operation with a stepwise steering and constant forward speed, as discussed in Section 4.1. At the beginning of this maneuver the Haidou-1 ARV was at the surface; when simulation starts, we set the command depth to 5 m, at t = 40 s, the command depth changes to 10 m. The Haidou-1 ARV only used rotating propellers to finish under-actuated depth control, this method can save energy, increase operational duration, and save space for placing more samples on the ARV.
The pseudo-order selection for MFASMC is L y = 2 and L u = 1 . The main control parameters of depth control are set as Table 6. Figure 11 shows some simulation results obtained during depth changing maneuvers. Table 7 shows the performance index of the controller step response.
From Figure 11 and Table 7, we note that all three of the control methods can be implemented using only rotated propellers to achieve Haidou-1 ARV depth control under undisturbed conditions. MFASMC and MFAC exhibit a similar response performance. Compared with PID, MFASMC and MFAC have smaller overshoots but longer adjusting time.
In order to further analyze the performance of the three controllers, consider the condition of the hydrodynamic coefficients change and environmental disturbances. For example, the ARV finishes sampling and restarts an autonomous search. We add a constant disturbance of 30 kg in the heave direction and reduce the metacentric height of the ARV by 20%. The control performances of the three methods are shown in Figure 12. The performance index of the depth controller step response is shown in Table 8.
By analyzing the response curves in Figure 12 and the performance indicators in Table 8, it can be observed that due to the influence of the model parameter mismatch, the PID exhibits significant oscillations, and the overshoot reaches to 37.4%. In contrast, despite the constant disturbance, both the MFAC and MFASMC can achieve the control effect under disturbed conditions. But MFAC exhibits larger overshoot up to 62% and longer adjusting time. MFASMC still maintains a consistent control performance. Compared with the undisturbed condition, the overshoot and adjusting time of MFASMC experience little change with the stochastic model parameter perturbation and environmental disturbances.
From the simulation results above, we find that for the Haidou-1 ARV under-actuated depth control problem, compared with PID method and MFAC method, the MFASMC method achieves a better performance, though the dynamic parameters of an ARV vary over a wide range and external disturbances. The proposed MFASMC control method has a strong robustness and adaptability.

5. Conclusions

In this study, we propose a data-driven, model-free adaptive sliding mode control (MFASMC) approach to address the Haidou-1 ARV motion control problem with uncertainties. The following conclusions can be obtained through simulation results:
  • The theoretical analysis of the Haidou-1 ARV motion control problem indicates that it will reduce propulsion system energy consumption greatly if we only use the elevators and the rotated main thrusters at the stern to finish under-actuated motion control. The difficulties of the ARV motion control can be summarized as a great hydrodynamic coefficients change and a strong coupling effect.
  • To address the above problem, we propose the MFASMC method. We theoretically analyzed the working principles of this method. The MFAC method relies only on the real-time measurement data of an ARV instead of any mathematical modeling information, and the SMC method guarantees the MFAC method’s fast convergence and low overshooting. It is an ideal method to deal with Haidou-1 ARV’s motion control problem.
  • The simulation results show that compared with PID and MFAC methods, though the hydrodynamic coefficients change and there are environmental disturbances, MFASMC still has good control performance and shows features of strong robustness and adaptability. It can also achieve the goal that Haidou-1 ARV under-actuated motion control only use the elevators and main thrusters, so it is feasible and effective for Haidou-1 ARV motion control. Haidou-1 ARV can cruise at the desired forward speed, heading, and depth even when the dynamic parameters of the ARV vary over a wide range and external disturbances exist.

Author Contributions

Conceptualization, J.L., Y.T. and H.Z.; methodology, Y.L.; software, J.L. and J.W.; validation, J.L. and Y.T.; formal analysis, J.L., Y.T. and R.D.; investigation, J.L. and Y.T.; resources, J.L., Y.T. and H.Z.; data curation, J.L.; writing—original draft preparation, J.L. and H.Z.; writing—review and editing, Y.T.; visualization, J.L.; supervision, Y.T.; funding acquisition, Y.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Key Research and Development Project under Grant Nos. 2023YFC2813000 and 2022YFF1400503, the National Natural Science Foundation of China under Grant No. 62173320, and Youth Innovation Promotion Association of Chinese Academy of Sciences under Grant No. 2022198.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data are contained within the article.

Acknowledgments

The authors express their gratitude to all of their colleagues in the Haidou-1 ARV Group in the Department of Underwater Robotics, at the Shenyang Institute of Automation, Chinese Academy of Sciences. We thank all of the participants in the experiment at the Mariana Trench in 2020 and 2021.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Chin, C.S.; Lau, M.W.S.; Low, E.; Seet, G.G.L. Robust and decoupled cascaded control system of underwater robotic vehicle for stabilization and pipeline tracking. Proc. Inst. Mech. Eng. Part I J. Syst. Control Eng. 2008, 222, 261–278. [Google Scholar] [CrossRef]
  2. Crowell, J. Design challenges of a next generation small AUV. In Proceedings of the 2013 OCEANS-MTS, San Diego, CA, USA, 17 February 2014; pp. 1–5. [Google Scholar]
  3. Hou, X.; Wang, J.; Bai, T.; Deng, Y.; Ren, Y.; Hanzo, L. Environment-Aware AUV Trajectory Design and Resource Management for Multi-Tier Underwater Computing. IEEE J. Sel. Areas Commun. 2023, 41, 474–490. [Google Scholar] [CrossRef]
  4. Huang, M.; Zhang, K.; Zeng, Z.; Wang, T.; Liu, Y. An AUV-Assisted Data Gathering Scheme Based on Clustering and Matrix Completion for Smart Ocean. IEEE Internet Things J. 2020, 7, 9904–9918. [Google Scholar] [CrossRef]
  5. Carrasco, P.L.N.; Bonin-Font, F.; Codina, G. Stereo graph-SLAM for autonomous underwater vehicles. Intell. Auton. Syst. 2016, 302, 351–360. [Google Scholar]
  6. Billingham, L. The role of inspection and intervention of AUVs in support of the oil field of the future. J. Offshore Technol. 2004, 12, 47. [Google Scholar]
  7. Zhang, F.; Marani, G.; Smith, R.N.; Choi, H.T. Future Trends in Marine Robotics. IEEE Robot. Autom. Mag. 2015, 22, 14–122. [Google Scholar] [CrossRef]
  8. Li, S.; Zeng, J.; Wang, Y. Navigation Under the Arctic Ice by Autonomous & Remotely Operated Underwater Vehicle. Robot 2011, 33, 509–512. [Google Scholar]
  9. Tang, Y.; Wang, J.; Lu, Y.; Yao, Z. Parametric Design Method and Experimental Research on Haidou Full-depth Ocean Autonomous and Remotely-operated Vehicle. Robot 2019, 41, 697–705. [Google Scholar]
  10. Wang, J.; Tang, Y.; Li, S.; Lu, Y.; Li, J.; Liu, T.; Jiang, Z.; Chen, C.; Cheng, Y.; Yu, D.; et al. The Haidou-1 hybrid underwater vehicle for the Mariana Trench science exploration to 10,908 m depth. J. Field Robot. 2024, 41, 1054–1079. [Google Scholar] [CrossRef]
  11. Hou, Z.; Wang, Z. From model-based control to data-driven control: Survey, classification and perspective. Inf. Sci. 2013, 235, 3–35. [Google Scholar] [CrossRef]
  12. Amoroso, C.; Liverani, A.; Francia, D.; Ceruti, A. Dynamics augmentation for high speed flying yacht hulls through pid control of foiling appendages. Ocean Eng. 2021, 221, 108115. [Google Scholar] [CrossRef]
  13. Hou, Z. The Parameter Identification, Adaptive Control and Model Free Learning Adaptive Control for Nonlinear Systems. Ph.D. Thesis, Northeastern University, Shenyang, China, 1994. [Google Scholar]
  14. Mišković, L.; Karimi, A.; Bonvin, D.; Gevers, M. Correlation-based tuning of decoupling multivariable controllers. Automatica 2007, 43, 1481–1494. [Google Scholar] [CrossRef]
  15. Wang, K.; Zhang, Z.; Wu, X.; Zhang, L. Multi-class object detection in tunnels from 3D point clouds: An auto-optimized lazy learning approach. Adv. Eng. Inform. 2022, 52, 101543. [Google Scholar] [CrossRef]
  16. Takano, Y.; Masuda, S. Iterative Feedback Tuning for regulatory control systems with measurable disturbances. IFAC PapersOnline 2021, 54, 245–250. [Google Scholar] [CrossRef]
  17. Lee, D.; Lee, S.J.; Yim, S.C. Reinforcement learning-based adaptive pid controller for dps. Ocean Eng. 2020, 216, 108053. [Google Scholar] [CrossRef]
  18. Diene, O.; Bhaya, A. Design of discrete-time adaptive PID controllers for a class of linear integrator systems. IFAC Proc. Vol. 2011, 44, 11344–11349. [Google Scholar] [CrossRef]
  19. Hou, Z.; Jin, S. A novel data-driven control approach for a class of discrete-time nonlinear systems. IEEE Trans. Control Syst. Technol. 2011, 19, 1549–1558. [Google Scholar] [CrossRef]
  20. Zhang, H.; Zhou, J.; Sun, Q.; Guerrero, J.; Ma, D. Data-driven control for interlinked AC/DC microgrids via model-free adaptive control and dual-droop control. IEEE Trans. Smart Grid 2017, 8, 557–571. [Google Scholar] [CrossRef]
  21. Zhu, Y.; Hou, Z. Controller compact form dynamic linearization based model free adaptive control. In Proceedings of the Decision & Control, Maui, HI, USA, 10–13 December 2012; pp. 4817–4822. [Google Scholar]
  22. Hou, Z.; Liu, S.; Tian, T. Lazy-learning-based data-driven model-free adaptive predictive control for a class of discrete-time nonlinear systems. IEEE Trans. Neural Netw. Learn. Syst. 2017, 28, 1914–1928. [Google Scholar] [CrossRef]
  23. Li, H.; Ning, X.; Li, W. Implementation of a MFAC based position sensorless drive for high speed BLDC motors with nonideal back EMF. ISA Trans. 2017, 67, 348–355. [Google Scholar] [CrossRef]
  24. Tanakitkorn, K.; Wilson, P.A.; Turnock, S.R.; Phillips, A.B. Sliding mode heading control of an overactuated, hovercapable autonomous underwater vehicle with experimental verification. J. Field Robot. 2018, 35, 396–415. [Google Scholar] [CrossRef]
  25. Zhang, Y.Y.; Gao, L.E.; Liu, W.D. Research on control method of AUV terminal sliding mode variable structure. In Proceedings of the International Conference on Robotics and Automation Sciences, Hong Kong, China, 26–29 August 2017. [Google Scholar]
  26. Yoerger, D.; Slotine, J. Robust trajectory control of underwater vehicles. IEEE J. Ocean. Eng. 1985, 10, 458–470. [Google Scholar] [CrossRef]
  27. Li, Z.; Bu, R. Trajectory tracking of under-actuated ships based on optimal sliding mode control with state observer. Ocean Eng. 2021, 233, 109186. [Google Scholar] [CrossRef]
  28. Chen, M.; Chen, W. Sliding mode control for a class of uncertain nonlinear system based on disturbance observer. Int. J. Adapt. Control Signal Process. 2010, 24, 51–64. [Google Scholar] [CrossRef]
  29. Wang, Y.; Yan, W.; Gao, J.; Yue, H. Neural network-based visual positioning control of unmanned underwater vehicles with thruster time delay. In Proceedings of the 2018 OCEANS-MTS, Kobe, Japan, 28–31 May 2018; pp. 1–6. [Google Scholar]
  30. Mat-Noh, M.; Mohd-Mokhtar, R.; Arshad, M.R.; Zain, Z.M.; Khan, Q. Review of sliding mode control application in autonomous underwater vehicles. Indian J. Geo-Mar. Sci. 2019, 48, 973–984. [Google Scholar]
  31. Yu, C.; Xiang, X.; Wilson, P.A.; Zhang, Q. Guidance-error-based robust fuzzy adaptive control for bottom following of a flight-style auv with saturated actuator dynamics. IEEE Trans. Cybern. 2020, 50, 1887–1899. [Google Scholar] [CrossRef]
  32. Fossen, T.I. Guidance and Control of Ocean Vehicles; Wiley: New York, NY, USA, 1994; pp. 16–18. [Google Scholar]
  33. Liao, Y.; Du, T.; Jiang, Q. Model-free adaptive control method with variable forgetting factor for unmanned surface vehicle control. Appl. Ocean Res. 2019, 93, 101945. [Google Scholar] [CrossRef]
  34. Wang, H.; Hou, Z. Model-free adaptive fault-tolerant control for subway trains with speed and traction/braking force constraints. IET Control. Theory Appl. 2020, 14, 1557–1566. [Google Scholar] [CrossRef]
  35. Hou, Z.; Jin, S. Model Free Adaptive Control: Theory and Application; Science Press: Beijing, China, 2013. [Google Scholar]
  36. Du, H.; Yu, X.; Chen, M.Z.; Li, S. Chattering-free discrete time sliding mode control. Automatica 2016, 68, 87–91. [Google Scholar] [CrossRef]
  37. Liu, J.; Wang, Y.; Tang, Y.; Yao, X. Research on Establishing and Simplifying the Dynamics Models of the ARV with Full Ocean Depth. Ocean Technol. 2019, 38, 21–29. [Google Scholar]
Figure 1. Haidou-1 ARV. The meaning of Chinese character in this figure is Shenyang Institute of Automation, CAS, Haidou-1.
Figure 1. Haidou-1 ARV. The meaning of Chinese character in this figure is Shenyang Institute of Automation, CAS, Haidou-1.
Sensors 24 03592 g001
Figure 2. The arrangement of Haidou-1 ARV motion control system.
Figure 2. The arrangement of Haidou-1 ARV motion control system.
Sensors 24 03592 g002
Figure 3. Haidou-1 ARV dynamics in different coordinates.
Figure 3. Haidou-1 ARV dynamics in different coordinates.
Sensors 24 03592 g003
Figure 4. The principle of the Haidou-1 ARV motion control system. the character * refers to the expected output signal.
Figure 4. The principle of the Haidou-1 ARV motion control system. the character * refers to the expected output signal.
Sensors 24 03592 g004
Figure 5. The motion control of Haidou-1 ARV in the horizontal plane. the blue arrows refers to the thrust direction of main thrusters.
Figure 5. The motion control of Haidou-1 ARV in the horizontal plane. the blue arrows refers to the thrust direction of main thrusters.
Sensors 24 03592 g005
Figure 6. Motion control of Haidou-1 ARV in vertical plane: (a) is the thrust allocation diagram of full-actuated depth control; (b) is the thrust allocation diagram of under-actuated depth control. The blue arrows refers to the thrust direction of main thrusters and the direction of elevators rotation.
Figure 6. Motion control of Haidou-1 ARV in vertical plane: (a) is the thrust allocation diagram of full-actuated depth control; (b) is the thrust allocation diagram of under-actuated depth control. The blue arrows refers to the thrust direction of main thrusters and the direction of elevators rotation.
Sensors 24 03592 g006
Figure 7. FFDL-MFAC control structure.
Figure 7. FFDL-MFAC control structure.
Sensors 24 03592 g007
Figure 8. A MFASMC motion control block diagram.
Figure 8. A MFASMC motion control block diagram.
Sensors 24 03592 g008
Figure 9. Horizontal plane motion simulation result (without disturbance and hydrodynamic coefficients change). (a) Heading step response curve and (b) forward speed response curve. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Figure 9. Horizontal plane motion simulation result (without disturbance and hydrodynamic coefficients change). (a) Heading step response curve and (b) forward speed response curve. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Sensors 24 03592 g009
Figure 10. Horizontal plane motion simulation result (with 20 Nm constant disturbance and hydrodynamic coefficients change). (a) Heading step response curve and (b) forward speed response curve. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Figure 10. Horizontal plane motion simulation result (with 20 Nm constant disturbance and hydrodynamic coefficients change). (a) Heading step response curve and (b) forward speed response curve. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Sensors 24 03592 g010
Figure 11. Simulation results in vertical plane (without disturbance). (a) is depth step response curve and (bd) are the rudder angle, pitch angle and pitch rate curves respectively. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Figure 11. Simulation results in vertical plane (without disturbance). (a) is depth step response curve and (bd) are the rudder angle, pitch angle and pitch rate curves respectively. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Sensors 24 03592 g011
Figure 12. Simulation result (with 30 kg constant disturbance and hydrodynamic coefficients change). (a) Depth step response curve and (bd) are the rudder angle, pitch angle and pitch rate curves, respectively. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Figure 12. Simulation result (with 30 kg constant disturbance and hydrodynamic coefficients change). (a) Depth step response curve and (bd) are the rudder angle, pitch angle and pitch rate curves, respectively. MFASMC control performance (black) compared with both PID (red) and MFAC (blue) control performance.
Sensors 24 03592 g012
Table 1. Main physical information of Haidou-1 ARV.
Table 1. Main physical information of Haidou-1 ARV.
ParameterValue
Dimension3.8 × 1.1× 1.6 m (L × W × H)
Weight2640 kg in air
Depth of operationMaximum 11,000 m
Time of operation10 h formal operation and with reserve
PropulsionTwo rotated main thrusters and two vertical thrusters
Center of buoyancy[0.0, 0.0, 0.0] m
Center of gravity [0.0, 0.0, 0.044] m
Coordinates of main thruster[−1.72, 0.6, −0.02] m
Coordinates of vertical Thruster (x-direction)0.75 m
Table 2. Main kinematics parameters of Haidou-1 ARV.
Table 2. Main kinematics parameters of Haidou-1 ARV.
DOFForces/MomentVelocitiesPositions/Euler Angles
Surge X u x
Sway Y v y
Heave Z w z
Roll K p ϕ
Pitch M q θ
Yaw N r ψ
Table 3. The main control parameters of MFASMC in horizontal plane motion.
Table 3. The main control parameters of MFASMC in horizontal plane motion.
MotionControl ParametersValue
Heading control λ h 0.5
ρ h [ 0.7 0.7 0.7 ] T
μ h 1
η h 0.2
Speed control λ s 0.001
ρ s [ 0.7 0.7 0.7 ] T
μ s 1
η s 0.2
Table 4. Performance index of heading controller step response (without disturbance and hydrodynamic coefficients change).
Table 4. Performance index of heading controller step response (without disturbance and hydrodynamic coefficients change).
Step AmplitudeControllerOvershoot/%Rise Time/sAdjusting Time/s
20°PID26.23.416.3
MFAC015.215.2
MFASMC2.97.815.5
90°PID018.718.7
MFAC016.316.3
MFASMC010.410.4
Table 5. Performance index of heading controller step response (with 20 Nm constant disturbance and hydrodynamic coefficients change).
Table 5. Performance index of heading controller step response (with 20 Nm constant disturbance and hydrodynamic coefficients change).
Step AmplitudeControllerOvershoot/%Rise Time/sAdjusting Time/s
20°PID183.1/27
MFAC30.2324
MFASMC1.63.415.3
90°PID01818
MFAC016.716.7
MFASMC01010
Table 6. The main control parameters of MFASMC in vertical plane control.
Table 6. The main control parameters of MFASMC in vertical plane control.
MotionControl ParametersValue
Depth control λ d 0.5
ρ d [ 0.7 0.7 0.7 ] T
μ d 1
η d 0.2
Table 7. Performance index of depth controller step response (without disturbance and hydrodynamic coefficients change).
Table 7. Performance index of depth controller step response (without disturbance and hydrodynamic coefficients change).
Step AmplitudeControllerOvershoot/%Rise Time/sAdjusting Time/s
5 mPID18.214.224.6
MFAC12.97.524.8
MFASMC11.64.527.1
10 mPID8.99.821
MFAC12.47.526.8
MFASMC10.45.726.5
Table 8. Performance index of depth controller step response (with 30 kg constant disturbance and hydrodynamic coefficients change).
Table 8. Performance index of depth controller step response (with 30 kg constant disturbance and hydrodynamic coefficients change).
Step AmplitudeControllerOvershoot/%Rise Time/sAdjusting Time/s
5 mPID37.413.2/
MFAC625.225.3
MFASMC11.63.39
10 mPID18.87.6/
MFAC11.77.225.4
MFASMC74.524.5
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Li, J.; Tang, Y.; Zhao, H.; Wang, J.; Lu, Y.; Dou, R. Under-Actuated Motion Control of Haidou-1 ARV Using Data-Driven, Model-Free Adaptive Sliding Mode Control Method. Sensors 2024, 24, 3592. https://doi.org/10.3390/s24113592

AMA Style

Li J, Tang Y, Zhao H, Wang J, Lu Y, Dou R. Under-Actuated Motion Control of Haidou-1 ARV Using Data-Driven, Model-Free Adaptive Sliding Mode Control Method. Sensors. 2024; 24(11):3592. https://doi.org/10.3390/s24113592

Chicago/Turabian Style

Li, Jixu, Yuangui Tang, Hongyin Zhao, Jian Wang, Yang Lu, and Rui Dou. 2024. "Under-Actuated Motion Control of Haidou-1 ARV Using Data-Driven, Model-Free Adaptive Sliding Mode Control Method" Sensors 24, no. 11: 3592. https://doi.org/10.3390/s24113592

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