Location via proxy:   [ UP ]  
[Report a bug]   [Manage cookies]                
Next Article in Journal
Secure Dynamic Scheduling for Federated Learning in Underwater Wireless IoT Networks
Previous Article in Journal
Pressure Fluctuation Characteristics of a Pump-Turbine in the Hump Area under Different Flow Conditions
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Autonomous Underwater Vehicle (AUV) Motion Design: Integrated Path Planning and Trajectory Tracking Based on Model Predictive Control (MPC)

1
Marine Electrical Engineering College, Dalian Maritime University, Dalian 116026, China
2
Department of System and Computer Engineering, Carleton University, Ottawa, ON K1S 5B6, Canada
*
Author to whom correspondence should be addressed.
J. Mar. Sci. Eng. 2024, 12(9), 1655; https://doi.org/10.3390/jmse12091655
Submission received: 20 August 2024 / Revised: 11 September 2024 / Accepted: 13 September 2024 / Published: 16 September 2024
(This article belongs to the Section Ocean Engineering)

Abstract

:
This paper attempts to develop a unified model predictive control (MPC) method for integrated path planning and trajectory tracking of autonomous underwater vehicles (AUVs). To deal with the computational burden of online path planning, an event-triggered model predictive control (EMPC) method is introduced by using the environmental change as a triggering mechanism. A collision hazard function utilizing the changing rate of hazard as a triggering threshold is proposed to guarantee safety. We further give an illustration of how to calculate this threshold. Then, a Lyapunov-based model predictive control (LMPC) framework is developed for the AUV to solve the trajectory tracking problem. Leveraging a nonlinear integral sliding mode control strategy, we construct the contraction constraint within the formulated LMPC framework, thereby theoretically ensuring closed-loop stability. We derive the necessary and sufficient conditions for recursive feasibility, which are subsequently used to prove the closed-loop stability of the system. In the simulations, the proposed path planning and tracking control are verified separately and integrated and combined with static and dynamic obstacles.

1. Introduction

Autonomous underwater vehicles (AUVs), which are small crafts capable of autonomously executing underwater missions, boasting excellent concealment and high safety, have been widely applied in fields such as ocean exploration, environmental monitoring, and underwater rescue [1]. Tasks such as localization [2], path planning [1], trajectory tracking [3], and detection [4,5] are essential for AUVs. Path planning and trajectory tracking are the indispensable components of AUV control systems to perform tasks effectively [6].
Path planning requires algorithms to possess the ability to predict the future and select points within the environment [6]. Therefore, compared to commonly used methods such as the A* algorithm [7,8], the dynamic window approach [9], and theartificial potential field method [10,11], model predictive control (MPC), with its receding horizon feature and predictive characteristics, exhibits excellent compatibility with path planning [12].
An advanced approach to MPC was formulated in [3], emphasizing the synergy between localized planning and path tracking for autonomous vehicles. This framework introduced an enhanced MPC method, leveraging refined particle swarm optimization techniques, to tackle both planning and tracking challenges in an integrated manner. The work reported in [13] devised a path planning strategy for intelligent vehicles to avoid collisions with dynamic pedestrians, incorporating an attention-guided long short-term memory network, a modified social force model, and a systematic exploration of MPC. This methodology specifically addresses the scenario of pedestrian–vehicle interactions at unsignaled intersections, emphasizing dynamic conflict resolution. The research in [14] focused on addressing the challenge of robust collision-free formation navigation for a set of multiple unmanned surface vehicles, considering these vehicles as underactuated nonlinear systems operating under both state and input constraints. The objective was to devise a solution for these constrained unmanned surface vehicles to navigate safely while maintaining their formation.
It can be seen that MPC has a good ability to deal with dynamic obstacles. Moreover, the multi-horizon prediction into the future enables MPC to generate more executable paths [15]. However, MPC encounters the issue of high computational cost, which is unfavorable for online solutions [15]. To address the issue of computational burden, an event-triggered mechanism is often combined with MPC to solve problems. In [16], an EMPC strategy incorporating an adaptive APF was devised for autonomous electric vehicles, enabling both obstacle evasion and precise trajectory tracking. In [17], an EMPC approach was formulated to accomplish trajectory following and obstacle circumvention for a wheeled mobile robot, taking into account input constraints and external disturbances.
The complete AUV motion planning generally consists of path planning and trajectory tracking [18]. Common methods used to handle trajectory tracking include PID control [19,20], sliding mode control [21,22], backstepping control [23,24], and so on. In contrast to the majority of conventional control approaches, the distinctive strength of MPC resides in its inherent ability to systematically incorporate and manage system constraints directly within the controller’s design phase, which renders MPC an exceptionally robust platform for tackling diverse control engineering challenges [25].
In [25], an innovative LMPC framework was introduced for AUVs, leveraging computational resources through online optimization to enhance trajectory tracking performance. By incorporating a nonlinear backstepping tracking control law, the study formulated contraction constraints within the LMPC problem, theoretically ensuring closed-loop stability and optimizing the AUV’s trajectory execution. The work reported in [26] formulated a robust MPC approach tailored for AUV trajectory tracking amidst bounded disturbances. This tube-based MPC approach includes two distinct optimization tasks: the first tackles a standard MPC problem for the nominal system, establishing a reference state trajectory, while the second strives to confine the perturbed system’s state within a tube encircling this reference trajectory, thereby ensuring the robust stability of the closed-loop systems. Research work in [27] designed a trajectory tracking scheme using the sliding mode control technique in order to be robust against bounded disturbances. In order to align the planned position, [27] made strict assumptions on the reference state, i.e., that position tracking error converged while velocity error converged.
In summary, the existing research on path planning and trajectory tracking for AUVs has the following limitations. For path planning, EMPC is often only used for local obstacle avoidance during trajectory tracking (e.g., [16,17]) rather than the entire path planning process, which we believe provides a limited reduction in computational burden during planning. Furthermore, path planning with safety as a consideration focuses excessively on the degree of the collision hazard itself (e.g., [28,29]) while neglecting the changing rate of the collision hazard, which is often more closely related to environmental changes. For trajectory tracking, the use of sliding mode control methods (e.g., [27]) requires constraints on the reference trajectory that needs position tracking error to converge while velocity error converges, and due to the inherent chattering phenomenon in sliding mode control, the actual tracking performance is not ideal. Moreover, the chattering phenomenon in sliding mode control has multifaceted impacts on the system, including degrading system stability, affecting dynamic performance, damaging system hardware, reducing control accuracy, and limiting the scope of system application [30]. Existing LMPC methods typically use backstepping or linear sliding mode control (e.g., [25]) as auxiliary control laws and are mostly applied to other models rather than AUVs (e.g., [31]).
To address these issues, for path planning, this paper proposes an EMPC-based path planning algorithm operating during the entire process while leveraging the environmental changes as a triggering mechanism to reduce the computational burden. Additionally, we innovatively incorporate a collision hazard evaluation function with a threshold based on the changing rate of collision hazard, enabling the AUV to make selections between reachability and safety. For trajectory tracking, to avoid the chattering phenomenon caused by sliding mode control while ensuring the stability of MPC, this paper constructs an LMPC method for trajectory tracking using integral sliding mode control as an auxiliary control law. This approach not only guarantees stability but also ensures tracking performance, and there is no need to make additional assumptions on the reference state.
The main contributions of the paper are as follows:
(1)
An EMPC leveraging environmental changes as a triggering mechanism is developed for path planning. Compared to [1,12], our approach, by accepting feasible solutions according to environmental change not only ensures reachability but also imposes a lower computational burden.
(2)
We innovatively introduce the changing rate of the collision hazard as the condition for safety penalty. Considering the possibility that the environment itself is at a high risk, traditional methods such as [28,29] that solely rely on hazard evaluation functions to determine collision avoidance actions may cause AUsV to constantly attempt to flee in such an environment. The proposed method takes safety into account based on environmental changes, which allows a larger feasible area while balancing safety and reachability.
(3)
The LMPC augmented with integral sliding mode control as an auxiliary control law has been employed for the trajectory tracking of AUV. Compared to [27], the proposed tracking approach not only ensures tracking performance but also eliminates the chattering phenomenon without making any assumptions on the reference path (position tracking error is converged while velocity error converged).
The remaining part of this paper is organized as follows: In Section 2, we introduce our path planning method. In Section 3, we first design the auxiliary control law and then incorporate it into our LMPC-based trajectory tracking method. Feasibility and stability are proven rigorously. In Section 4, we introduce our integrated path planning and trajectory tracking method. In Section 5, we explain our simulation results. In Section 6, we draw a conclusion of our work.

2. Path Planning Method Based on EMPC and Changing Rate of Collision Hazard

In this section, we will first explain the environment and then establish a kinematic model that describes the movement of AUV, and subsequently, we will present an approach to path planning utilizing EMPC as the foundation.

2.1. Environment Description

To better illustrate our path planning methods, we will first explain the working environment of AUVs in this part. Thus, the following two assumptions are needed.
Assumption 1.
The environmental information obtained from the sensor of AUV is comprehensive.
Remark 1.
Assumption 1 differs from the limit that “Global information is known”. Here, we require that all environmental information within the sensor’s range is known, rather than requiring that the entire global information is previously known.
Assumption 1 imposes a prerequisite for path planning, The credibility of sensor information typically serves as the foundation for path planning and even the motion design of AUVs, as exemplified in [1,32]. Therefore, to pursue more precise path planning, the formulation of Assumption 1 is reasonable. Meanwhile, to facilitate the description of obstacle constraints, we make the following assumption.
Assumption 2.
All obstacles can be completely enclosed by circular areas.
Assumption 2 requires that circular areas be able to enclose obstacles. In fact, existing methods often use polygons or circles to enclose irregular obstacles such as [33]. In the real situation, the enclosed areas of these rules will simplify the description of obstacle constraints and simplify the calculation of MPC [33]. Here, for the sake of convenience, we uniformly use circular areas to enclose obstacles.
Assumptions 1 and 2 limit the path planning problem to an environment where sensor detection is possible and obstacle information can be formulated, laying a foundation for us to subsequently develop a path planning method based on MPC.

2.2. AUV Kinematics

Given the AUV’s sway velocity being substantially lower than its surge velocity, the nonholonomic kinematic equations effectively model the vehicle’s motion dynamics at the velocity level with sufficient accuracy, as demonstrated in [1]. Thus, the AUV motion in the horizontal plane is
x ˙ = u 1 cos ψ ν 1 sin ψ v cos ψ y ˙ = u 1 sin ψ + ν 1 cos ψ v sin ψ ψ ˙ = r 1 = ω
where x , y , ψ is the desired position and orientation; u 1 , ν 1 , r 1 are surge, sway, and yaw velocities; v is the resultant tangential velocity of the vehicle; and ω is the angular velocity. This can be written as
x ˙ = h ( x , u )
where x = x , y , ψ T is the state of the system, u = v , ω T is the input.
MPC can be used for real-time path planning, but due to its computationally intensive nature, it is difficult to ensure the efficiency of online planning when using MPC. Additionally, existing path planning methods often prioritize reachability as the primary goal, but in hazardous situations, safety should be the primary consideration.
Therefore, the main objective in path planning of this paper is as follows: Plan a collision-free path for AUV (2) while ensuring computational efficiency, requiring the capability of trading off the priorities of reachability and safety.

2.3. Path Planning Method Based on EMPC

In this part, we aim to outline our proposed path-planning method. Crucial components of our method will be introduced next.
Problem 1.
Define t k as the event-triggered time. Let x tar = x t a r , y t a r , ψ t a r T denote the target point; g i ( t k ) denote the ground penalty which is the basic penalty of the environment; A s ( t k ) denote the collision hazard evaluated at t k , which is the risk assessment at t k  [29], M s u m denote the total number of obstacles; and A δ denote the threshold of changing rate of collision hazard. For ξ t k , t k + N p , the optimal problem can be formulated as
min u , x J p ( x ( t k ) , u ( t k ) ) s . t . x ˙ ( ξ | t k ) = h ( x ( ξ | t k ) , u ( ξ | t k ) ) x ( ξ | t k ) X p u ( ξ | t k ) U p | | x ( ξ | t k ) x ̲ i | | 2 + | | y ( ξ | t k ) y ̲ i | | 2 | | r ̲ i | | 2 ( i [ 1 , M s u m ] )
where the cost function is
J p ( x ( t k ) , u ( t k ) ) = J a ( x ( t k ) , u ( t k ) + t k t k + N p κ A δ ( ξ | t k ) S ) d ξ , J a ( x ( t k ) , u ( t k ) ) = t k t k + N p ( | | x ( ξ | t k ) x tar | | Q 2 + | | u ( ξ | t k ) | | R 2 + | | j = 1 M s u m g j ( ξ | t k ) | | P ) d ξ ,
N p is the prediction horizon; Q, R, P and S are weighting matrices; X p and U p are, respectively, the region of state and input of AUV system (2); ( x ̲ i , y ̲ i ) is the position; and r ̲ i is the radius of the ith obstacle. κ is a constant relevant to A δ , let D A s ( t ) = Δ A s ( t ) Δ A s ( t 1 ) ,
κ = 1 Δ D A s 0 , A s A δ o r D A s < 0 , A s β 0 Δ D A s 0 , A s < A δ o r D A s < 0 , A s < β
where Δ A s ( t ) = 1 T ( A s ( t ) A s ( t 1 ) ) , β is a positive constant to ensure that κ does not switch continuously around A δ .
The weights Q, R, P, and S are assigned based on the current objectives that need to be achieved, with a higher value assigned to the weight corresponding to the primary goal. Typically, to ensure reachability, Q is set to a relatively large value. Furthermore, to prioritize safety in critical situations, S, as the weight for the collision hazard function, needs to be set to a significantly high value. The ground penalty g ( t ) is used to prevent the AUV from driving closely along the boundary of obstacles. A s ( t ) , on the other hand, is a penalty based on safety, ensuring that the AUV prioritizes safety before reachability when it is in a dangerous situation. The setting of A δ provides a boundary for switching between reachability and safety.

2.4. Event-Triggered Mechanism

Due to the significant computational load of MPC, it is challenging to ensure the efficiency of online planning. Therefore, we decide to introduce an event-triggered mechanism to enhance computational efficiency.
Since MPC can generate a sequence of optimal moves in a single computation, we propose to only re-plan when the environment changes (i.e., re-compute MPC). If the environment remains unchanged, we will utilize the previously computed feasible solution. Thus, we first need to define what a change in the environment is.

2.4.1. Definition of Environment Change

We categorize the following main cases as belonging to the realm of environmental changes.
(1)
New obstacles are added or existing obstacles are reduced.
(2)
The obstacle changes from stationary to dynamic.
(3)
The velocity or orientation of a dynamic obstacle changes (i.e., it does not match the previously predicted motion state).
Remark 2.
As a supplementary note to the third point, the presence of obstacles with constant speed and heading in the environment is not considered a change in the environment, as their subsequent positions and impact on our AUV can be predicted.
In particular, there are some other special cases in which we need to recalculate the MPC.
(1)
A new penalty term is added to the cost function (for instance, A s ( t ) is added when Δ A s ( t ) A δ ).
(2)
All feasible solutions obtained from a single MPC computation have been exhausted.
At these special moments, a trigger is also required.
Moreover, since it is difficult to mathematically explain how to avoid the Zeno phenomenon based on environmental changes as a triggering mechanism, we make the following assumption while considering practical situations.
Assumption 3.
There exists a minimal time ς > 0 during two changing actions of the environment.
Remark 3.
From a practical perspective, this assumption is reasonable. Firstly, the finite obstacles present in the environment are unlikely to be constantly altering their navigation postures. Additionally, in real-world scenarios, there exists a sampling time, where ς > 0 is equal to this sampling time, such as [16,17].

2.4.2. Determination of Environmental Change

Based on the conclusions of [28,29], the collision hazard evaluation function typically takes into account factors such as the relative speed, angle, and distance between ships. Therefore, the collision hazard evaluation function can effectively describe environmental information in a mathematical manner.
According to [28,29], the collision hazard evaluation function can be formulated as
A s ( t ) = j = 1 M s u m K t ( d m i n d j ( t ) ) q v R ( t ) 2
where d m i n represents the minimum safe distance, d j ( t ) represents the distance between AUV and the jth obstacle, v R ( t ) is the relative speed, K t is a positive constant, and q 1 .
Therefore, we can predict the value of A s ( t ) at a fixed point regardless of our AUV to determine if the environment has changed, as shown in Figure 1. A is a fixed point; O 1 , O 2 , O 3 are stationary obstacles; and T S 1 , T S 2 are dynamic obstacles whose velocities are v T S 1 and v T S 2 , respectively.
At time t, we can predict A s ( t ) in the future N steps of fixed point A, written as A s 1 A , A s 2 A , A s 3 A , , A s N A , which is relevant to t , t + 1 , t + 2 , , t + N 1 .
Compare the predicted collision hazard with the actual calculated collision hazard. If they are not equal, it indicates that the environment has changed, and the MPC needs to be recalculated. Therefore, the event-triggered mechanism based on environment changes can be given by
t k + 1 = min t ˜ k + 1 , t k + N p
where
t ˜ k + 1 = ξ : A s ( t ) A s . A
The upper and lower bounds for the inter-event time Δ k + 1 are specified as Δ m a x = N p Δ m i n = ς , respectively. Thus, Zeno behavior can be avoided because of the designed event-triggered mechanism (5).

2.5. Design of Changing Rate-Based Collision Hazard Function

The existing literature, such as [28,29], often advocates for determining collision avoidance based on whether a ship is in a high-risk situation (i.e., checking if A s ( t ) exceeds a certain collision hazard threshold). However, ships may inherently operate in high-risk environments, resulting in A s ( t ) continuously being treated as a penalty in the cost function. This defeats the original purpose of setting a threshold. The threshold is intended to enable the system to switch between reachability and safety. If A s ( t ) is constantly included, the AUV will first escape to a safe area and then re-ensure reachability in a safer environment, significantly increasing the path length and consequently energy consumption. Moreover, paths in high-risk environments are not necessarily unusable. If the AUV always prioritizes safety, it may become overly conservative, losing its ability to operate in complex scenarios.
Therefore, this paper proposes using the rate of change in risk A δ as a condition to determine whether to include A s as a penalty, which is analogous to how an airbag in a car deploys based on acceleration.

Calculation of A δ

As shown in Figure 2, if we consider the most extreme scenario, then the AUV and the dynamic obstacle are at the minimum safe distance from each other, and they are moving towards each other. The following equation can be satisfied.
| | v s u m | | m a x = | | v O S | | m a x + | | v T S | | m a x
d j = d m i n _ T S + d m i n _ O S = d m i n
where v s u m is the resultant velocity.
At this time,
A s l i m = K t ( d m i n d m i n _ T S + d m i n _ O S ) q ( v s u m ) 2 = K t ( v s u m ) 2
where A s l i m is the extreme collision hazard.
The extreme changing rate of the collision hazard is when it changes from 0 to A s l i m within a sampling step. And if we consider all the obstacles, it can be formulated as
A δ = 1 T j = 0 M s u m K t ( v s u m j ) 2
where v s u m j is the resultant velocity with the jth obstacle.
Specifically, when the obstacle is stationary, the resultant velocity is the velocity of our AUV.

2.6. Algorithm of the Proposed Path Planning Method

The path planning algorithm is summarized as Algorithm 1.
Algorithm 1 Path Planning Method based on EMPC and changing rate of collision hazard
Input: 
v (resultant tangential velocity), ω (yaw velocity)
Output: 
x (position)
 1:
Given the initial state x 0 of AUV and total duration t t o t a l
 2:
Calculate the changing rate threshold A δ by (8)
 3:
Set a fixed point A to judge if the environment changes
 4:
t = 0
 5:
while  t t t o t a l  do
 6:
    Evaluate the collision hazard of environment A s ( t ) by (4)
 7:
    Calculate the changing rate of collision hazard Δ A s ( t )
 8:
    Predict the collision hazard of A in the future steps, written as A s 1 A , A s 2 A , A s 3 A , , A s N A
 9:
    if  Δ A s ( t ) A δ  then
10:
        Use J p as cost function
11:
    else
12:
        Use J a as cost function
13:
    Solve Problem 1 to obtain the input sequence u 0 , u 1 , u 2 , , u N 1
14:
    Use u 0 as input at time t
15:
     t = t + 1 , k = 1
16:
    for  k N 1  do
17:
        if  A s ( t + k + 1 ) = = A s k A  then
18:
           Use u k as input at time t + k
19:
            k = k + 1
20:
        else
21:
            t = t + k 1
22:
           break
23:
Record the position x and input u
Remark 4.
In contrast to [29,32,34], which solely emphasizes the magnitude of collision hazard, the path planning method presented in this paper innovatively incorporates the changing rate of collision hazard. This additional consideration enables a more comprehensive assessment of potential hazards and allows a larger feasible area for planning since our method can work in a high collision hazard environment but [29,32,34] attempts to flee from such environment. Furthermore, by employing EMPC to balance between feasible and optimal solutions, our approach enhances planning efficiency. Consequently, the paths generated by our method are not only safer but also more rational, as they account for both the current risk level and its trend over time.

3. Trajectory Tracking Method Based on LMPC

In this section, we will introduce a trajectory-tracking method based on LMPC. Integral sliding mode control is used as an auxiliary controller.

3.1. AUV Dynamics

Based on the study of underwater vehicles in [35], we can model the AUV as follows:
η ˙ = R ( ψ ) v M v ˙ + C ( v ) v + D ( v ) v + g ( η ) = τ
where η = x , y , ψ T is the position and heading of the AUV; v = u , ν , r T is the velocity of the vehicle; and R ( ψ ) is the rotation matrix depending on the heading ψ .
R ( ψ ) = cos ( ψ ) sin ( ψ ) 0 sin ( ψ ) cos ( ψ ) 0 0 0 1
M is the inertia matrix including added mass, C ( v ) is the state-dependent matrix of Coriolis and centripetal terms, D ( v ) is the hydrodynamic damping and lift matrix, g ( η ) is the vector of gravitational forces and moments, and τ = τ u , τ v , τ r T is the vector of thrust forces and moments and the generalized control input is expressed as τ = B u , where B is the control matrix and the control input is defined as u = u 1 , u 2 , u 3 , u 4 T .
Additionally, by selecting the center of gravity as the origin of the body-fixed reference frame, the system matrices can be simplified as M = diag ( M u ˙ , M v ˙ , M r ˙ ) and D ( v ) = diag ( X u , Y v , N r ) + diag ( D u u , D v ν , D r r ) , g ( η ) = 0 and
C ( v ) = 0 0 M v ˙ 0 0 M u ˙ M v ˙ ν M u ˙ 0
M x = m X u ˙ , M y = m Y v ˙ , and M ψ = I z N r ˙ are inertia terms including added mass; X u , Y v and N r are linear drag terms; and D u , D v , and D r are corresponding quadratic drag terms. The overall control system model is built as follows:
x ˙ = R ( ψ ) v M 1 ( τ C ( v ) v D ( v ) v ) = f ( x , τ ) .
where the state is defined as x = x , y , ψ , u , ν , r T .
The main objective of trajectory tracking can be summarized as follows: Using the planned path x D from Algorithm 1 as a reference, control AUV (13) converges to a planned path x D by LMPC while using integral sliding mode control as an auxiliary control law.

3.2. Trajectory Tracking Method Based on LMPC

Reference states and reference inputs can be constructed based on the information obtained through path planning. The reference state can be obtained as follows.
η D = x = x D , y D , ψ D , u = v D , u D = v , ν D = 0 , r D = ω
where η D is the reference position and v D is the reference velocity. Therefore, the reference state x D is
x D = x D , y D , ψ D , v , 0 , ω
Moreover, the reference input τ D can be obtained from (10). Thus, the problem of trajectory tracking based on LMPC can be formulated as follows.
Problem 2.
Let τ h ( . ) denote the auxiliary Lyapunov-based nonlinear tracking control law and let V ( . ) be the corresponding Lyapunov function; the optimal problem can be formulated as
min τ , x J t ( x ( t ) , τ ( t ) ) = 0 N 1 ( x ( s ) , τ ( s ) ) d s
s . t . x ˙ ( s ) = f ( x ( s ) , τ ( s ) )
| τ ( s ) | τ max
V x f ( x ( 0 ) , τ ( 0 ) ) V x f ( x ( 0 ) , τ h ( 0 ) )
where ( x , τ ) = ( x x D ) T Q t ( x x D ) + ( τ τ D ) T R t ( τ τ D ) , N is the prediction horizon, Q t and R t are weighting matrices.
The introduction of the contraction constraint (16d) facilitates our demonstration that the LMPC controller inherits the inherent stability traits of τ h , enabling a precise outline of a guaranteed region of attraction. Additionally, owing to the real-time optimization process, the LMPC controller dynamically executes optimal tracking control, adhering to the system’s physical constraints, thereby optimizing performance while ensuring system stability [25].

3.3. Design of Auxiliary Tracking Controller

In this part, we will construct the auxiliary tracking controller using integral sliding mode control.
Firstly, we define the following tracking position errors:
e x = x x D e y = y y D e ψ = ψ ψ D
Taking the derivative of (17) and substituting in (13), we have
e ˙ x = x ˙ x ˙ D = u cos ( ψ ) ν sin ( ψ ) x ˙ D e ˙ y = y ˙ y ˙ D = u sin ( ψ ) + ν cos ( ψ ) y ˙ D e ˙ ψ = ψ ˙ ψ ˙ D = r r D
Taking the derivative of (18), we have
e ¨ x = u ˙ cos ( ψ ) u r sin ( ψ ) ν ˙ sin ( ψ ) ν r cos ( ψ ) x ¨ D e ¨ y = u ˙ sin ( ψ ) + u r cos ( ψ ) + ν ˙ cos ( ψ ) ν r sin ( ψ ) y ¨ D e ¨ ψ = r ˙ r ˙ D
To devise the trajectory tracking auxiliary integral sliding mode controller, we shall select sliding surfaces with the objective of
s = c e + e ˙ + λ 0 t e ( τ ) d τ
where s = s 1 , s 2 , s 3 T , c = c 1 , c 2 , c 3 T , e = e 1 , e 2 , e 3 T , λ = λ 1 , λ 2 , λ 3 T , c 1 , c 2 , c 3 and λ 1 , λ 2 , λ 3 are positive constants. Taking the derivative of these sliding mode surfaces and substitute in (13), we have
s ˙ 1 = c 1 e ˙ x + e ¨ x + λ 1 e x = c 1 ( u cos ( ψ ) ν sin ( ψ ) x ˙ D ) + λ 1 ( x x D ) + ( M y M x ν r X u M x u D u M x u | u | + τ u h M x ) cos ( ψ ) u r sin ( ψ ) ( M x M y u r Y v M y ν D v M y ν | ν | + τ v h M y ) sin ( ψ ) ν r cos ( ψ ) x ¨ D
s ˙ 2 = c 2 e ˙ y + e ¨ y + λ 2 e y = c 1 ( u sin ( ψ ) ν cos ( ψ ) y ˙ D ) + λ 2 ( y y D ) + ( M y M x ν r X u M x u D u M x u | u | + τ u h M x ) sin ( ψ ) + u r cos ( ψ ) + ( M x M y u r Y v M y ν D v M y ν | ν | + τ v h M y ) cos ( ψ ) ν r sin ( ψ ) y ¨ D
s ˙ 3 = c 3 e ˙ ψ + e ¨ ψ + λ 3 e ψ = c 3 ( r r D ) + M x M y M ψ u ν N r M ψ r D r M ψ r | r | + τ r h M ψ
To guarantee the convergence of these sliding surfaces to zero within a finite time frame, the subsequent dynamics will be applied to the sliding surfaces.
s ˙ 1 = k 1 s 1 W 1 s i g n ( s 1 ) s ˙ 2 = k 2 s 2 W 2 s i g n ( s 2 ) s ˙ 3 = k 3 s 3 W 3 s i g n ( s 3 )
where k 1 , k 2 , k 3 and W 1 , W 2 , W 3 are positive constants.
Let
A s 1 = k 1 s 1 W 1 s i g n ( s 1 ) + x ¨ D + ν r cos ( ψ ) + u r sin ( ψ ) c 1 ( u cos ( ψ ) ν sin ( ψ ) x ˙ D ) λ 1 ( x x D ) M y M x ν r cos ( ψ ) + X u M x u cos ( ψ ) + D u M x u | u | c o s ( ψ ) M x M y u r sin ( ψ ) Y v M y ν sin ( ψ ) D v M y ν | ν | sin ( ψ )
and
B s 2 = k 2 s 2 W 2 s i g n ( s 2 ) + y ¨ D + ν r sin ( ψ ) u r cos ( ψ ) c 2 ( u sin ( ψ ) + ν cos ( ψ ) y ˙ D ) λ 2 ( y y D ) M y M x ν r sin ( ψ ) + X u M x ν sin ( ψ ) + D u M x u | u | sin ( ψ ) + M x M y u r cos ( ψ ) + Y v M y ν cos ( ψ ) + D v M y ν | ν | cos ( ψ )
Thus, we have
A s 1 = τ u h M x cos ( ψ ) τ v h M y sin ( ψ ) B s 2 = τ u h M x sin ( ψ ) + τ v h M y cos ( ψ )
From (27), we can obtain
τ u h = M x ( cos ( ψ ) A s 1 + sin ( ψ ) B s 2 ) τ v h = M y ( sin ( ψ ) A s 1 + cos ( ψ ) B s 2 )
Similarly, we can obtain
τ r h = M ψ s ˙ 3 M ψ c 3 ( r r D ) M ψ λ 3 ( ψ ψ D ) ( M x M y ) u ν + N r r + D r r | r |
And the Lyapunov function candidate can be formulated as
V = 1 2 s 1 2 + 1 2 s 2 2 + 1 2 s 3 2
Taking the derivative of (30), we have
V ˙ = s 1 s ˙ 1 + s 2 s ˙ 2 + s 3 s ˙ 3 = k 1 s 1 2 W 1 | s 1 | k 2 s 2 2 W 2 | s 2 | k 3 s 3 2 W 3 | s 3 | 0
Based on the standard Lyapunov proof, the closed-loop system under conditions (28) and (29) is globally asymptotically stable.

3.4. Recursive Feasibility and Stability of LMPC

Now, we will first analyze the recursive feasibility of Problem 2 and then explain the stability.

3.4.1. Feasibility Analysis

Theorem 1.
Suppose Assumptions 1–3 hold. Suppose the reference state x D and reference input from Algorithm 1 are obtained before trajectory tracking. Let ( τ ¯ u h , τ ¯ v h , τ ¯ r h ) denote the upper bound of ( τ u h , τ v h , τ r h ) , respectively. For Problem 2, if τ max max τ ¯ u h , τ ¯ v h , τ ¯ r h is satisfied, then τ h τ max can hold. LMPC (16) admits recursive feasibility.
Proof. 
We observe that, given the current system state x ( t ) , τ h ( t ) is always feasible for the LMPC problem (16), if the condition τ h τ max is satisfied. To prove that τ h τ max holds, we will transform this problem into a specific one.
We observe the auxiliary control laws derived from (28) and (29). Since M x , M y , M ψ , X u , Y v , N r and D u , D v , D r are fundamental parameters of the vessel, they are constants, and all the reference path parameters η D , η ˙ D and η ¨ D are also determined once the path planning is completed. Therefore, the parameter that can influence the inequality τ h τ max is the velocity v . Hence, to ensure that the auxiliary control laws satisfy τ h τ max , we need to guarantee that v has an upper bound.
From (10), we can obtain
v = R T ( ψ ) η ˙
Since R T ( ψ ) = max { | cos ψ | + | sin ψ | , 1 } 2 , we further obtain
v 2 η ˙
In order to obtain η ˙ , we will perform the following transformation.
η ˙ = η ˙ η ˙ D + η ˙ D η ˙ η ˙ D + η ˙ D = e ˙ + η ˙ D
η ˙ D is a certain number after path planning is finished; let
η ˙ D = η ˙ ¯ D = x ˙ ¯ D , y ˙ ¯ D , ψ ˙ ¯ D
From (30), we have
η ( t ) η D ( t ) 2 η ( 0 ) η D ( 0 ) 2
In other words, we can reformulate it as
e ( t ) 2 = η ( t ) η D ( t ) 2 η ( 0 ) η D ( 0 ) 2 = e ( 0 ) 2
Further, according to (20), we have
e ˙ = s c e λ 0 t e ( τ ) d τ
Therefore, we have
e ˙ = s c e λ 0 t e ( τ ) d τ s + ce + λ 0 t e ( τ ) d τ
Due to the sign-preserving property of integration and the fact that e ( t ) e ( t ) 2 e ( 0 ) 2 , we have
| | e ˙ | | 0 + c m a x e ( 0 ) 2 + t λ m a x e ( 0 ) 2 = ( c m a x + t λ m a x ) e ( 0 ) 2
where c m a x = max c 1 , c 2 , c 3 and λ m a x = λ 1 , λ 2 , λ 3 .
Substituting in (34), we have
η ˙ ( c m a x + t λ m a x ) e ( 0 ) 2 + η ˙ ¯ D
Thus,
v v ¯ = 2 ( c m a x + t λ m a x ) e ( 0 ) 2 + 2 η ˙ ¯ D
From the AUV model, we have the fact that the initial matrix is symmetric positive definite and upper bounded: > M ¯ I M = M T > 0 [25].
Therefore, substituting in C ( v ) and D ( v ) , we have
| | C ( v ) | | C ¯ = 2 ( c m a x + t λ m a x ) e ( 0 ) 2 M ¯ + 2 η ˙ ¯ D M ¯
| | D ( v ) | | D ¯ = 2 D ¯ 1 + 2 D ¯ 2 ( c m a x + t λ m a x ) e ( 0 ) 2 M ¯ + η ˙ ¯ D M ¯
where D ¯ 1 = max | X u | , | Y v | , | N r | and D ¯ 2 = max D u , D v , D r .
Substituting (37), (41), (43), (44) in (25), (26), we have
A s 1 A ¯ s 1 = x ¨ D + v ¯ 2 cos ( ψ ) + v ¯ 2 sin ( ψ ) + c 1 | | η ˙ η ˙ D | | + λ 1 | | η η D | | + C ¯ v ¯ cos ( ψ ) + D ¯ v ¯ sin ( ψ ) = x ¨ D + 2 v ¯ 2 + c 1 ( c m a x + t λ m a x ) e ( 0 ) 2 + λ 1 e ( 0 ) 2 + v ¯ C ¯ 2 + D ¯ 2
and
B s 2 B ¯ s 2 = y ¨ D + v ¯ 2 sin ( ψ ) + v ¯ 2 cos ( ψ ) + c 2 | | η ˙ η ˙ D | | + λ 2 | | η η D | | + C ¯ v ¯ sin ( ψ ) + D ¯ v ¯ cos ( ψ ) = y ¨ D + 2 v ¯ 2 + c 2 ( c m a x + t λ m a x ) e ( 0 ) 2 + λ 2 e ( 0 ) 2 + v ¯ C ¯ 2 + D ¯ 2
Therefore, substituting (45) and (46) in (28), we have
τ u h = A s 1 2 + B s 2 2 M x ( A s 1 A s 1 2 + B s 2 2 cos ( ψ ) + B s 2 B s 2 2 + B s 2 2 sin ( ψ ) ) A ¯ s 1 2 + B ¯ s 2 2 M x = τ ¯ u h
τ v h = A s 1 2 + B s 2 2 M y ( A s 1 A s 1 2 + B s 2 2 sin ( ψ ) + B s 2 B s 2 2 + B s 2 2 cos ( ψ ) ) A ¯ s 1 2 + B ¯ s 2 2 M y = τ ¯ v h
Similarly, we have
τ r h M ψ c 3 | | η ˙ η ˙ D | | + M ψ λ 3 | | η η D | | + C ¯ + D ¯ M ψ c 3 ( c m a x + t λ m a x ) e ( 0 ) 2 + λ 3 e ( 0 ) 2 + C ¯ + D ¯ = τ ¯ r h
Thus,
| | τ h | | = max τ ¯ u h , τ ¯ v h , τ ¯ r h
Thus, if τ max max τ ¯ u h , τ ¯ v h , τ ¯ r h is satisfied, then τ h τ max holds. The proposed LMPC is recursively feasible.    □
It is noteworthy that the integral sliding mode controller merely serves as a preliminary estimation for the optimization problem (16) without being directly implemented on the system. Consequently, the auxiliary controller ensures feasibility, while the LMPC controller refines the control performance through optimization, achieving a more effective control strategy.

3.4.2. Asymptotic Stability Analysis

Theorem 2.
Suppose Assumption 1–3 holds. Suppose the reference state x D and reference input from Algorithm 1 are obtained before trajectory tracking. Then, the closed-loop system is asymptotically stable; i.e., the AUV will converge to the planned path x D with the control law τ based on LMPC.
Proof. 
Regarding the stability proof, given that all feasible solutions satisfy the constraint imposed by (16d) in Problem 2, and considering the fact that the constructed auxiliary controller satisfies V ˙ 0 according to (31), we can consequently prove the stability by combining these two conditions. The formulaic representation of this proof can be stated as follows: According to converse Lyapunov theorems [36], there exists functions α i ( . ) , i = 1 , 2 , 3 which belong to class K such that the following inequalities hold:
α 1 ( x ) V ( x ) α 2 ( x ) V x f ( x , τ h ) α 3 ( x )
According to (16d), we have
V x f ( x , τ ) V x f ( x , τ h ) α 3 ( x )
Utilizing the Lyapunov argument, we claim that the closed-loop system is asymptotically stable, with a guaranteed region of attraction denoted by R (where R is the set of rational numbers).    □

3.5. Algorithm of Proposed Trajectory Tracking Method

Our algorithm can be summarized as Algorithm 2.
Algorithm 2 Trajectory Tracking Method based on LMPC
Input: 
x 0 (initial state)
Output: 
τ (current input), x (next state)
1:
Given an initial state x 0
2:
t = 0
3:
for  t t m a x   do
4:
    Solve Problem 2 to get the predictive sequence of τ
5:
    Use the first item of the sequence of τ as the (sub-)optimal solution at the current time
6:
     t = t + 1
Remark 5.
In Algorithm 2, the adoption of suboptimal solutions is entirely acceptable and highly desirable for any nonlinear MPC algorithm, given the following pivotal facts. Firstly, owing to the nonlinearity of the system dynamics, the best-guaranteed solution to (16) obtained through iterative methods is inherently a local optimum. Crucially, when deploying on embedded platforms with limited computational prowess, restricting the iteration count becomes essential to sustain real-time control. This implies embracing suboptimal strategies, offering a crucial balance between numerical efficiency and control effectiveness. This enables a straightforward trade-off by specifying the maximum iteration count, ensuring that the stability of the tracking control remains intact while optimizing for computational efficiency.
Remark 6.
Compared to [27], the method proposed in this paper offers several key advantages. Firstly, it does not impose restrictions on the reference trajectory, such as requiring both position and velocity to converge simultaneously in [27]. Instead, it directly addresses position errors, thereby providing a broader range of applicability. Furthermore, by utilizing LMPC for trajectory tracking, our approach avoids the chattering phenomenon inherent in simple sliding mode control methods employed in [27]. Additionally, the convergence speed and tracking performance achieved by our LMPC-based approach surpass those of simply using sliding mode trajectory tracking, demonstrating its superiority in terms of both stability and accuracy.

4. Integrated Path Planning and Trajectory Tracking Method of AUV

The integrated EMPC-based path planning and LMPC-based trajectory tracking framework of AUV is illustrated in Figure 3. The planner calculates the environmental collision hazard A s ( t ) and its rate Δ A s ( t ) of change based on the actual state and judges whether it is necessary to re-plan or introduce new penalties; the tracking controller tracks the reference path x D obtained from planning, using LMPC τ with the integral sliding mode control as an auxiliary control law τ h .

5. Simulation Results

5.1. Path Planning

First, we will validate path planning. We set the parameters as follows: the sampling time is T = 0.2 s, the prediction horizon in path planning is N p = 10 , and the weighting matrices are as follows: Q = diag ( 1 , 5 , 0.1 ) , R = 0.01 , P = 1 , S = 7 , maximal velocity is v m a x = 0.8 m/s, minimal velocity is v m i n = v m a x , maximal angular velocity is ω m a x = π / 4 rad/s, and minimal angular velocity is ω m i n = ω m a x . The changing rate threshold is set as A δ = 67 (m/s)2, where K t = 3 .
As shown in Figure 4, Figure 4a represents the initial environment, where there are two dynamic obstacles. However, they are both in a static state for an initial period of time. When they start moving, their speeds are as follows: One of them moves solely horizontally with a speed of 0.025 m/s, while the other moves both horizontally with a speed of 0.005 m/s and vertically with a velocity of 0.01 m/s. The red line segments indicate the predicted sequence of the path generated by the MPC path planner. In the period when the dynamic obstacle is initially stationary, MPC is not updated (i.e., only utilizing the feasible solution without recalculation), AUV will follow the entire predicted sequence of the path, instead of strictly utilizing the first item of the predicted sequence, as illustrated in Figure 4b. When the dynamic obstacle begins to move, MPC recalculates, and at this point, instead of utilizing a feasible solution, it employs the optimal solution as input, as depicted in Figure 4c, where the black hollow circles represent the initial position of dynamic obstacles. Figure 4d–f, illustrate the collision avoidance process of AUV with dynamic obstacles. Since the speed and direction of the obstacle remained unchanged, feasible solutions were used throughout the entire process. Figure 4g demonstrates that AUV has successfully completed the collision avoidance, and Figure 4h shows that AUV has finally reached its target point. Figure 5 shows the velocity and angular velocity changes during path planning.
Other situations are shown in Figure 6 and Figure 7. Meanwhile, in order to verify the improvement of computing efficiency by an event-triggered mechanism, we recorded the number of MPC calculations in the above three environments, as shown in Table 1. It can be seen that under the action of an event-triggered mechanism, the calculation time of MPC decreases significantly.

5.2. Trajectory Tracking

In this section, we will validate the proposed trajectory tracking algorithm using the sine function and conduct a comparative analysis with the straightforward approach of employing integral sliding mode control. The parameter of LMPC settings are outlined as follows: M u ˙ = 283.6 ,   M v ˙ = 593.2 ,   M r ˙ = 29 , X u = 26.9 ,   Y v = 35.8 ,   N r = 3.5 , D u = 241.3 ,   D v = 503.8 ,   D r = 76.9 , the initial state is set as x = ( 0 , 0 , π / 3 , 0 , 0 , 0 ) T , the prediction horizon is N = 10 , the sampling time is T = 0.2 s, the total duration is set to 120 0.2 = 24 s, the weighting matrices are Q t = diag ( 10 4 , 10 4 , 10 3 , 10 , 10 , 10 ) , R t = 10 ( 8 ) I , and I is unit matrix. The parameters of integral sliding mode control are c 1 = 6 , c 2 = 6 , c 3 = 6 , k 1 = 3 , k 2 = 2 , k 3 = 2 , W 1 = 0.1 , W 2 = 0.1 , W 3 = 0.1 , λ 1 = 1 , λ 2 = 3 , λ 3 = 0.4 , which is the same as the auxiliary controller.
Figure 8 illustrates the simulation results of trajectory tracking using both integral sliding mode control and LMPC. In this figure, the blue line represents the reference trajectory, the green line denotes the tracking trajectory achieved by integral sliding mode control, and the red line indicates the tracking trajectory by LMPC. It can be seen that the chattering phenomenon occurs when the sliding mode control is used, which affects the tracking effect. However, LMPC outperforms the straightforward application of integral sliding mode control in terms of tracking performance. Moreover, LMPC exhibits a significantly faster convergence speed in the initial stage compared to integral sliding mode control, and it is capable of avoiding the chattering phenomenon that may occur in integral sliding mode control. Figure 9 depicts the state tracking performance, and it can be observed that the integral sliding mode control exhibits relatively large tracking errors in the initial stage, requiring a longer convergence time to the reference trajectory compared to LMPC. Furthermore, the chattering phenomenon significantly impacts the tracking performance across each dimension. Figure 10 shows the simulation results of the input signals.

5.3. Integrated Path Planning and Trajectory Tracking

In this section, we will conduct simulation validation for the proposed integrated path planning and trajectory tracking approach. All parameter selections are identical to those previously defined, and the environment setup for the path planning component remains unchanged from previous discussions. Figure 11 presents the simulation results, demonstrating that the proposed method can effectively accomplish the task of integrated path planning and trajectory tracking with satisfactory performance. Figure 12 illustrates the input results for this simulation.

6. Conclusions

This paper presented a comprehensive approach that integrates path planning and trajectory tracking for AUVs. During the path planning phase, we employed an event-triggered mechanism to reduce the computational load of path planning. Furthermore, a collision hazard function utilizing the changing rate of hazard as a threshold was proposed to ensure safety. We subsequently elaborated on how to calculate this threshold. In the trajectory tracking phase, we constructed an LMPC trajectory tracking method with integral sliding mode control serving as an auxiliary control law. This approach not only guaranteed stability and feasibility but also outperformed the direct application of integral sliding mode control in terms of performance. In the future, we will endeavor to optimize the computational complexity of LMPC and make fuller use of the prediction horizon in MPC for path planning.

Author Contributions

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

Funding

This work was supported in part by the National Natural Science Foundation of China under Grants 52171292 and 51939001, in part by Dalian Outstanding Young Talents Project under Grant 2022RJ05.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The original contributions presented in the study are included in the article; further inquiries can be directed to the corresponding author.

Conflicts of Interest

The author declares no conflicts of interest.

References

  1. Shen, C.; Shi, Y.; Buckham, B.J. Integrated Path Planning and Tracking Control of an AUV: A Unified Receding Horizon Optimization Approach. IEEE/ASME Trans. Mechatron. 2017, 22, 1163–1173. [Google Scholar] [CrossRef]
  2. Ullah, I.; Adhikari, D.; Khan, H.; Anwar, M.S.; Ahmad, S.; Bai, X. Mobile robot localization: Current challenges and future prospective. Comput. Sci. Rev. 2024, 53, 100651. [Google Scholar] [CrossRef]
  3. Zuo, Z.; Yang, X.; Li, Z.; Wang, Y.; Han, Q.; Wang, L.; Luo, X. MPC-Based Cooperative Control Strategy of Path Planning and Trajectory Tracking for Intelligent Vehicles. IEEE Trans. Intell. Veh. 2021, 6, 513–522. [Google Scholar] [CrossRef]
  4. Ullah, I.; Chen, J.; Su, X.; Esposito, C.; Choi, C. Localization and detection of targets in underwater wireless sensor using distance and angle based algorithms. IEEE Access 2019, 7, 45693–45704. [Google Scholar] [CrossRef]
  5. Su, X.; Ullah, I.; Liu, X.; Choi, D. A review of underwater localization techniques, algorithms, and challenges. J. Sens. 2020, 2020, 6403161. [Google Scholar] [CrossRef]
  6. Huang, Y.; Chen, L.; Chen, P.; Negenborn, R.R.; Van Gelder, P. Ship collision avoidance methods: State-of-the-art. Saf. Sci. 2020, 121, 451–473. [Google Scholar] [CrossRef]
  7. Lin, Z.; Wu, K.; Shen, R.; Yu, X.; Huang, S. An Efficient and Accurate A-Star Algorithm for Autonomous Vehicle Path Planning. IEEE Trans. Veh. Technol. 2024, 73, 9003–9008. [Google Scholar] [CrossRef]
  8. Votion, J.; Cao, Y. Diversity-Based Cooperative Multivehicle Path Planning for Risk Management in Costmap Environments. IEEE Trans. Ind. Electron. 2019, 66, 6117–6127. [Google Scholar] [CrossRef]
  9. Lee, D.H.; Lee, S.S.; Ahn, C.K.; Shi, P.; Lim, C.C. Finite Distribution Estimation-Based Dynamic Window Approach to Reliable Obstacle Avoidance of Mobile Robot. IEEE Trans. Ind. Electron. 2021, 68, 9998–10006. [Google Scholar] [CrossRef]
  10. Pan, Z.; Zhang, C.; Xia, Y.; Xiong, H.; Shao, X. An Improved Artificial Potential Field Method for Path Planning and Formation Control of the Multi-UAV Systems. IEEE Trans. Circuits Syst. II Express Briefs 2022, 69, 1129–1133. [Google Scholar] [CrossRef]
  11. Szczepanski, R. Safe Artificial Potential Field–Novel Local Path Planning Algorithm Maintaining Safe Distance from Obstacles. IEEE Robot. Autom. Lett. 2023, 8, 4823–4830. [Google Scholar] [CrossRef]
  12. Deng, S.Y.; Hao, L.Y.; Wu, Z.J. Path Planning Scheme for AUV Based on Improved Model Predictive Control. In Proceedings of the 2023 IEEE 2ND Industrial Electronics Society Annual Online Conference, New York, NY, USA, 8–10 December 2023. [Google Scholar]
  13. Chen, H.; Zhang, X. Path Planning for Intelligent Vehicle Collision Avoidance of Dynamic Pedestrian Using Att-LSTM, MSFM, and MPC at Unsignalized Crosswalk. IEEE Trans. Ind. Electron. 2022, 69, 4285–4295. [Google Scholar] [CrossRef]
  14. Wen, G.; Lam, J.; Fu, J.; Wang, S. Distributed MPC-Based Robust Collision Avoidance Formation Navigation of Constrained Multiple USVs. IEEE Trans. Intell. Veh. 2024, 9, 1804–1816. [Google Scholar] [CrossRef]
  15. Wei, H.; Shi, Y. MPC-based motion planning and control enables smarter and safer autonomous marine vehicles: Perspectives and a tutorial survey. IEEE/CAA J. Autom. Sin. 2022, 10, 8–24. [Google Scholar] [CrossRef]
  16. Yang, H.; Wang, Z.; Xia, Y.; Zuo, Z. EMPC with adaptive APF of obstacle avoidance and trajectory tracking for autonomous electric vehicles. ISA Trans. 2023, 135, 438–448. [Google Scholar] [CrossRef]
  17. Li, P.; Wang, S.; Yang, H.; Zhao, H. Trajectory Tracking and Obstacle Avoidance for Wheeled Mobile Robots Based on EMPC With an Adaptive Prediction Horizon. IEEE Trans. Cybern. 2022, 52, 13536–13545. [Google Scholar] [CrossRef]
  18. Gan, W.Y.; Zhu, D.Q.; Xu, W.L.; Sun, B. Survey of trajectory tracking control of autonomous underwater vehicles. J. Mar. Sci. Technol. 2017, 25, 13. [Google Scholar]
  19. Moreno-Valenzuela, J.; Pérez-Alcocer, R.; Guerrero-Medina, M.; Dzul, A. Nonlinear PID-Type Controller for Quadrotor Trajectory Tracking. IEEE/ASME Trans. Mechatron. 2018, 23, 2436–2447. [Google Scholar] [CrossRef]
  20. Iqbal, U.; Samad, A.; Nissa, Z.; Iqbal, J. Embedded control system for autarep—A novel autonomous articulated robotic educational platform. Teh.-Vjesn.-Tech. Gaz. 2014, 21, 1255–1261. [Google Scholar]
  21. Zhai, J.; Xu, G. A novel non-singular terminal sliding mode trajectory tracking control for robotic manipulators. IEEE Trans. Circuits Syst. II Express Briefs 2020, 68, 391–395. [Google Scholar] [CrossRef]
  22. Nie, R.; He, W.; Du, W.; Lang, Z.; He, S. Dynamic Event-Triggered SMC of Multi-Agent Systems for Consensus Tracking. IEEE Trans. Circuits Syst. II Express Briefs 2022, 69, 1188–1192. [Google Scholar] [CrossRef]
  23. Sabiha, A.D.; Kamel, M.A.; Said, E.; Hussein, W.M. ROS-based trajectory tracking control for autonomous tracked vehicle using optimized backstepping and sliding mode control. Robot. Auton. Syst. 2022, 152, 104058. [Google Scholar] [CrossRef]
  24. Davila, J. Exact Tracking Using Backstepping Control Design and High-Order Sliding Modes. IEEE Trans. Autom. Control 2013, 58, 2077–2081. [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. 2017, 65, 5796–5805. [Google Scholar] [CrossRef]
  26. Hao, L.Y.; Wang, R.Z.; Shen, C.; Shi, Y. Trajectory Tracking Control of Autonomous Underwater Vehicles Using Improved Tube-Based Model Predictive Control Approach. IEEE Trans. Ind. Inform. 2024, 20, 5647–5657. [Google Scholar] [CrossRef]
  27. Elmokadem, T.; Zribi, M.; Youcef-Toumi, K. Trajectory tracking sliding mode control of underactuated AUVs. Nonlinear Dyn. 2016, 84, 1079–1091. [Google Scholar] [CrossRef]
  28. Zhang, W.; Goerlandt, F.; Kujala, P.; Wang, Y. An Advanced Method For Detecting Possible Near Miss Ship Collisions from AIS Data. Ocean Eng. 2016, 124, 141–156. [Google Scholar] [CrossRef]
  29. Johansen, T.A.; Pérez, T.; Cristofaro, A. Ship Collision Avoidance and COLREGS Compliance Using Simulation-Based Control Behavior Selection with Predictive Hazard Assessment. IEEE Trans. Intell. Transp. Syst. 2016, 17, 3407–3422. [Google Scholar] [CrossRef]
  30. Iqbal, J. Modern control laws for an articulated robotic arm. Eng. Technol. Appl. Sci. Res. 2019, 9, 4057–4061. [Google Scholar] [CrossRef]
  31. Xu, B.; Suleman, A.; Shi, Y. A multi-rate hierarchical fault-tolerant adaptive model predictive control framework: Theory and design for quadrotors. Automatica 2023, 153, 111015. [Google Scholar] [CrossRef]
  32. Wang, Y.; Wang, C.; Zhao, W.; Xu, C. Decision-Making and Planning Method for Autonomous Vehicles Based on Motivation and Risk Assessment. IEEE Trans. Veh. Technol. 2021, 70, 107–120. [Google Scholar] [CrossRef]
  33. Liu, Z.; Zhu, D.; Liu, C.; Yang, S.X. A novel path planning algorithm of AUV with model predictive control. Int. J. Robot. Autom. 2022, 37, 460–467. [Google Scholar] [CrossRef]
  34. Wang, H.; Lu, B.; Li, J.; Liu, T.; Xing, Y.; Lv, C.; Cao, D.; Li, J.; Zhang, J.; Hashemi, E. Risk Assessment and Mitigation in Local Path Planning for Autonomous Vehicles With LSTM Based Predictive Model. IEEE Trans. Autom. Sci. Eng. 2022, 19, 2738–2749. [Google Scholar] [CrossRef]
  35. Fossen, T.I. Marine Control Systems Guidance, Navigation, and Control of Ships, Rigs and Underwater Vehicles; Marine Cybernetics: Trondheim, Norway, 2002. [Google Scholar]
  36. Zhu, Q. Nonlinear Systems; MDPI-Multidisciplinary Digital Publishing Institute: Basel, Switzerland, 2023. [Google Scholar]
Figure 1. Determination of environment change by using fixed point A.
Figure 1. Determination of environment change by using fixed point A.
Jmse 12 01655 g001
Figure 2. AUV in limiting cases.
Figure 2. AUV in limiting cases.
Jmse 12 01655 g002
Figure 3. Integrated path planning and trajectory tracking framework of AUV.
Figure 3. Integrated path planning and trajectory tracking framework of AUV.
Jmse 12 01655 g003
Figure 4. (a) Initial environment. (b) Use of feasible solutions (not updating MPC). (c) Environment changes (MPC planner updates). (d) Collision avoidance (1). (e) Collision avoidance (2). (f) Collision avoidance (3). (g) Collision avoidance successful. (h) Reach. The red triangle is our AUV, the green triangle is the target position, the green circle is the obstacle, the black circle is the initial position of the dynamic obstacle, and the red dashed line segment is the predicted trajectory.
Figure 4. (a) Initial environment. (b) Use of feasible solutions (not updating MPC). (c) Environment changes (MPC planner updates). (d) Collision avoidance (1). (e) Collision avoidance (2). (f) Collision avoidance (3). (g) Collision avoidance successful. (h) Reach. The red triangle is our AUV, the green triangle is the target position, the green circle is the obstacle, the black circle is the initial position of the dynamic obstacle, and the red dashed line segment is the predicted trajectory.
Jmse 12 01655 g004
Figure 5. The velocity of path planning.
Figure 5. The velocity of path planning.
Jmse 12 01655 g005
Figure 6. Initial obstacles positions’ messages: ( 1 , 1 ) , ( 0.5 , 0.5 ) , ( 0 , 2 ) , ( 0.5 , 0.5 ) , ( 0.5 , 1 ) , ( 2 , 1 ) , ( 0.7 , 2 ) . (a) Initial environment. (b) Planning result.
Figure 6. Initial obstacles positions’ messages: ( 1 , 1 ) , ( 0.5 , 0.5 ) , ( 0 , 2 ) , ( 0.5 , 0.5 ) , ( 0.5 , 1 ) , ( 2 , 1 ) , ( 0.7 , 2 ) . (a) Initial environment. (b) Planning result.
Jmse 12 01655 g006
Figure 7. Initial obstacles’ positions messages: ( 0.6 , 0.4 ) , ( 0.7 , 0.25 ) , ( 0.8 , 2 ) , ( 0.5 , 2 ) , ( 0.1 , 1 ) , ( 2 , 1 ) , ( 0.5 , 0.5 ) , ( 0 , 1.5 ) , ( 1.5 , 0.5 ) , ( 1 , 0.5 ) . (a) Initial environment. (b) Planning result.
Figure 7. Initial obstacles’ positions messages: ( 0.6 , 0.4 ) , ( 0.7 , 0.25 ) , ( 0.8 , 2 ) , ( 0.5 , 2 ) , ( 0.1 , 1 ) , ( 2 , 1 ) , ( 0.5 , 0.5 ) , ( 0 , 1.5 ) , ( 1.5 , 0.5 ) , ( 1 , 0.5 ) . (a) Initial environment. (b) Planning result.
Jmse 12 01655 g007
Figure 8. The tracking results.
Figure 8. The tracking results.
Jmse 12 01655 g008
Figure 9. The state trajectories.
Figure 9. The state trajectories.
Jmse 12 01655 g009
Figure 10. The control input signals.
Figure 10. The control input signals.
Jmse 12 01655 g010
Figure 11. Integrated path planning and trajectory tracking.
Figure 11. Integrated path planning and trajectory tracking.
Jmse 12 01655 g011
Figure 12. Input of integrated path planning and trajectory tracking.
Figure 12. Input of integrated path planning and trajectory tracking.
Jmse 12 01655 g012
Table 1. Calculation times of the MPC.
Table 1. Calculation times of the MPC.
No Event-Triggered MechanismEvent-Based
Figure 414119
Figure 616321
Figure 717224
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

Deng, S.-Y.; Hao, L.-Y.; Shen, C. Autonomous Underwater Vehicle (AUV) Motion Design: Integrated Path Planning and Trajectory Tracking Based on Model Predictive Control (MPC). J. Mar. Sci. Eng. 2024, 12, 1655. https://doi.org/10.3390/jmse12091655

AMA Style

Deng S-Y, Hao L-Y, Shen C. Autonomous Underwater Vehicle (AUV) Motion Design: Integrated Path Planning and Trajectory Tracking Based on Model Predictive Control (MPC). Journal of Marine Science and Engineering. 2024; 12(9):1655. https://doi.org/10.3390/jmse12091655

Chicago/Turabian Style

Deng, Si-Yi, Li-Ying Hao, and Chao Shen. 2024. "Autonomous Underwater Vehicle (AUV) Motion Design: Integrated Path Planning and Trajectory Tracking Based on Model Predictive Control (MPC)" Journal of Marine Science and Engineering 12, no. 9: 1655. https://doi.org/10.3390/jmse12091655

APA Style

Deng, S.-Y., Hao, L.-Y., & Shen, C. (2024). Autonomous Underwater Vehicle (AUV) Motion Design: Integrated Path Planning and Trajectory Tracking Based on Model Predictive Control (MPC). Journal of Marine Science and Engineering, 12(9), 1655. https://doi.org/10.3390/jmse12091655

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