Next Article in Journal
Analysis of Holding Force Acting on Anchored Vessels
Previous Article in Journal
Early Jurassic Gypsum within Eastern African Continental Marginal Basins and Its Significance for Gas Play
Previous Article in Special Issue
Binocular Vision-Based Non-Singular Fast Terminal Control for the UVMS Small Target Grasp
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Disturbance Observer-Based Model Predictive Control for an Unmanned Underwater Vehicle

1
Department of Aeronautical and Aviation Engineering, The Hong Kong Polytechnic University, Kowloon, Hong Kong, China
2
Research Centre for Unmanned Autonomous Systems, The Hong Kong Polytechnic University, Kowloon, Hong Kong, China
3
School of Engineering, The University of Newcastle, Callaghan, NSW 2308, Australia
4
BIT-BMSTU Joint School, Beijing Institute of Technology, Beijing 102401, China
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2024, 12(1), 94; https://doi.org/10.3390/jmse12010094
Submission received: 26 November 2023 / Revised: 24 December 2023 / Accepted: 28 December 2023 / Published: 2 January 2024
(This article belongs to the Special Issue Subsea Robotics)

Abstract

:
This work addresses the motion control problem for a 4-degree-of-freedom unmanned underwater vehicle (UUV) in the presence of nonlinear dynamics, parametric uncertainties, system constraints, and time-varying external disturbances. A disturbance observer-based control scheme is proposed, which is structured around the model predictive control (MPC) method integrated with an extended active observer (EAOB). Compared to the conventional disturbance observer, the developed EAOB has the ability to handle both external disturbances and system/measurement noises simultaneously. The EAOB leverages a combination of sensor measurements and a system dynamic model to estimate disturbances in real-time, which allows continuous estimation and compensation of time-varying disturbances back to the controller. The proposed disturbance observer-based MPC is implemented by feeding the estimated disturbances back into the MPC’s prediction model, which forms an effective adaptive controller with a parameter-varying model. The proposed control strategy is validated through simulations in a Gazebo and robot operating system environment. The results show that the proposed method can effectively reject unpredictable disturbances and improve the UUV’s control performance.

1. Introduction

The continuous development of unmanned underwater vehicles (UUVs) has led to their increasing utilization in various demanding underwater tasks in recent years. In the field of offshore infrastructure inspection, UUVs have proven their effectiveness in applications like inspecting underwater bridge substructures [1] and pipeline inspection [2]. UUVs also play a significant role in mapping and exploration in extreme environments, such as mapping the seafloor in ice-covered waters [3], mapping shipwrecks [4], and conducting hyperspectral imaging of Arctic macroalgal habitats [5]. Furthermore, specialized UUVs with unique structures and actuators have been developed for specific underwater operations. Examples include the addition of a crawling skid to a UUV for underwater maintenance tasks [6], the development of a prototype UUV for marine-growth removal [7], and the establishment of an underwater manipulator for delicate repair operations [8]. These vehicles have proven instrumental in replacing humans for hazardous and labor-intensive underwater work, effectively reducing operational costs and associated risks. Currently, the primary focus of development is achieving autonomy for underwater vehicles, enabling them to make decisions and perform tasks without constant human intervention. With a higher level of autonomy, UUVs offer several advantages such as the ability to carry out maritime missions over long distances or in hazardous areas.
The challenges in designing control systems for UUVs arise from their parametric uncertainties and unpredictable environmental disturbances. Various control strategies have been applied to UUVs. Proportional–integral–derivative (PID) control is a commonly used controller in UUV control strategies [9]. One advantage of PID control is its ability to effectively handle uncertainties in system parameters. Unlike some other control methods that heavily rely on precise mathematical models, PID control adjusts its control output based on the current error without explicitly requiring knowledge of the system’s underlying model. This adaptability enables the PID controller to accommodate variations and uncertainties in system parameters, ensuring robust performance. Numerous PID controllers have been developed and implemented for UUVs, such as the fractional-order PID controller that optimizes parameters with respect to the parameter uncertainties [10], the adaptive fuzzy nonlinear PID controller that provides robustness against external disturbances [11], and the intelligent-PID with PD feedforward, which further enhances stability [12]. Sliding mode control (SMC) becomes a widely used nonlinear control method in UUV motion control [13], which proves effective in handling systems with uncertainties, disturbances, and nonlinearities. A dual closed-loop integral SMC method has been developed for controlling underactuated UUVs [14]. This approach effectively handles the nonlinear and coupled behaviors of the vehicle, making it suitable for three-dimensional underactuated scenarios. A sliding mode-based fault tolerant control method integrated with thrust allocation has also been proposed to reduce the steady error caused by thruster faults [15]. However, SMC suffers from the chattering problem caused by its discontinuous control law when the vehicle moves at high speeds, leading to decreased accuracy and energy loss.
Neural network (NN)-based control methods, as a type of adaptive control technique, also effectively address parametric uncertainties by learning and adapting to changing environments or system dynamics. Unlike traditional methods, NN-based control approximates system dynamics using NNs and adjusts network parameters based on data and feedback. This adaptability enables the control system to handle variations, uncertainties, and disturbances, enhancing robustness and flexibility. Moreover, NN-based control excels in managing complex and nonlinear systems by capturing intricate patterns and relationships, ensuring accurate control in highly uncertain scenarios. A hybrid coordination method that uses reinforcement learning to learn system behavior online was implemented in an AUV [16]. A robust neural network approximation-based output-feedback tracking controller has also been proposed to effectively compensate for uncertainties [17]. However, the system stability of NN-based control methods is often challenging to theoretically prove. Thus, the validation of the control system typically relies on experimental evidence. Furthermore, the effectiveness of the neural network adaptive controller relies significantly on the number of neural network nodes, leading to a substantial computational burden that hinders its practical implementation in engineering applications.
Disturbance observer-based control (DOBC) is a control technique that aims to address the challenges posed by environmental disturbances in a control system. It involves the estimation and compensation of disturbances to improve the system’s overall performance and robustness. In contrast to other approaches that deal with disturbances by designing robust controllers, as mentioned earlier, DOBC ensures that the performance of the outer-loop controller is not degraded when disturbances are estimated in the inner loop. A nonlinear disturbance observer (NDO) was designed and incorporated into a nonsingular fast terminal sliding mode control scheme for trajectory tracking of an under-actuated UUV [18]. This incorporation guarantees finite-time convergence and demonstrates improved immunity to external disturbances. An implementation of a disturbance observer has been incorporated into fuzzy adapted S-Surface control to improve robustness against unmodeled disturbances [19]. A study conducted in 2019 introduced a modified constrained controller that combines a computed-torque controller (CTC) with a newly designed NDO for improved performance [20]. This modified controller enhances the accuracy of disturbance compensation by optimizing the evaluation function of the conventional H controller. Additionally, it incorporates considerations for control input constraints within the evaluation function. To enhance resilience against external disturbances and model uncertainties, an adaptive disturbance observer that combines the extended state observer (ESO) technique and high-order SMC was developed [21]. This adaptive disturbance observer was integrated with backstepping and nonlinear PD controllers to enhance control performance. Its efficacy was confirmed through rigorous validation in multiple experimental scenarios.
Although the methods mentioned earlier are capable of mitigating external disturbances and unmodeled uncertainty to a certain degree, they possess certain limitations. In the case of DOBC methods, most of them have the assumption of zero measurement noise, which is unrealistic in practical marine robotic systems. On the other hand, control methods such as SMC and NN-based adaptive control can address measurement noise, but they introduce issues of their own, such as chattering and high computational complexity. Furthermore, when designing a viable control system for UUVs, it is essential to account for system input and state constraints.
Model predictive control (MPC) is a control strategy that involves solving an optimal control problem (OCP) with a finite horizon recursively to determine the control action. This approach ensures that the system constraints are consistently considered throughout the control process [22]. As a result, MPC has gained significant interest in marine robotics due to its capability to handle control limits, control variation bounds, and state constraints. The application of MPC to marine vessels for dynamic positioning was demonstrated in [23]. The study showed that implementing MPC allows for the distribution of force generation over a specific time period and enables the planning of vessel motion based on the varying configuration of the rotatable thrusters. Nonlinear model predictive control (NMPC) has also been developed to enable an AUV to follow predefined trajectories in the water column [24], showcasing the potential for real-time MPC control with in situ estimated water current profiles. Furthermore, a Lyapunov-based MPC has emerged in recent years to ensure closed-loop stability [25]. The robustness of NMPC for UUV motion control has been experimentally validated in a water tank capable of generating directional ocean currents [26]. These MPC-based studies have effectively demonstrated the advantages of using MPC in UUV motion control through numerical simulations and experiments. Recently, MPC based on the active disturbance rejection control (ADRC) was also proposed for motion control of an AUV [27]. This method incorporates a discrete extended state observer to estimate disturbances and applies feedback control to compensate for them. By combining the strengths of MPC and DOBC, the controller can effectively handle parametric uncertainties and external disturbances in the inner loop. Meanwhile, MPC can address system constraints in the outer loop. Therefore, by further developing a suitable disturbance observer that is robust against measurement noise, a feasible and efficient control system for UUVs can be ensured.
Motivated by the aforementioned considerations, an extended active observer (EAOB) is developed using the extended Kalman Filter (EKF) to integrate with MPC and form the disturbance observer-based MPC (DOBMPC) in this work. The significant contribution of the designed EAOB lies in its capability to estimate disturbances in the presence of measurement noise. Additionally, the unmodeled parameter in the MPC’s prediction model is considered part of the disturbance term, effectively addressing the issue of parametric uncertainty. Unlike the conventional approach of compensating estimated disturbances into control inputs, the estimated disturbances are incorporated into the MPC’s prediction model and updated at each time step. This allows the MPC to generate an optimal control law while taking disturbances into account. The proposed control method aims to achieve the following objectives:
  • The proposed EAOB demonstrates the capacity to effectively estimate disturbances in the presence of measurement noise. This is a notable improvement compared to previous literature, where the assumption of no measurement noise was prevalent, with only a limited number of papers addressing this crucial aspect.
  • The proposed approach represents a significant advancement in compensating for disturbances by integrating real-time disturbance estimation into the prediction model of the MPC at each time step. This results in a parameter-varying model, surpassing previous methods that simply added estimated disturbances to the baseline control input. By employing this enhanced approach, more precise and adaptive control can be achieved, marking a notable improvement over previous compensation methods.
  • In this work, the estimated disturbances are explicitly taken into account within the prediction horizon of the MPC framework. This enables the generation of optimal control inputs that effectively reject disturbances, surpassing previous related works that may not have explicitly considered disturbances within the optimization process. By incorporating the estimated disturbances throughout the MPC’s prediction horizon, this approach ensures the provision of control actions that account for the presence of disturbances.
The structure of the paper is outlined as follows. Section 2 describes the dynamic model of the UUV. Section 3 explains the design of the proposed EAOB. Section 4 covers the implementation of the entire DOBMPC system. Section 5 showcases and discusses the results obtained from employing the proposed DOBMPC for dynamic positioning and trajectory tracking. Lastly, Section 6 summarizes the research work and outlines future directions.

2. Problem Formulation

In this research work, we selected BlueROV2 [28] which has 4 degrees of freedom as the UUV platform. Its motion encompasses surge, sway, heave, and yaw. Fossen’s theory [29] is employed to model the motion of UUV, which includes rigid body, added mass, and damping. This section provides detailed explanations of the kinematic and kinetic equations governing UUV motion. These equations serve as the foundation for establishing a system model for motion control. The notations of parameters obtained in the UUV dynamic model are summarized in Table 1.

2.1. Kinematic Model

The UUV’s motion states are described using two reference frames: the body-fixed reference frame (BRF) and the inertial reference frame (IRF). The BRF is fixed to the vehicle, with the center of gravity serving as the origin, and the body axes aligned with the principal axes of inertia. The longitudinal axis, denoted as the x b , extends from aft to fore. The transversal axis, referred to as the y b , extends from port to starboard. Per the right-hand rule, the z b axis is perpendicular to both the x b and y b axes. The UUV’s motion is characterized as the motion of the BRF relative to the IRF. The IRF is employed to track the vehicle’s trajectory and define the control objectives. In this work, the IRF is aligned with the north-east-down (NED) coordinate system. This choice is motivated by the prevalence of expressing position vectors in NED coordinates within various navigation applications and simulation environments. The axes in IRF are denoted as x i , y i , and z i , as shown in Figure 1.
In the UUV’s model states, the linear and angular velocities are described in the BRF as v = [ u , v , w , p , q , r ] T , while the linear and angular position are expressed in the IRF as η = [ x , y , z , ϕ , θ , ψ ] T . Since the velocity vector and position vector are expressed in different reference frames, the rotation matrix R b i are required for describing the relationship between them. Let v b = [ u , v , w ] T represent the linear velocity in BRF, and v i represents the linear velocity in IRF. Based on [30], the v b and v i can be related by equation:
v i = R b i ( Θ ) v b
where Θ includes the Euler angles (roll ϕ , pitch θ and yaw ψ ). Then the rotation matrix can be computed based on Θ as:
R b i ( Θ ) = c o s ψ c o s θ c o s ψ s i n θ s i n ϕ s i n ψ c o s ϕ c o s ψ c o s θ s i n ϕ + s i n ψ s i n ϕ s i n ψ c o s θ s i n ψ s i n θ c o s ϕ + c o s ψ c o s ϕ s i n ψ s i n θ c o s ϕ c o s ψ s i n ϕ s i n θ c o s θ s i n ϕ c o s θ c o s ϕ .
For the transformation of angular states, let ω b = [ p , q , r ] T represents angular velocity in the BRF relative to the IRF then:
Θ ˙ = T ( Θ ) ω b
where Θ ˙ = [ ϕ ˙ , θ ˙ , ψ ˙ ] is the Euler angle rate. The transformation matrix T ( Θ ) which represents the relationship between angular states in the BRF and IRF can be expressed as:
T ( Θ ) = 1 s i n ϕ t a n θ c o s ϕ t a n θ 0 c o s ϕ s i n ϕ 0 s i n ϕ / c o s θ c o s ϕ / c o s θ .
Therefore, the relationship between UUV’s velocity and position is given by:
η ˙ = p ˙ Θ ˙ = R b i ( Θ ) 0 3 × 3 0 3 × 3 T ( Θ ) v b ω b = J ( η ) v
J ( η ) = R b i ( Θ ) 0 3 × 3 0 3 × 3 T ( η )
where p = [ x , y , z ] T represents the linear position of UUV in the IRF.

2.2. Kinetic Model

To simplify the process of deriving the dynamic equations for UUV motion, it is common to assume that the vehicle behaves as a rigid body. This assumption eliminates the need to analyze the interactions between individual mass elements. The overall dynamic model can be expressed as follows:
M v ˙ + C ( v ) v + D ( v ) v + g ( η ) = τ + w
where M v ˙ is the mass matrix, C ( v ) v is the Coriolis and centripetal matrix, D ( v ) v is the hydrodynamic damping matrix, g ( η ) is the vector of the gravitational and buoyancy forces, the τ = [ X , Y , Z , K , M , N ] T is the total propulsion forces and moments, and w is the external disturbance. The M and C ( v ) v contain terms for both the rigid body and hydrodynamic added mass as:
M = M R B + M A C ( v ) = C R B ( v ) + C A ( v ) .

2.2.1. Rigid-Body Dynamics

By using Newtonian physics, the rigid-body dynamics of the UUV may be deduced as follows:
M R B v ˙ + C R B ( v ) v = τ R B .
Assuming that the origin of the BRF is positioned at the geometric center of the UUV and the vehicle exhibits symmetry in both the port–starboard and fore–aft plane, the rigid-body mass matrix can be simplified. As a result, the rigid-body mass M R B can be expressed as:
M R B = m 0 0 0 m z g 0 0 m 0 m z g 0 0 0 0 m 0 0 0 0 m z g 0 I x 0 0 m z g 0 0 0 I y 0 0 0 0 0 0 I z
where m is the mass of the vehicle, I x , I y and I z are the inertia moments about the x b , y b , and z b axes in BRF, measured in k g m 2 ; z g is the position of the CG in relation to the centre of the vehicle in z b axis, measured in meters. Subsequently, using the skew-symmetric cross-product operation on M R B yields the result of the rigid-body Coriolis and centripetal matrix C R B ( v ) is given by:
C R B ( v ) = 0 0 0 0 m w m v 0 0 0 m w 0 m u 0 0 0 m v m u 0 0 m w m v 0 I z r I y q m w 0 m u I z r 0 I x p m v m u 0 I y q I x p 0

2.2.2. Hydrodynamics

The hydrodynamics studied in this work encompass both hydrodynamic added mass and hydrodynamic damping. Hydrodynamic added mass can be perceived as a virtual mass that is introduced to a system when a body accelerates or decelerates, requiring the movement of a certain volume of the surrounding fluid. This concept is formulated based on Kirchhoff’s equation.
In an ideal fluid, for a rigid body that is either at rest or moving at a forward speed U 0 , the hydrodynamic system inertia matrix M A is positive semi-definite. The hydrodynamic coefficients are defined as the partial derivatives of the added mass force with respect to the corresponding acceleration. In many practical applications, the nondiagonal elements of M A are significantly smaller than the diagonal elements. As a result, the off-diagonal terms of M A can be disregarded, leading to a simplified form of M A as follows:
M A = X u ˙ 0 0 0 0 0 0 Y v ˙ 0 0 0 0 0 0 Z w ˙ 0 0 0 0 0 0 K p ˙ 0 0 0 0 0 0 M q ˙ 0 0 0 0 0 0 N r ˙
Accordingly, the nonlinear hydrodynamic Coriolis and centripetal matrix C A ( v ) can be calculated as:
C A ( v ) = 0 0 0 0 z w ˙ w Y v ˙ v 0 0 0 z w ˙ w 0 X u ˙ u 0 0 0 Y v ˙ v X u ˙ u 0 0 z w ˙ w Y v ˙ v 0 N r ˙ r M q ˙ q z w ˙ w 0 X u ˙ u N r ˙ r 0 K p ˙ p Y v ˙ v X u ˙ u 0 M q ˙ q K p ˙ p 0
The primary components of hydrodynamic damping for UUVs are potential damping, skin friction, wave drift damping, and damping caused by vortex shedding. Typically, potential damping and wave drift damping are disregarded in UUVs model. These various damping factors contribute to both linear and quadratic damping, as follows:
D ( v ) = D L + D N L ( v )
The linear damping term ( D L ) is a result of skin friction, while the nonlinear damping matrix ( D N L ) is caused by quadratic damping and higher-order terms. Due to decoupling, the damping matrix is derived to be diagonal. As a result, the linear damping matrix is represented by Equation (15), and the quadratic damping matrix is represented by Equation (16).
D L = diag X u , Y v , Z w , K p , M q , N r
D N L ( v ) = diag X u | u | | u | , Y v | v | | v | , Z w | w | | w | , K p | p | | p | , M q | q | | q | , N r | r | | r | .

2.2.3. Hydrostatics

Archimedes [31] established the foundational principles of fluid statics, which form the basis of hydrostatics today. Considering the mass of the UUV as m measured in kg, acceleration due to gravity as g, water density as ρ measured in kg/m3, and the volume of fluid displaced by the UUV as ∇ measured in m3. Therefore, the weight of the UUV can be expressed as W = mg, while the buoyancy force B is expressed as B = ρ g .
Given the center of buoyancy of the UUV is r b , assume the centre of the vehicle’s body frame is placed at the center of buoyancy (CB), then r b = [ 0 , 0 , 0 ] T . Since the vehicle has symmetry in the xz-plane and xy-plane, the position of the CG of the vehicle r g becomes r g = x g , y g , z g T = 0 , 0 , z g T . Thus, the overall restoring force vector g ( η ) can be calculated using Euler angle transformation as:
g ( η ) = ( W B ) sin θ ( W B ) cos θ sin ϕ ( W B ) cos θ cos ϕ z g W cos θ sin ϕ z g W sin θ 0 .

2.2.4. Propeller Model and Control Allocation

A realistic model of the propeller is taken into account in the dynamic model of the UUV. The control inputs, denoted as u = [ u 1 , u 2 , u 3 , u 4 ] T , where u 1 , u 2 , u 3 , u 4 correspond to the forces and moments in the surge, sway, heave, and yaw directions of the UUV, respectively. The BlueROV2 is equipped with six propellers to facilitate movement in 4 degrees of freedom, resulting in an over-actuation scenario. Hence, the control inputs u are allocated to each propeller using the control allocation matrix. The thrust vector, represented as t = [ t 1 , t 2 , t 3 , t 4 , t 5 , t 6 ] T , is determined as follows:
t = A u = 1 1 0 1 1 1 0 1 1 1 0 1 1 1 0 1 0 0 1 0 0 0 1 0 u
where t is the thrust produced by all propellers, and the layout of six propellers is shown in Figure 2. The blue propellers rotate clockwise, the green propellers rotate counterclockwise, and the red arrow indicates the positive surge direction.
The propulsion matrix, denoted as K, is utilized to calculate the combined force and moment that propel the UUV. This matrix represents the spatial distribution of propellers on the BlueROV2’s structure:
τ = K t .
For calculating the propulsion matrix, given that l x i is the distance between the centre of propeller i and the CG in x b direction, and t x i is the force projection to x direction; therefore, the forces and moments produced by propeller 1 are:
τ 1 = t x 1 t y 1 t z 1 t z 1 l y 1 t y 1 l z 1 t x 1 l z 1 t z 1 l x 1 t y 1 l x 1 t x 1 l y 1 = t 1 cos α t 1 sin α 0 t 1 sin α · l z 1 t 1 cos α · l z 1 t 1 sin α · l x 1 cos α · l y 1 = cos α sin α 0 sin α · l z 1 cos α · l z 1 sin α · l x 1 cos α · l y 1 t 1
where α denotes the angle at which the propeller is positioned with respect to the UUV’s forward direction, measured in radians. Using the value α = π / 4 rad and l x 1 = 0.156 m, l y 1 = 0.111 m, l z 1 = 0.072 m for propeller 1. Therefore, the first column in K can be obtained. The rest column can be calculated in the same way, thus the propulsion matrix becomes:
K = 0.707 0.707 0.707 0.707 0 0 0.707 0.707 0.707 0.707 0 0 0 0 0 0 1 1 0.051 0.051 0.051 0.051 0.111 0.111 0.051 0.051 0.051 0.051 0.002 0.002 0.167 0.167 0.175 0.175 0 0 .

2.2.5. Nonlinear Model

In summary, for achieving motion control of the UUV, the system state is defined as x = [ η ; v ] . From the Equations (5) and (7), the general form of the UUV is obtained as:
x ˙ = η ˙ v ˙ = f x , τ , w , t = J ( η ) v M 1 τ + w C ( v ) v D ( v ) v g ( η ) .

3. Extended Active Observer

When designing control systems, it is often customary to apply the principle of superposition when accounting for wave τ wave and current disturbance τ current [29]. The disturbance term also encompasses unmodeled dynamics Δ τ , such as uncertainties related to rigid-body parameters (e.g., inertia and mass properties) and hydrodynamic parameters (e.g., hydrodynamic damping force) that are challenging to accurately identify. This principle implies that all sources of disturbances are combined and included on the right-hand side of Equation (22) as the disturbance term w = [ X w , Y w , Z w , K w , M w , N w ] T ,
w = τ wave + τ current + Δ τ .
Assumption A1.
It is assumed that the disturbance caused by ocean waves ( τ wave ) and currents ( τ current ), as well as the uncertainty in unmodeled dynamics ( Δ τ ), are bounded, specifically by τ w a v e τ 1 ¯ , τ c u r r e n t τ 2 ¯ , Δ τ τ 3 ¯ . τ 1 ¯ , τ 2 ¯ , and τ 3 ¯ are unknown positive constants to be estimated. As a result, the total disturbance w is bounded by the sum of these limits, i.e., w τ 1 ¯ + τ 2 ¯ + τ 3 ¯ .
Assumption A2.
It is assumed that the total disturbance w is slow time-varying signal.
Therefore, the internal disturbance model can be constructed as:
w = M v ˙ + C ( v ) v + D ( v ) v + g ( η ) τ w ˙ = 0 .

3.1. Observer Design

For using EKF to construct a disturbance observer to compensate for the unpredictable uncertainties, the disturbance term w is considered as system states along with the position η and velocity v .
In real-world scenarios, it is common for the system being modeled to exhibit continuous-time dynamics, while measurements are obtained at discrete time intervals. To address this problem, the continuous–discrete EKF (CD-EKF) is employed for constructing the EAOB. The CD-EKF incorporates both continuous and discrete dynamics into the estimation process, operating similarly to the standard EKF but with the additional capability of handling discrete dynamics. The continuous dynamics are typically described using differential equations, while the discrete dynamics are represented by difference equations. During the prediction step of the CD-EKF, the continuous dynamics are discretized by integrating forward in time using numerical integration techniques, effectively capturing the system’s continuous evolution between measurement updates. In the update step, the CD-EKF incorporates the discrete-time measurements to correct and refine the state estimate. By seamlessly combining both continuous and discrete dynamics within the estimation process, the CD-EKF offers improved accuracy and robustness in estimating the state variables of systems with mixed dynamics. Therefore, the system process is represented as a continuous-time model, while the discrete-time measurements are taken. The system process model can be reconstructed as:
x ˙ ( t ) = f ( x ( t ) , τ ( t ) , w ( t ) ) + W ( t ) W ( t ) N ( 0 , Q ( t ) ) .
where system state x = [ η T v T w T ] T , W ( t ) refers to the process noise that is assumed to be zero mean Gaussian noise with covariance Q ( t ) , f ( · ) refers to the nonlinear system process model, and t represents time in continuous form. Therefore, all the functions in the system process model are defined in continuous time.
Therefore, the system process model can be formulated based on the UUV’s model in Equation (22):
f ( x , τ , w ) = J ( η ) v ( M ) 1 [ τ + w C ( v ) v D ( v ) v g ( η ) ] w ˙
The measurement states contain the position η , velocity v , and propulsion forces and moments τ , thus the discrete-time measurement model is formulated as:
z k = h x k + V k V k N 0 , R k
where measurement states z = [ η T v T τ T ] T , V k is the measurement noise which is assumed to be zero mean Gaussian noise with covariance R k , h ( · ) refers to the nonlinear measurement model that relates the system states to the measurements obtained from sensors, and k denotes time in discrete form. Thus, all the functions in the measurement model are defined in discrete time. The first 12 terms of the measurement model are identity to the system process model, and the τ can be calculated based on disturbance term w as:
τ = M v ˙ + C ( v ) v + D ( v ) v + g ( η ) w .
The accurate estimation of solutions heavily relies on the design of the noise covariance matrices for the system process Q ( t ) and measurements R k . One approach to constructing Q ( t ) is by utilizing the piecewise white noise model (PWNN). This stochastic model allows for the representation of varying noise characteristics across different time intervals or regions. By incorporating PWNN, the time-varying dynamics of the system can be more precisely captured in the EKF. This is particularly beneficial when dealing with systems that exhibit nonstationary or changing noise characteristics. The equation for calculating the system process noise covariance Q ( t ) based on PWNN is as follows:
Q ( t ) = E Γ W ( t ) W ( t ) Γ = Γ σ 2 Γ .
where Γ = [ Δ t 2 / 2 , Δ t , Δ t ] T is the noise gain of the system, Δ t is the sampling time step, and σ 2 represents the variance of the white noise process. The covariance of the measurement noise R k is also dependent on the sampling time step Δ t , which is defined as:
R k = d i a g [ Δ t , Δ t , Δ t ] .
The matrix Q ( t ) is used to model the uncertainty and variability in the system dynamics. By adjusting the Q(t), it can control the level of confidence the observer has in the predicted state estimates. Meanwhile, the matrix R k captures the uncertainty associated with the sensor measurements. Consequently, the tuning of Q ( t ) and R k determines the weighting between the system model and the measurements. As the current work is being conducted in simulation, where higher measurement accuracy is present, further adjusting R k allows for greater reliance on measurements:
R k = d i a g [ Δ t 2 / 2 , Δ t 2 / 2 , Δ t 2 / 2 ] .
To adapt the real-world implementation, the matrix R k can be further fine-tuned according to the specific sensors employed. For instance, the accelerometer and gyroscope are commonly employed for state measurement, but they often introduce unavoidable noise into the measurements. Consequently, in such cases, it is crucial to carefully determine the measurement noise matrix R k . Numerous studies have been conducted in this area. In 2021, an experimental approach was proposed to analyze the impact of different weightings of matrix Q ( t ) and R k on state estimation derived from the accelerometer and gyroscope [33]. In addition, a study also developed a dynamic noise model for adaptive filtering of the gyroscope [34]. This work introduced the dynamic Allan variance, which utilized a novel truncation window based on entropy features to construct the noise model. Additionally, an adaptive Kalman filter was designed to accommodate practical system and computational environments. Furthermore, a disturbance observer with adaptation laws has been developed based on the generalized super-twisting algorithm [21]. This allows the observer to be auto-tuned, improving robustness to both external disturbances and model uncertainties.
The system process model f ( x , τ , w ) and the measurement model h ( x ) can be linearized by taking the partial derivatives of each to evaluate the state transition matrix F and the measurement matrix H at each operating point with Jacobian matrix. Equation (32) provides the state transition matrix F that captures the connection between the current state and the subsequent predicted state in a dynamic system. This matrix is derived using continuous-time t as a basis. The measurement matrix, denoted as H , establishes the connection between sensor measurements and the predicted system state, as expressed in Equation (33), with consideration for discrete-time k.
F ( t ) = f x x ^ ( t ) , τ ( t ) , w ( t )
H k = h x x ^ k k 1
Denote the three elements in the second row of matrix F ( t ) as F 21 ( t ) , F 22 ( t ) , and F 23 ( t ) . Therefore
F 21 ( t ) = M 1 M η ^ v ^ ˙ + C ( v ^ ) v ^ η ^ + D ( v ^ ) v ^ η ^ + g ( η ^ ) η ^ , F 22 ( t ) = M 1 ( C ( v ^ ) v ^ v ^ + D ( v ^ ) v ^ v ^ ) , F 23 ( t ) = M 1 .
The CD-EKF is a recursive estimation algorithm, where the main procedure can be divided into prediction and update parts. Before starting the recursion, an initialization step is performed based on the first measurement:
x ^ t 0 = E x t 0 , P t 0 = Var x t 0 .
In the prediction part, it predicts the state estimate x ^ k k 1 = x ^ t k based on the previous state estimate and the system dynamics. Then the error covariance matrix P k k 1 = P t k can be calculated based on the state transition matrix F . The prediction part is shown as follows:
solve x ^ ˙ ( r t ) = f ( x ^ ( t ) , τ ( t ) ) P ˙ ( t ) = F ( t ) P ( t ) + P ( t ) F ( t ) T + Q ( t ) with x ^ t k 1 = x ^ k 1 k 1 P t k 1 = P k 1 k 1 x ^ k k 1 = x ^ t k P k k 1 = P t k
The prediction step consists of both continuous-time and discrete-time components. The first equation, x ^ ˙ ( t ) = f ( x ^ ( t ) , τ ( t ) ) , represents the continuous-time dynamics of the system. It describes how the estimated state x ^ evolves over time based on the current estimated state and the total propulsion force and moments τ . The second equation, P ˙ ( t ) = F ( t ) P ( t ) + P ( t ) F ( t ) T + Q ( t ) , represents the continuous-time evolution of the error covariance matrix P . It captures how the uncertainty in the estimated state evolves over time, taking into account the system’s dynamics represented by the matrix F and the process noise covariance matrix Q . The discretization occurs implicitly between the time steps t k 1 and t k . The initial conditions for the discrete-time updates are set based on the estimated state and error covariance matrix at time t k 1 , denoted by x ^ k 1 | k 1 and P k 1 | k 1 , respectively. These initial values are then used to compute the updated estimates x ^ k | k 1 and P k | k 1 at time t k .
Therefore, in Equation (36), a numerical integration method should be applied for the discretization of a continuous-time system process model. Various ways of discretization in EKF have been discussed [35]. In this work, the continuous dynamics of the system are approximated using a deterministic integration scheme. This scheme yields a deterministic estimation of the system’s behavior between measurement updates, assuming no uncertainty or stochasticity in the system dynamics. Deterministic integration methods are preferred due to their computational efficiency, avoiding the computational burden associated with simulating random processes. Specifically, the fourth-order Runge–Kutta (RK4) method [36] is selected for its superior accuracy and stability compared to lower-order integration methods like Euler’s method or the second-order Runge–Kutta method. The RK4 method achieves this by evaluating the system dynamics at multiple intermediate points during each integration step, resulting in a more precise estimation of the state variables.
In the update part, it calculates the measurement residual y ^ k k with current measurements z ( k ) and measurement model. Then the Kalman Gain K k at time k can be determined based in the predicted error covariance matrix P k k 1 and linearized measurement matrix H k . Finally, it updates the state estimate x ^ k k based on the predicted state estimate x ^ k k 1 and the Kalman Gain K k , and recalculate the error covariance matrix P k k based on Kalman Gain K k and the linearized measurement model H k . The following equations express the procedure in EKF’s update part
y ^ k k = z k h x ^ k k 1 K k = P k k 1 H k T H k P k k 1 H k T + R k 1 x ^ k k = x ^ k k 1 + K k y ^ k k P k k = I K k H k P k k 1 .
The equation in the EKF update part is formulated in discrete time. The time step at which the equation is evaluated is denoted by k. The notation k k signifies that the variable or state being considered is at time step k. On the other hand, k k 1 refers to the estimation or prediction at time step k based on the information available up to the previous time step, which is k 1 .

3.2. Stability Analysis

The system process model Equation (26) can be extended as:
x ˙ = f x , τ , w + G ξ x = J ( η ) v ( M ) 1 [ τ + w C ( v ) v D ( v ) v g ( η ) ] w ˙ + G ξ η ξ v ξ w , Y = H X + V k
where Y is the output of the system, G is a unit matrix, ξ η , ξ v and ξ w represent the process noises of system states [ η T v T w T ] T , respectively.
Therefore, in the above observer design process as Equation (37), the state estimate x ^ ˙ is formulated as:
x ^ ˙ = f x , τ , w + P H T ( H P H T + R ) 1 ( Y H x ^ ) ,
where
P ˙ = f x ^ P + P f T x ^ + G Q G T P H T ( H P H T + R ) 1 H P .
The stability of using the EKF for force estimation has been demonstrated in [37]. Accordingly, the stability analysis of the proposed EAOB method can be conducted using two theorems.
Theorem 1.
The proposed EAOB for the system described in Equation (22) is locally stable, given that
1.
α 1 I Q ( t ) α 2 I ,
2.
α 3 I R k α 4 I .
3.
Then the following is true:
α 5 I t t + σ F 23 ( τ ) T F 23 ( τ ) d τ α 6 I
where F 23 ( τ ) in Equation (34) is bounded based on Assumption 1, and α 1 6 are positive constants.
Theorem 2.
Assume that the model of a linearized system is as follows:
1.
uniformly completely observable;
2.
uniformly completely controllable;
3.
α 1 I Q ( t ) α 2 I ;
4.
α 3 I R k α 4 I /;
5.
F ( t ) α 5 , G ( t ) α 6 , H k α 7 .
Then the following equation, which is derived from Equation (37), is true:
x ^ ˙ = F x ^ + P H T ( H P H T + R ) 1 H x ˜ , x ˜ ˙ = F P H T ( H P H T + R ) 1 H x ˜ ,
is uniformly asymptotically stable based on [38], where x ˜ = x x ^ is the unforced optimal filter.
As per Theorem 2, it is necessary to linearize the nonlinear dynamic system. The linearized system can be constructed with Equations (32) and (33) as follows:
x ˙ = F ( t ) x + G ξ x , z = H X + V k .
To ensure the stability of the EAOB, certain conditions must be met. Firstly, the linearized system must be fully observable, which can be achieved by satisfying conditions 2 and 3 in Theorem 1. Secondly, the linearized system must be fully controllable, which can be accomplished by meeting condition 1 in Theorem 1. Finally, stability can be achieved by utilizing the outcomes of Theorem 2.

4. Disturbance Observer-Based Model Predictive Control (DOBMPC)

MPC is a model-based control strategy, which determines the control action by recursively solving OCPs and respects the system constraints during the control, as shown in Figure 3.
In the MPC control loop, it receives reference states, system constraints, and measurement states from the dynamic system, and outputs the control inputs back to the system. The MPC calculates the predicted outputs based on the prediction model with a sequence of control inputs over a certain horizon, and the optimizer solves the quadratic programming (QP) problem as:
min U , X t = 0 T h ( x ( t ) , u ( t ) ) y r e f Q 2 d t + h ( x ( T ) ) y N , r e f Q N 2 subject to x ˙ = f ( x ( t ) , u ( t ) ) ; u ( t ) U x ( t ) X x ( 0 ) = x t 0
where u ( t ) and x ( t ) represent control inputs and system states at time t; T is the prediction horizon which refers to the number of time steps to look forward; y r e f and y N , r e f are the stage reference states in the prediction horizon and the terminal reference states, respectively; Q and Q N are the weighting matrics for stage states and terminal states; f ( · ) and h ( · ) are the prediction model and system output functions; and U and X are constraints in control inputs and system states.
When designing a real-world system, it is important to consider the input constraints based on the physical limits of the actuator being used. In this case, the control inputs u are bounded, as u 1 f m a x , u 2 f m a x , u 3 f m a x , u 4 M m a x . f m a x and M m a x represent the maximum allowed force and moment limits, respectively. The f m a x and M m a x are determined based on the propeller thrust force datasheet in [26]. In this study, the MPC also takes system constraints into account. The vehicle’s linear velocity is limited as v b v m a x . Here, v m a x represents the maximum linear velocity. The v m a x is determined based on the system’s specification in [28], while v m a x = 1.5   m / s . To ensure that the constraints are taken into account during optimization and further assure control feasibility, the input constraints are written into U , while the system constraints are written into X in the cost function in Equation (44).
To tune the MPC, there are several important steps to follow. First, the prediction horizon T is selected, taking into account the trade-off between control performance and computational burden. To find an optimal value that balances these factors, the horizon is incrementally increased during simulations and evaluated for improved control performance while maintaining the real-time operation of the MPC. Additionally, MPC allows for the prioritization of multiple control objectives by assigning weighting factors in the matrix Q to each objective. In this particular work, the yaw angle ψ is given the highest priority, followed by the position states x, y, and z. The terminal cost is associated with the final state of the system at the end of the prediction horizon. The weighting matrix at terminal states Q N reflects the relative significance of achieving the desired steady state or target. A higher weight indicates a stronger emphasis on reaching the desired terminal state. However, since the focus of this work is on the robustness of the controller, Q N is set equal to the values in Q to provide less aggressive control.
Once the MPC has been fine-tuned to attain the desired control performance, the proposed EAOB, as described in Section 3, can be incorporated into the MPC. The estimated states x ^ k k provided by the EAOB are divided into two components. The first component consists of the estimated positions η ^ and velocities v ^ , which are utilized by the MPC module to enhance the accuracy of the system states. Simultaneously, the second component, the estimated disturbances w ^ , is incorporated into the MPC’s prediction model as Equation (22) at each time step. According to Assumption 2, the disturbance term w throughout the prediction horizon T remains consistent with the estimated disturbance v ^ at the current time step.
Therefore, the DOBMPC algorithm is implemented in a receding horizon with the following steps:
  • At the sampling time instant, utilize prediction Equation (36) and update Equation (37) to estimate the disturbance w ^ using the EAOB approach.
  • Update the parameters within the disturbance term w in the prediction model of the MPC, as represented by Equation (22), at the current time instant and within the prediction horizon [ 0 , T ] , by incorporating the estimated disturbance w ^ obtained in the initial step.
  • The OCP in the Equation (44) is solved to obtain the optimized control sequence u * ( s ) , s [ 0 , T ] .
  • The first set of the control sequence u * ( s ) , s [ 0 , Δ t ] is implemented in the dynamic system, while the rest will be treated as initial conditions in the next iteration.
  • At the next sampling instant, the OCP in the Equation (44) will be solved again with the measurement states and new initial condition.
By integrating the EAOB with MPC, the parameters within the disturbance term w in the MPC’s prediction model are continuously updated at each time step, as outlined in step 2. This integration results in a nonlinear parameter-varying model. Consequently, the MPC’s optimizer incorporates the estimated disturbances, enabling it to generate optimal control inputs that effectively reject disturbances at each iteration.
To realize the MPC, the OCP should be discretized from t 0 to t T and solved with multiple shooting schemes. Therefore, it becomes a sequential quadratic programming (SQP) which is executed in a real-time iteration scheme [39]. In this research work, the implementations are completed through ACADOS [40]. ACADOS is a versatile and efficient open-source optimization framework designed specifically for real-time MPC applications. It follows a two-stage approach, consisting of an offline stage and an online stage. In the offline stage, ACADOS defines the system dynamics, cost function, and constraints, formulating the MPC problem as a nonlinear programming problem (NLP). It compiles this representation into a solver-ready format. In the online stage, ACADOS solves the NLP in real time, taking the current system state as input and iteratively optimizing the control inputs while satisfying the dynamics and constraints. ACADOS offers various advantageous functionalities, such as efficient numerical algorithms, real-time capabilities, and the flexibility to choose solvers, constraints, and objective functions based on specific requirements.
In order to implement MPC in real-world applications, it is crucial to enhance computational efficiency. This work reduces the computational burden through the utilization of ACADOS. However, there are alternative methods that can also be considered for real-time implementation of MPC. In 2020, a new class of condensing-based MPC iteration schemes was proposed [41], which demonstrated the asymptotic stability and ensured important constraint satisfaction properties of the closed-loop system, regardless of the number of Newton updates performed. Another iteration scheme for reducing the computational burden of constrained discrete-time linear systems was proposed, specifically for moving horizon estimation-based output feedback MPC [42]. Additionally, a robust early termination MPC approach was recently introduced [43]. This method is based on the barrier function and continuous-time primal-dual gradient flow technique. The results indicated that the proposed approach offers a suboptimal yet feasible and effective solution when early termination is applied. Considering these alternative algorithms could be beneficial for the implementation of the MPC algorithm, providing further options to enhance computational efficiency.
The overall block diagram of the proposed DOBMPC is depicted in Figure 4. The EAOB module receives measurements of positions η , velocities v , and propulsion forces and moments τ . It then outputs the estimated positions η ^ , velocities v ^ , and disturbances w ^ . The MPC module utilizes the estimated positions η ^ and velocities v ^ as system states. It generates control inputs u based on the error e between the reference trajectory (comprising positions η d and velocities v d ) and the system states. The estimated disturbances w ^ are directly written into the MPC prediction model, as illustrated in the figure. The resulting optimal control inputs u , which account for the disturbances, are then passed through the control allocation process to drive the system plant.

5. Results and Discussion

The performance of the proposed DOBMPC is verified by simulation in the UUV simulator [44], which is an extension of the open-source robotics simulator Gazebo to underwater scenarios. It is also utilized to construct a more realistic simulation environment.
For real-world implementation, it is crucial to acquire measurements of system states, encompassing linear and angular positions, as well as linear and angular velocity. In the absence of GPS signals in the underwater environment, alternative sensors are employed. Underwater acoustic positioning systems, such as ultra-short baseline (USBL), are commonly preferred due to their enhanced mobility, providing reliable linear position information for the UUV. The attitude and heading reference system (AHRS) can be utilized to determine the UUV’s angular position, including pitch, roll, and yaw, enabling the acquisition of necessary attitude information. Additionally, the AHRS incorporates gyroscopes as part of its sensor suite, allowing the estimation of angular velocity. For the UUV’s linear velocity, the Doppler velocity log (DVL) is typically used. However, an alternative and more economical method exists, which estimates velocity based on thrust and a static relationship between thrust and velocity at steady state. It is important to note that this alternative method may exhibit reduced accuracy, particularly in the presence of significant external disturbances.
The specifications of the BlueROV2 used in this research work are defined in a unified robot description format (URDF) file, which is used for representing the robot model. The robot model in the URDF file follows the dynamic model in Section 2. Therefore, the parameters in the BlueROV2’s model are shown in the following tables. Table 2 indicates the rigid body parameter includes mass m, weight W, buoyancy B, and inertia I x   I y   I z . Table 3 specifies the hydrodynamic terms, which include added mass produced when the UUV travels through the fluid and the linear damping force caused by the skin friction.
In the disturbance rejection tests, two motion control problems are employed, which are dynamic positioning and trajectory tracking. The results from the proposed DOBMPC are compared against PID and baseline MPC controllers. Based on Fossen’s theory [29], the disturbance term is defined in the force level as Equation (22). Therefore, to directly observe the disturbance rejection performance, the disturbances are generated as body wrenches, which include forces and moments in 4 DOF. The ROS service A p p l y B o d y W r e n c h is used to generate the forces and moments that act at the CG of the UUV in the IRF. Thus, the rotation matrix, as the Equation (6), is required to transfer the disturbances w that are estimated in the BRF to the IRF for comparing results.
Table 4 lists the MPC parameters that apply to both the proposed DOBMPC and baseline MPC. The baseline MPC used for comparison also employs the same cost function as the proposed DOBMPC, as described in Equation (44). Since the prediction horizon is 60 and the sample time is 0.05 s, the system considers 3 s forward. The average time for solving the OCP problems is 7 ms, which allows the system to run in real time. The PID parameters that utilized in this work are also listed in Table 5. The implemented PID controller utilizes the system states of position η and velocity v , as well as the control inputs of forces and moments τ . The control inputs computed by the PID controller are subsequently allocated to each propeller using the control allocation method described in Equation (18).

5.1. Dynamic Positioning Results

For dynamic positioning, the UUV encounters two types of disturbances: simulated periodic wave effects and constant current effects. These disturbances manifest as forces and moments acting on the UUV. In the case of periodic disturbances, sinusoidal waves with random force amplitudes ranging from 10–16 N are applied in the x i , y i , and z i directions, while sinusoidal waves with random moment amplitudes ranging from 1–2 Nm are applied around the z i axis. Utilization of a wave spectrum model, such as the JONSWAP (Joint North Sea Wave Project) spectrum [45], can provide an additional approach to validate the proposed method and improve the disturbance model in future work. The JONSWAP spectrum, developed based on extensive measurements of wave characteristics in the North Sea, offers a statistical representation of wave heights and frequencies, enabling the simulation of wave forces and wave-induced motions. Recent studies have successfully employed this model to estimate the impact of waves on the control system of an underwater quadrotor [46] and assess the effects of waves and currents on motion control of underwater gliders [47]. Additionally, a numerical model was developed [48] to study currents under significant wave height. By further integrating the wave and current model, it becomes possible to achieve a more precise representation of real-world conditions, leading to a comprehensive evaluation and refinement of the DOBMPC’s performance.
The UUV is set to remain stationary at the position [ 0 , 0 , 20 ] in the IRF while keeping a yaw angle of 0 degrees, in the presence of disturbances. Figure 5 displays the estimated disturbances alongside the generated disturbances. As shown in the figure, the estimated disturbances closely match the generated disturbances, and the estimation delay is shorter than the sample time, proving the feasibility of the proposed EAOB.
After compensating the estimated disturbances into the MPC’s prediction model, it improves the disturbance rejection ability of the controller significantly compared to the PID and the MPC, as shown in Figure 6. A 2D diagram that indicates the dynamic positioning results of three controllers is also demonstrated in Figure 7, while the blue trajectory shows the DOBMPC can stay at the reference point more stably.
The corresponding control inputs of the proposed DOBMPC under periodic waves are illustrated in Figure 8.
To generate constant disturbances, a 10 N force is applied in the x i , y i , and z i directions at time t = 10 s, and a 5 Nm torque is applied around the z i axis at the same time. In Figure 9, a slight overshoot can be observed when the disturbances abruptly change from 0 N to 10 N. This overshoot is caused by the significant difference in estimated states between two time steps. The EAOB takes less than 0.5 s to accurately adjust the estimated states using recursive iteration. Figure 10 displays the tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers when subjected to constant currents. It clearly demonstrates the varying levels of disturbance rejection capability among the three controllers. The DOBMPC controller precisely estimates disturbances and compensates for them, resulting in errors converging to zero in each direction. The x–y diagram in Figure 11 further illustrates the dynamic positioning performance of the three controllers. By overlaying disturbances in the same direction, it becomes evident that the proposed DOBMPC significantly enhances disturbance rejection ability.
The corresponding control inputs of the proposed DOBMPC for dynamic positioning under constant current effect is illustrated in Figure 12.
In addition, this work also examines the disturbance rejection capability of the superposition of periodic wave and constant current effect in dynamic positioning. Sinusoidal waves with random force amplitudes ranging from 3 to 6 N are applied in the x i , y i , and z i directions, while sinusoidal waves with random moment amplitudes ranging from 1 to 2 Nm are applied around the z i axis. At time t = 4 s, the constant current effect is also superposed with 10 N in the x i , y i , and z i directions, and 3 Nm around the z i axis. Figure 13 shows the comparison of applied and estimated disturbances, which are highly coincident. The tracking error and control inputs are shown in Figure 14 and Figure 15, respectively.

5.2. Trajectory Tracking Results

To assess the performance of trajectory tracking, two kinds of movement scenarios are employed. Firstly, a circular path with a radius of 2 m is employed. The UUV’s yaw angle is defined to be relative to the surge direction. To assess the system’s robustness, a 10 N force is applied in the x i , y i , and z i directions, along with a 5 Nm torque around the z i axis. Figure 16 illustrates the comparison between the estimated disturbances and the generated disturbances. As the disturbance term incorporates unmodeled components from the dynamic model, the disparity between the estimated and generated disturbances can be attributed to the nonlinear damping force experienced by the UUV during circular trajectory movement. The tracking error of PID, MPC, and the proposed DOBMPC is shown in Figure 17, demonstrating a significant reduction in tracking error with the proposed DOBMPC. Additionally, Figure 18 and Figure 19 provide a visual representation of the trajectory tracking results. The corresponding control inputs of the proposed DOBMPC are illustrated in Figure 20.
To evaluate the effectiveness of the proposed control method in tracking a highly nonlinear trajectory, a lemniscate trajectory with a 2 m amplitude is utilized. Throughout the movement, the yaw angle remains constant at 0 degrees. Additionally, periodic wave effects are incorporated into the testing process. These waves have random force amplitudes ranging from 10 to 16 N and random moment amplitudes ranging from 2 to 4 Nm. Figure 21 provides the comparison between generated disturbances and estimated disturbances. The results demonstrate that the disturbance forces in the x i , y i , and z i directions can still be accurately estimated when following a lemniscate trajectory. However, challenges arise when accurately estimating the disturbance moment around z i during the tracking of this trajectory. This can lead to occasional deviations or noise around the actual disturbance value. The complexity of unmodeled nonlinear hydrodynamics, which becomes more prominent when tracking a nonlinear trajectory like the lemniscate, could be a contributing factor to this issue. In Figure 22, the system states of tracking a lemniscate trajectory under periodic waves are compared between PID, MPC, and the proposed DOBMPC. While the system states of PID and MPC exhibit irregularities due to time-varying massive disturbances, the states of DOBMPC remain relatively smooth. The tracking error, depicted in Figure 23, shows a significant reduction with the proposed DOBMPC compared to PID and MPC. Lastly, Figure 24 provides a visual representation of the trajectory tracking results in three dimensions. The corresponding control inputs of the proposed DOBMPC for tracking the lemniscate trajectory are illustrated in Figure 25.

5.3. Results Analysis

The above figures demonstrate that the proposed observer can accurately estimate disturbances of both periodic wave effects and constant current effects. The observer also shows the ability to capture the unmodeled dynamics. However, it can be observed that when the frequency of periodic wave effects is too high, the observer may lose the accuracy of estimating disturbances. This is because the disturbance term is assumed to be a slow time-varying signal.
Table 6 presents an analysis of the performance of dynamic positioning and trajectory tracking of the UUV. The evaluation is based on the root mean square error (RMSE). RMSE is a commonly used metric in control systems literature and has been widely accepted as a measure of performance. The use of RMSE allows for easy comparison and interpretation of results across different controllers. It provides a quantitative measure that can be used to assess and rank the performance of different control strategies. Furthermore, RMSE is less sensitive to outliers compared to other metrics, such as mean absolute error (MAE). It considers the squared errors, which amplifies the impact of larger errors, making it suitable for capturing the performance of control systems where extreme errors may occur.
The lowest RMSE in each row is highlighted. The results clearly demonstrate that the utilization of the proposed DOBMPC significantly enhances the system’s ability to reject disturbances.

6. Conclusions

In this paper, a robust DOBMPC has been developed for dynamic positioning and trajectory tracking of a UUV in the presence of unpredictable disturbances. The simulation results provide evidence of the control strategy’s effectiveness in rejecting disturbances. The proposed control strategy offers several significant contributions. Firstly, it demonstrates the ability to estimate time-varying disturbances in real time, enabling prompt compensation. Secondly, it exhibits robustness against measurement noise, ensuring reliable performance. Moreover, the MPC framework guarantees the consideration of system constraints during the recursive solving of the optimal control problem. This ensures the UUV operates within defined limits. The estimated disturbances are directly incorporated into the MPC’s prediction model at each time step, enabling the calculation of an optimal control law. In summary, the developed DOBMPC approach provides a robust control strategy for dynamic positioning and trajectory tracking of UUVs, effectively compensating for disturbances while considering system constraints.
The future work encompasses two primary aspects. Firstly, a comparative analysis can be conducted to assess the effectiveness and robustness of the proposed DOBMPC in relation to other robust controllers, such as SMC [32], which have the capability to adapt to complex operational environments, and other DOBC methods mentioned in the literature review [18,19,20,21]. These comparisons will provide valuable insights into the performance of the proposed approach. Secondly, the validation of the DOBMPC can be enhanced by conducting simulations in a more realistic environment. It can be achieved by using computational fluid dynamics to create a wave model [49]. This will allow for a better representation of real-world conditions and further evaluation and refinement of the DOBMPC’s performance.

Author Contributions

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

Funding

This research was funded by the Research Centre for Unmanned Autonomous Systems with project ID: P0046487, and the Department of Civil and Environmental Engineering at The Hong Kong Polytechnic University.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data presented in this study are openly available in: https://github.com/HKPolyU-UAV/bluerov2.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Hou, S.; Jiao, D.; Dong, B.; Wang, H.; Wu, G. Underwater inspection of bridge substructures using sonar and deep convolutional network. Adv. Eng. Inform. 2022, 52, 101545. [Google Scholar] [CrossRef]
  2. Hu, S.; Feng, R.; Wang, Z.; Zhu, C.; Wang, Z.; Chen, Y.; Huang, H. Control system of the autonomous underwater helicopter for pipeline inspection. Ocean. Eng. 2022, 266, 113190. [Google Scholar] [CrossRef]
  3. Barker, L.D.; Jakuba, M.V.; Bowen, A.D.; German, C.R.; Maksym, T.; Mayer, L.; Boetius, A.; Dutrieux, P.; Whitcomb, L.L. Scientific challenges and present capabilities in underwater robotic vehicle design and navigation for oceanographic exploration under-ice. Remote Sens. 2020, 12, 2588. [Google Scholar] [CrossRef]
  4. Mogstad, A.A.; Ødegård, Ø.; Nornes, S.M.; Ludvigsen, M.; Johnsen, G.; Sørensen, A.J.; Berge, J. Mapping the historical shipwreck figaro in the high arctic using underwater sensor-carrying robots. Remote Sens. 2020, 12, 997. [Google Scholar] [CrossRef]
  5. Summers, N.; Johnsen, G.; Mogstad, A.; Løvås, H.; Fragoso, G.; Berge, J. Underwater hyperspectral imaging of Arctic macroalgal habitats during the polar night using a novel mini-ROV-UHI portable system. Remote Sens. 2022, 14, 1325. [Google Scholar] [CrossRef]
  6. Preuß, H.; Cherewko, V.; Wollstadt, J.; Wendt, A.; Renkewitz, H. Crawfish Goes Swimming: Hardware Architecture of a Crawling Skid for Underwater Maintenance with a BlueROV2. In Proceedings of the OCEANS 2022, Hampton Roads, VA, USA, 17–20 October 2022; pp. 1–5. [Google Scholar] [CrossRef]
  7. Mai, C.; Benzon, M.V.; Sørensen, F.F.; Klemmensen, S.S.; Pedersen, S.; Liniger, J. Design of an Autonomous ROV for Marine Growth Inspection and Cleaning. In Proceedings of the 2022 IEEE/OES Autonomous Underwater Vehicles Symposium (AUV), Singapore, 19–21 September 2022; pp. 1–6. [Google Scholar] [CrossRef]
  8. Mao, J.; Song, G.; Hao, S.; Zhang, M.; Song, A. Development of a Lightweight Underwater Manipulator for Delicate Structural Repair Operations. IEEE Robot. Autom. Lett. 2023, 8, 6563–6570. [Google Scholar] [CrossRef]
  9. Woolsey, C. Review of Marine Control Systems: Guidance, Navigation, and Control of Ships, Rigs and Underwater Vehicles. J. Guid. Control. Dyn. 2005, 28, 574–575. [Google Scholar] [CrossRef]
  10. Liu, L.; Zhang, L.; Pan, G.; Zhang, S. Robust yaw control of autonomous underwater vehicle based on fractional-order PID controller. Ocean. Eng. 2022, 257, 111493. [Google Scholar] [CrossRef]
  11. Hasan, M.W.; Abbas, N.H. Disturbance Rejection for Underwater robotic vehicle based on adaptive fuzzy with nonlinear PID controller. ISA Trans. 2022, 130, 360–376. [Google Scholar] [CrossRef]
  12. Bingul, Z.; Gul, K. Intelligent-PID with PD Feedforward Trajectory Tracking Control of an Autonomous Underwater Vehicle. Machines 2023, 11, 300. [Google Scholar] [CrossRef]
  13. Healey, A.; Lienard, D. Multivariable sliding mode control for autonomous diving and steering of unmanned underwater vehicles. IEEE J. Ocean. Eng. 1993, 18, 327–339. [Google Scholar] [CrossRef]
  14. Yan, Z.; Wang, M.; Xu, J. Robust adaptive sliding mode control of underactuated autonomous underwater vehicles with uncertain dynamics. Ocean. Eng. 2019, 173, 802–809. [Google Scholar] [CrossRef]
  15. Lv, T.; Zhou, J.; Wang, Y.; Gong, W.; Zhang, M. Sliding mode based fault tolerant control for autonomous underwater vehicle. Ocean. Eng. 2020, 216, 107855. [Google Scholar] [CrossRef]
  16. Carreras, M.; Batlle, J.; Ridao, P. Hybrid coordination of reinforcement learning-based behaviors for AUV control. In Proceedings of the 2001 IEEE/RSJ International Conference on Intelligent Robots and Systems. Expanding the Societal Role of Robotics in the the Next Millennium (Cat. No.01CH37180), Maui, HI, USA, 29 October–3 November 2001; Volume 3, pp. 1410–1415. [Google Scholar] [CrossRef]
  17. Elhaki, O.; Shojaei, K. A robust neural network approximation-based prescribed performance output-feedback controller for autonomous underwater vehicles with actuators saturation. Eng. Appl. Artif. Intell. 2020, 88, 103382. [Google Scholar] [CrossRef]
  18. Patre, B.M.; Londhe, P.S.; Waghmare, L.M.; Mohan, S. Disturbance estimator based non-singular fast fuzzy terminal sliding mode control of an autonomous underwater vehicle. Ocean. Eng. 2018, 159, 372–387. [Google Scholar] [CrossRef]
  19. Lakhekar, G.V.; Waghmare, L.M.; Roy, R.G. Disturbance Observer-Based Fuzzy Adapted S-Surface Controller for Spatial Trajectory Tracking of Autonomous Underwater Vehicle. IEEE Trans. Intell. Veh. 2019, 4, 622–636. [Google Scholar] [CrossRef]
  20. Dai, Y.; Wu, D.; Yu, S.; Yan, Y. Robust control of underwater vehicle-manipulator system using grey wolf optimizer-based nonlinear disturbance observer and H-infinity controller. Complexity 2020, 2020, 6549572. [Google Scholar] [CrossRef]
  21. Guerrero, J.; Torres, J.; Creuze, V.; Chemori, A. Adaptive disturbance observer for trajectory tracking control of underwater vehicles. Ocean. Eng. 2020, 200, 107080. [Google Scholar] [CrossRef]
  22. Kamel, M.; Stastny, T.; Alexis, K.; Siegwart, R. Model predictive control for trajectory tracking of unmanned aerial vehicles using robot operating system. In Robot Operating System (ROS) the Complete Reference (Volume 2); Springer: Cham, Switzerland, 2017; pp. 3–39. [Google Scholar] [CrossRef]
  23. Veksler, A.; Johansen, T.A.; Borrelli, F.; Realfsen, B. Dynamic Positioning With Model Predictive Control. IEEE Trans. Control Syst. Technol. 2016, 24, 1340–1353. [Google Scholar] [CrossRef]
  24. Medagoda, L.; Williams, S.B. Model predictive control of an autonomous underwater vehicle in an in situ estimated water current profile. In Proceedings of the 2012 Oceans, Yeosu, Republic of Korea, 21–24 May 2012; pp. 1–8. [Google Scholar] [CrossRef]
  25. Shen, C.; Shi, Y.; Buckham, B. Trajectory Tracking Control of an Autonomous Underwater Vehicle Using Lyapunov-Based Model Predictive Control. IEEE Trans. Ind. Electron. 2018, 65, 5796–5805. [Google Scholar] [CrossRef]
  26. Cao, Y.; Li, B.; Li, Q.; Stokes, A.A.; Ingram, D.M.; Kiprakis, A. A Nonlinear Model Predictive Controller for Remotely Operated Underwater Vehicles With Disturbance Rejection. IEEE Access 2020, 8, 158622–158634. [Google Scholar] [CrossRef]
  27. Arcos-Legarda, J.; Gutiérrez, Á. Robust Model Predictive Control Based on Active Disturbance Rejection Control for a Robotic Autonomous Underwater Vehicle. J. Mar. Sci. Eng. 2023, 11, 929. [Google Scholar] [CrossRef]
  28. Robotics, B. BlueROV2: The World’s Most Affordable High-Performance ROV; BlueROV2 Datasheet; Blue Robotics: Torrance, CA, USA, 2016. [Google Scholar]
  29. Fossen, T.I. Handbook of Marine Craft Hydrodynamics and Motion Control; John Wiley & Sons: Hoboken, NJ, USA, 2011; pp. 167–183. [Google Scholar]
  30. Kane, T.R.; Likins, P.W.; Levinson, D.A. Spacecraft Dynamics; McGraw-Hill Book Company: New York, NY, USA, 1983. [Google Scholar]
  31. Chondros, T.G. Distinguished Figures in Mechanism and Machine Science: Their Contributions and Legacies Part 1; Springer: Berlin/Heidelberg, Germany, 2007; pp. 1–30. [Google Scholar]
  32. von Benzon, M.; Sørensen, F.F.; Uth, E.; Jouffroy, J.; Liniger, J.; Pedersen, S. An Open-Source Benchmark Simulator: Control of a BlueROV2 Underwater Robot. J. Mar. Sci. Eng. 2022, 10, 1898. [Google Scholar] [CrossRef]
  33. Alfian, R.I.; Ma’arif, A.; Sunardi, S. Noise reduction in the accelerometer and gyroscope sensor with the Kalman filter algorithm. J. Robot. Control 2021, 2, 180–189. [Google Scholar] [CrossRef]
  34. Bai, Y.; Wang, X.; Jin, X.; Su, T.; Kong, J.; Zhang, B. Adaptive filtering for MEMS gyroscope with dynamic noise model. ISA Trans. 2020, 101, 430–441. [Google Scholar] [CrossRef] [PubMed]
  35. Frogerais, P.; Bellanger, J.J.; Senhadji, L. Various ways to compute the continuous-discrete extended Kalman filter. IEEE Trans. Autom. Control 2011, 57, 1000–1004. [Google Scholar] [CrossRef]
  36. Butcher, J.C. A history of Runge-Kutta methods. Appl. Numer. Math. 1996, 20, 247–260. [Google Scholar] [CrossRef]
  37. Chan, L.; Naghdy, F.; Stirling, D. Extended active observer for force estimation and disturbance rejection of robotic manipulators. Robot. Auton. Syst. 2013, 61, 1277–1287. [Google Scholar] [CrossRef]
  38. Kalman, R.E.; Bucy, R.S. New results in linear filtering and prediction theory. J. Fluids Eng. 1961, 84, 95–108. [Google Scholar] [CrossRef]
  39. Diehl, M.; Bock, H.G.; Diedam, H.; Wieber, P.B. Fast direct multiple shooting algorithms for optimal robot control. In Fast Motions in Biomechanics and Robotics: Optimization and Feedback Control; Springer: Berlin/Heidelberg, Germany, 2006; pp. 65–93. [Google Scholar] [CrossRef]
  40. Verschueren, R.; Frison, G.; Kouzoupis, D.; van Duijkeren, N.; Zanelli, A.; Quirynen, R.; Diehl, M. Towards a modular software package for embedded optimization. IFAC-PapersOnLine 2018, 51, 374–380. [Google Scholar] [CrossRef]
  41. Feller, C.; Ebenbauer, C. Sparsity-exploiting anytime algorithms for model predictive control: A relaxed barrier approach. IEEE Trans. Control Syst. Technol. 2020, 28, 425–435. [Google Scholar] [CrossRef]
  42. Gharbi, M.; Ebenbauer, C. Anytime MHE-based output feedback MPC. IFAC-PapersOnLine 2021, 54, 264–271. [Google Scholar] [CrossRef]
  43. Hosseinzadeh, M.; Sinopoli, B.; Kolmanovsky, I.; Baruah, S. Robust to early termination model predictive control. IEEE Trans. Autom. Control 2023. early access. [Google Scholar] [CrossRef]
  44. Manhães, M.M.M.; Scherer, S.A.; Voss, M.; Douat, L.R.; Rauschenbach, T. UUV Simulator: A Gazebo-based package for underwater intervention and multi-robot simulation. In Proceedings of the OCEANS 2016 MTS/IEEE, Monterey, CA, USA, 19–23 September 2016. [Google Scholar] [CrossRef]
  45. Hasselmann, K.; Barnett, T.P.; Bouws, E.; Carlson, H.; Cartwright, D.E.; Enke, K.; Ewing, J.; Gienapp, A.; Hasselmann, D.; Kruseman, P.; et al. Measurements of wind-wave growth and swell decay during the Joint North Sea Wave Project (JONSWAP). In Ergaenzungsheft zur Deutschen Hydrographischen Zeitschrift, Reihe A; Deutsches Hydrographisches Institut: Hamburg, Germany, 1973; pp. 1–95. [Google Scholar]
  46. Ohhira, T.; Kawamura, A.; Shimada, A.; Murakami, T. An underwater quadrotor control with wave-disturbance compensation by a UKF. IFAC-PapersOnLine 2020, 53, 9017–9022. [Google Scholar] [CrossRef]
  47. Ullah, B.; Ovinis, M.; Baharom, M.B.; Ali, S.S.A.; Khan, B.; Javaid, M.Y. Effect of waves and current on motion control of underwater gliders. J. Mar. Sci. Technol. 2020, 25, 549–562. [Google Scholar] [CrossRef]
  48. Marechal, G.; Ardhuin, F. Surface Currents and Significant Wave Height Gradients: Matching Numerical Models and High-Resolution Altimeter Wave Heights in the Agulhas Current Region. J. Geophys. Res. Ocean. 2021, 126, e2020JC016564. [Google Scholar] [CrossRef]
  49. Li, Z.; Deng, G.; Queutey, P.; Bouscasse, B.; Ducrozet, G.; Gentaz, L.; Le Touzé, D.; Ferrant, P. Comparison of wave modeling methods in CFD solvers for ocean engineering applications. Ocean. Eng. 2019, 188, 106237. [Google Scholar] [CrossRef]
Figure 1. The reference frames of the UUV.
Figure 1. The reference frames of the UUV.
Jmse 12 00094 g001
Figure 2. The propeller configuration of the BlueROV2, propeller 1, 2, 3, and 4 provide thrust in x-y plane, while propeller 5 and 6 provide thrust in vertical direction [32].
Figure 2. The propeller configuration of the BlueROV2, propeller 1, 2, 3, and 4 provide thrust in x-y plane, while propeller 5 and 6 provide thrust in vertical direction [32].
Jmse 12 00094 g002
Figure 3. Control loop of the MPC, which mainly includes an optimizer and a prediction model.
Figure 3. Control loop of the MPC, which mainly includes an optimizer and a prediction model.
Jmse 12 00094 g003
Figure 4. Block diagram of the proposed DOBMPC scheme with disturbance compensation incorporated.
Figure 4. Block diagram of the proposed DOBMPC scheme with disturbance compensation incorporated.
Jmse 12 00094 g004
Figure 5. Disturbances estimation of periodic waves with random force and moment amplitudes.
Figure 5. Disturbances estimation of periodic waves with random force and moment amplitudes.
Jmse 12 00094 g005
Figure 6. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under periodic disturbances.
Figure 6. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under periodic disturbances.
Jmse 12 00094 g006
Figure 7. Trajectories of dynamic positioning results of the proposed DOBMPC, baseline MPC, and PID controllers under periodic disturbances.
Figure 7. Trajectories of dynamic positioning results of the proposed DOBMPC, baseline MPC, and PID controllers under periodic disturbances.
Jmse 12 00094 g007
Figure 8. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under periodic wave effect.
Figure 8. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under periodic wave effect.
Jmse 12 00094 g008
Figure 9. Disturbances estimation of constant currents in x, y, and z directions.
Figure 9. Disturbances estimation of constant currents in x, y, and z directions.
Jmse 12 00094 g009
Figure 10. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents.
Figure 10. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents.
Jmse 12 00094 g010
Figure 11. Trajectories of dynamic positioning results of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents.
Figure 11. Trajectories of dynamic positioning results of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents.
Jmse 12 00094 g011
Figure 12. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under constant currents.
Figure 12. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under constant currents.
Jmse 12 00094 g012
Figure 13. Disturbances estimation of superposition of periodic wave and constant current effect in x, y, and z directions.
Figure 13. Disturbances estimation of superposition of periodic wave and constant current effect in x, y, and z directions.
Jmse 12 00094 g013
Figure 14. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under superposition of periodic wave and constant current effect.
Figure 14. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under superposition of periodic wave and constant current effect.
Jmse 12 00094 g014
Figure 15. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under superposition of periodic wave and constant current effect.
Figure 15. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for dynamic positioning under superposition of periodic wave and constant current effect.
Jmse 12 00094 g015
Figure 16. Disturbances estimation of constant currents during circular trajectory tracking.
Figure 16. Disturbances estimation of constant currents during circular trajectory tracking.
Jmse 12 00094 g016
Figure 17. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents during circular trajectory tracking.
Figure 17. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents during circular trajectory tracking.
Jmse 12 00094 g017
Figure 18. Circular trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers in x, y, z, and yaw directions.
Figure 18. Circular trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers in x, y, z, and yaw directions.
Jmse 12 00094 g018
Figure 19. Three-dimensional circular trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers.
Figure 19. Three-dimensional circular trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers.
Jmse 12 00094 g019
Figure 20. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for tracking circular trajectory under constant currents.
Figure 20. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for tracking circular trajectory under constant currents.
Jmse 12 00094 g020
Figure 21. Disturbances estimation of periodic waves during lemniscate trajectory tracking.
Figure 21. Disturbances estimation of periodic waves during lemniscate trajectory tracking.
Jmse 12 00094 g021
Figure 22. Lemniscate trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers in x, y, z, and yaw directions.
Figure 22. Lemniscate trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers in x, y, z, and yaw directions.
Jmse 12 00094 g022
Figure 23. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents during lemniscate trajectory tracking.
Figure 23. Tracking errors of the proposed DOBMPC, baseline MPC, and PID controllers under constant currents during lemniscate trajectory tracking.
Jmse 12 00094 g023
Figure 24. Three-dimensional lemniscate trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers.
Figure 24. Three-dimensional lemniscate trajectory tracking results of the proposed DOBMPC, baseline MPC, and PID controllers.
Jmse 12 00094 g024
Figure 25. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for tracking lemniscate trajectory under periodic waves.
Figure 25. Control inputs of the proposed DOBMPC in surge, sway, heave, and yaw direction for tracking lemniscate trajectory under periodic waves.
Jmse 12 00094 g025
Table 1. Notations in the UUV dynamic model.
Table 1. Notations in the UUV dynamic model.
Surge Sway HeaveRoll Pitch Yaw
Position η x y z (m) ϕ   θ   ψ (rad)
Velocity v u v w (m/s)p q r (rad/s)
Forces and Moments τ X Y Z (N)K M N (Nm)
Control Inputs u u 1   u 2   u 3 (N)/ / u 4 (Nm)
Disturbances w X w   Y w   Z w (N) K w   M w   N w (Nm)
Measured Disturbances w X w   Y w   Z w (N)/ / N w (Nm)
Unmeasured Disturbances w / / / K w   M w / (Nm)
Added Mass X u ˙   Y v ˙   Z w ˙ (kg) K p ˙   M q ˙   N r ˙ (kgm2/rad)
Linear Damping X u   Y v   Z w (Ns/m) K p   M q   N r (Ns/rad)
Nonlinear Damping X u | u |   Y v | v |   Z w | w | (Ns2/m2) K p | p |   M q | q |   N r | r | (Ns2/rad2)
Feedback Variablesx y z (m) ϕ   θ   ψ (rad)
u v w (m/s)p q r (rad/s)
X Y Z (N)/ / N w (Nm)
Table 2. BlueROV2 rigid-body parameters defined in URDF file.
Table 2. BlueROV2 rigid-body parameters defined in URDF file.
ParameterValue
m11.26 kg
W112.8 N
B114.8 N
I x 0.3 kgm2
I y 0.63 kgm2
I z 0.58 kgm2
Table 3. BlueROV2 hydrodynamic parameters defined in URDF file.
Table 3. BlueROV2 hydrodynamic parameters defined in URDF file.
DirectionParameterValue
Surge X u ˙ 1.7182 kg
Sway Y v ˙ 0 kg
Heave Z w ˙ 5.468 kg
Roll K p ˙ 0 kgm2/rad
Pitch M q ˙ 1.2481 kgm2/rad
Yaw N r ˙ 0.4006 kgm2/rad
Surge X u −11.7391 Ns/m
Sway Y v −20 Ns/m
Heave Z w −31.8678 Ns/m
Roll K p −25 Ns/rad
Pitch M q −44.9085 Ns/rad
Yaw N r −5 Ns/rad
Table 4. MPC parameters utilized in this work.
Table 4. MPC parameters utilized in this work.
Controller ParametersValue
Prediction horizon60
Sample time (s)0.05
Q[300 300 150 10 10 150 10 10 10 10 10 10 15 15 15 0.5]
Q N [300 300 150 10 10 150 10 10 10 10 10 10]
OCP time (ms)7
Table 5. PID parameters utilized in this work.
Table 5. PID parameters utilized in this work.
Control GainSurgeSwayHeaveYaw
K p 5557
K i 0.050.050.050.1
K d 1.21.21.20.6
Table 6. RMSE of the proposed DOBMPC, baseline MPC, and PID controllers in dynamic positioning and trajectory tracking.
Table 6. RMSE of the proposed DOBMPC, baseline MPC, and PID controllers in dynamic positioning and trajectory tracking.
MotionDisturbanceDirectionPID (m)MPC (m)DOBMPC (m)
X0.13740.16890.0537
DynamicPeriodicY0.10950.19340.0605
Positioningwave effectsZ0.08710.08960.0350
Yaw0.05360.11080.0282
X0.78930.30990.0521
DynamicConstantY0.75440.28820.0482
Positioningcurrent effectsZ0.20320.15080.0469
Yaw0.78580.45470.0491
SuperpositionX1.49910.56660.0932
Dynamicof waveY1.39210.51510.0501
Positioningand currentsZ0.21790.16030.0486
Yaw0.51410.30390.1100
Circular X2.36260.80120.2924
TrajectoryConstantY1.64330.55210.2629
Trackingcurrent effectsZ0.17630.15100.0233
Yaw0.43550.63250.2582
Lemniscate X0.98540.37640.2306
TrajectoryConstantY0.77320.38440.1504
Trackingcurrent effectsZ0.08770.11330.0510
Yaw0.20590.24130.1457
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

Hu, Y.; Li, B.; Jiang, B.; Han, J.; Wen, C.-Y. Disturbance Observer-Based Model Predictive Control for an Unmanned Underwater Vehicle. J. Mar. Sci. Eng. 2024, 12, 94. https://doi.org/10.3390/jmse12010094

AMA Style

Hu Y, Li B, Jiang B, Han J, Wen C-Y. Disturbance Observer-Based Model Predictive Control for an Unmanned Underwater Vehicle. Journal of Marine Science and Engineering. 2024; 12(1):94. https://doi.org/10.3390/jmse12010094

Chicago/Turabian Style

Hu, Yang, Boyang Li, Bailun Jiang, Jixuan Han, and Chih-Yung Wen. 2024. "Disturbance Observer-Based Model Predictive Control for an Unmanned Underwater Vehicle" Journal of Marine Science and Engineering 12, no. 1: 94. https://doi.org/10.3390/jmse12010094

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