Next Article in Journal
Decreasing Vulnerability of Storm Surge Disasters in Coastal Cities of China over the Past 30 Years
Previous Article in Journal
Model and Simulation of a Floating Hybrid Wind and Current Turbines Integrated Generator System, Part I: Kinematics and Dynamics
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Receding Horizon Navigation and Control System for Autonomous Merchant Ships: Reducing Fuel Costs and Carbon Emissions under the Premise of Safety

1
Transport and Communications College, Shanghai Maritime University, Shanghai 201306, China
2
Merchant Marine College, Shanghai Maritime University, Shanghai 201306, China
*
Author to whom correspondence should be addressed.
These authors contributed equally to this work.
J. Mar. Sci. Eng. 2023, 11(1), 127; https://0-doi-org.brum.beds.ac.uk/10.3390/jmse11010127
Submission received: 7 December 2022 / Revised: 20 December 2022 / Accepted: 27 December 2022 / Published: 6 January 2023
(This article belongs to the Section Ocean Engineering)

Abstract

:
In order to solve the multi-objective planning and trajectory tracking control problem related to maritime autonomous surface ships (MASSs), a new design scheme for autonomous navigation is proposed in this paper, with a receding horizon navigation and control (RHNC) system that contains navigation and control modules. In the navigation module, we designed a superposition field gradient descent local search algorithm based on the cost field, emission field, and guidance field to navigate the MASS reference path, and in the control module, we designed a nonlinear controller that can handle multiple constraints based on the NMPC framework. Under the new scheme, the navigation module completes local path planning to reduce costs and emissions, the control module accomplishes accurate trajectory tracking and real-time collision avoidance, and the information is transmitted in both directions between the two modules to collaboratively complete the MASS navigation and control tasks. We conducted a simulation study of the navigation algorithm and controller and the autonomous navigation system using a Kriso Container ship (KCS). The simulation results demonstrate the effectiveness of the proposed cooperative design scheme in reducing navigation costs and emissions and avoiding autonomous collision avoidances.

1. Introduction

Reducing costs, emissions, and collision avoidance in ship navigation has always been an hot topic in the field of marine engineering research, and the regulations on energy consumption and emissions issued by the International Maritime Organization (IMO), such as the Energy Efficiency Existing ship Index (EEXI) and the Carbon Intensity Indicator (CII), have brought the costs and emissions incurred in ship navigation into focus. With the development of artificial intelligence, unmanned vehicles, and advanced communication technologies, these hot issues are also at the forefront of research on maritime autonomous surface ships (MASSs). To achieve the goal of economic, green, and safe navigation, the route design becomes a complex multi-objective task, which is very challenging for the MASS navigation system. In order to reduce this burden, more research is needed, for example, by putting the safety objectives of navigation into the control system to solve. Therefore, the navigation and control modules in the MASS navigation system need to be designed to accomplish multi-objective autonomous navigation.
Guidance, navigation, and control (GNC) [1], the classical structure in autonomous navigation systems, contains a navigation module and a control module. Under the GNC structure, the path planning algorithm of the navigation module determines the reference path for the generation of trajectory information, which then determines the design of the controller and controls the control decision variables by the designed controller to finally maneuver the ship and track the reference trajectory. Path planning and trajectory tracking are the underlying processes of the navigation and control modules, which at this stage have generated abundant research on path planning and tracking control.
Path planning is usually divided into global and local path planning based on the type of environmental information [2]. Global path planning finds a safe path from the initial state to the target state considering known obstacles and assuming a complete environment model is available [3], so it is widely used in guidance systems for unmanned ships, robots, autonomous underwater vehicles, and unmanned vehicles. Grid-based global path planning was originally proposed in the form of Dijkstra’s algorithm [4,5]. The latter is a heuristic algorithm compared to Dijkstra’s algorithm, which also incorporates obstacle avoidance. Refs. [6,7] used the A* algorithm to plan weather routes, and in [8], it was applied to the path planning of unmanned surface vehicles (USVs). A constrained A* method was proposed for the optimal path planning of unmanned vehicles in constrained marine environments, with a vector map representing sea currents superimposed on a binary map to simulate static environmental disturbances, which are robust and computationally efficient for the global path planning of unmanned vessels under moving obstacles. An APF-based multi-directional a* algorithm was proposed in [9] to generate safer and shorter navigation trajectories within wind farm waters. To address the limitations of existing global path planning methods in which path planning is independent of the USV control phase, ref. [10] proposed an A*-VVGO algorithm that implements velocity variation by adding a temporal dimension to the map modeling process, which provides a new way to avoid obstacles compared to traditional path planning methods. In addition, in order to ensure the security of the path, the above algorithm introduces an artificial potential field method in map modeling.
From the above, it is clear that the A* algorithm has many applications and has been the subject of in-depth studies in the field of global path planning. In addition to the above two methods, the ant colony algorithm, which is an intelligent swarm algorithm, is also used for global path planning, which has good convergence and can find the globally optimal path [2,11,12]. The global path planning method is to find a suitable path between start and end points according to a search algorithm under the premise that the environmental information is known, which has limitations in scenarios where the environmental information is partially unknown and often requires improvements to achieve dynamic planning. In terms of safety, a static and dynamic obstacle layout in the environment is needed for global path planning before effective collision avoidance can be achieved.
Local planning methods often show good applicability when a ship only has access to local environmental information during navigation and needs to focus on the surrounding environment to avoid collisions with other ships. Local path planning algorithms include dynamic window [13], velocity obstacle [14], and artificial potential field (APF) [15]. The dynamic window algorithm (DWA) was used in [3] for local path planning to track the global path by tracking the intersection of global and local paths, avoiding dynamic obstacles. Artificial potential field (APF) methods are mathematically elegant and simple for dynamically complex conditions, but easily fall into local optimality; in [16], APF was improved so that it could be moved out of local optimality. A hybrid method was proposed in [17] based on the global planner A* algorithm and local planner APF method, called the multiple subgoal artificial potential field (MTAPF) algorithm, which can guarantee the optimality, rationality, and path continuity of the formation trajectory. This combined global and local planning method had significant optimization effects. A field simulating electromagnetic wave propagation was constructed in [18] via the fast marching method, which had no local minima problem and reduced the computational burden. Local path planning utilizes local environmental information around a ship, considers sensor information for situational awareness, and emphasizes avoiding nearby dynamic obstacles to generate feasible and safe paths. Often, the purpose of local path planning in existing studies is to avoid obstacles, especially dynamic obstacles.
Including carbon emissions under the premise of considering cost will inevitably make the ship’s routes more complicated. The challenges brought by carbon emissions coupled with ship control multivariate characteristics require us to use advanced nonlinear multi-constraint control methods as technical support for the control module to accomplish accurate trajectory tracking. In tracking control, most traditional research has focused on linear control techniques, such as PID [1]; however, ship dynamics are highly nonlinear, and nonlinear factors, such as wind and wave disturbances, and hydrodynamic damping can adversely affect the performance of the ship. At present, the research on ship motion control is mainly focused on the underdriven ship trajectory tracking control problem, which is better applied in the design of automatic rudders and track rudders. The commonly used robust control methods include sliding mode control (SMC), H∞ control, neural network control, and optimal control, among others [19]. A controller combining SMC and backstepping techniques was used in [20,21], showing good robustness. Ref. [22] designed a data-driven neural predictor based on integral parallel learning that does not require the support of a kinematic model. Ref. [23] proposed a method for robust neural network control with a new performance function, two additional terms, the radial basis function (RBF) neural network (NN), and the command filter backpropagation method, which can handle AUV trajectory tracking in unknown environments compared to conventional methods.
Although all of the above methods have good robustness and some of the neural network control algorithms can get rid of the dependence of traditional control algorithms on environmental information, a ship is subject to dynamic state constraints and the control constraints of rudder angle and main engine speed during motion, and there are certain limitations in the processing of these constraints via these methods. In contrast, model predictive control (MPC) can handle complex constraints very well [24,25]. In [26], the performance of H∞ and MPC was compared, and the conclusion was that the MPC controller performed better in terms of accuracy and response time under good driving conditions. For the nonlinear problem (NLP) of underactuated surface vessel tracking control, combined nonlinear model predictive control (NMPC) was used in [27] to transform static and dynamic object collision avoidance into a constraint problem embedded in MPC, further demonstrating the advantage of MPC in handling multiple constraints. An improved MPC was proposed in [28] based on global heading constraints (GCCs) and the event triggering mechanism (ETM), which ultimately optimized the deviation according to its predictive capability and energy saving-effect. Ref. [29] proposed a kind of collision avoidance constraint based on the ship safety domain, and a collision risk index (CRI) event trigger was added based on DCPA/TCPA, which is in turn based on the embedded collision avoidance constraint. This not only enables collision avoidance for dynamic and static obstacles of a smart ship but also reduces the computational complexity of the NMPC controller and the computation time of the system. The above studies illustrate that MPC, a control method that is more capable of handling multiple dynamics constraints, is well suited for MASS motion control.
In a study on combining navigation and control, the artificial potential field method and multi-constrained model predictive control (MMPC) were combined in [30] to complete path planning and trajectory tracking control, and it describes the tracking task as a multi-constraint model predictive control (MMPC) problem. In [31], the A* algorithm was combined with the sliding mode control approach as the underlying technique for an integrated path planning and trajectory tracking control framework. The path planning algorithm was used to find an optimal and smooth path while avoiding static and dynamic obstacles, and a pure path tracking approach was used to convert the generated geometric path into a time-dependent trajectory profile, which can serve as instructions for the trajectory tracking controller. In [32], the path planning problem was transformed into a rolling optimization problem. Combined with the NMPC controller, a unified rolling time-domain optimization scheme was proposed to solve the underwater survey path planning and trajectory tracking problem for AUVs. It is thus clear that the combination of navigation and control is ultimately a collaborative optimization of path planning and tracking control algorithms.
Most of the existing studies on path planning focus on global path planning with the goal of optimizing time [33] or energy consumption [34], or on safety-oriented local planning [35]. Studies also use a hybrid approach considering both [17], where global planning is mostly static, and local planning situations are mainly dynamic and static with collision avoidance planning, where safety is the top priority when avoiding collisions. As for the problem studied in this paper, the global and local planning algorithms have certain limitations. It is difficult to balance the three goals of cost reduction, emission reduction, and collision avoidance, and the combination of traditional control and path planning algorithms is not sufficient enough; there is only one-way information transfer between the two modules, which is not conducive to autonomous MASS navigation. Therefore, in this paper, the multi-objective path planning problem in MASS navigation is transformed into a search problem of the lowest point of the superposition potential field, the tracking control problem is transformed into an optimization problem of error dynamics in the design of the controller, and the ship dynamic and collision avoidance constraints are systematically added to this optimization problem, in order to take into account the three major objectives of ship navigation. The output of tracking control optimization is fed back into the path searching problem as information to provide starting state updates as the next moment of the path seeking optimization, forming a closed-loop structure between path planning and controller for collaborative optimization. In addition, in this paper, we also design an event trigger mechanism to close the potential cost and carbon emission field when the obstacle reaches the emergency hazard collision avoidance range of the ship, with navigation safety as the top priority.
The contributions of this study are as follows:
  • The design of a new autonomous navigation system is proposed, which accomplishes the economic and green goals of navigation in the path planning module and ensures the safety of navigation in the control module;
  • Based on the superposition of fields, cost and emission fields according to their consumption rate are constructed, and guided fields are designed to transform the path search problem into a gradient descent optimization problem to solve the multi-objective path planning problem of MASS;
  • A navigation and control system framework for path planning and rolling NMPC tracking control co-optimization is designed for the problem of determining whether the reference trajectory and tracking controller track with high accuracy during multi-objective planning.
The rest of the paper is organized as follows: The problem statement is given in Section 2. Section 3 gives the specific procedure of establishing the potential field and the design of the path planning algorithm. Section 4 gives the design process of the three-degree-of-freedom model and controller for ship motion and collision avoidance constraints. Section 5 presents the design process of the real-time navigation and control system. Section 6 verifies the local path planning algorithm and the effectiveness of the system through simulation. Finally, Section 7 gives the conclusion.

2. Problem Statement

2.1. Problem Description

In the ocean, the density of ships is low, weather conditions are more complex compared with nearshore disturbance, and collision avoidance behavior is less frequent as well, so when a MASS is sailing in the ocean, most of the time, it is important to consider reducing fuel consumption and emissions during the voyage. Therefore, in this paper, we proposed a new solution to the MASS navigation and control problem, in which we transformed the multi-objective optimization problem into a superposition field seeking problem and put the collision avoidance problem into the control module to solve, which is closer to the actual movement of the ship than the navigation module. In addition, the ship’s motion system has the characteristics of time delay, large inertia, nonlinearity, and underdrive; therefore, precise tracking control of the complex trajectory of the ship has high requirements for both controller and path planning. It is often difficult for offline path planning to meet the precise trajectory tracking, and the synergy between navigation and control must be exploited to better accomplish the autonomous navigation task. Therefore, how to design a navigation and control system so that the ship can accurately track complex routes under multi-objective navigation decisions is the main problem to be solved in this paper.
From the above, it is clear that the mission of the MASS navigation system involves the following three aspects:
(i)
A guidance module for multi-objective path planning;
(ii)
A control module for precise trajectory tracking and to guarantee navigation safety;
(iii)
The collaborative optimization of guidance and control for information interaction and synergy optimization between navigation and control modules.

2.2. Framework of Receding Horizon Navigation and Control System

The navigation and control system framework proposed in this paper aimed toward multi-objective planning and trajectory tracking control for MASS ocean voyages and keeping the ship as close to the planned trajectory as possible while ensuring safety. At the beginning of each sampling moment, new planning was performed according to the change in the positional state of the ship to achieve real-time planning. Figure 1 gives the general architecture, and the core of the system is the navigation and the control modules.
In the navigation module, we transformed the wind, wave, and current environment of navigation into a superposed potential field covering costs and emissions as well as the shortest circuit target, performed a path search based on that field, turned the path points into trajectory points by adding time constraints, and transformed the reference trajectory points into state volume references via Equation (19). In the control module, we designed an objective optimization function for MASS trajectory tracking which contained two nonlinear performance metrics: the error between the reference state volume and the ship’s predicted state volume, and the rate of change in the control variables (rudder angle and propeller speed). The multiple constraints for nonlinear optimization included control variable constraints (rudder angle and propeller speed) and ship dynamic constraints [29]. In addition, to ensure that the path planning of multiple targets did not negatively affect autonomous collision avoidance, the collision avoidance mechanism was triggered when the radar detected an obstacle nearby, acting simultaneously on both the navigation and control modules: the cost potential field was turned off, and the collision avoidance constraint was turned on.

3. Guidance Module

Field theory is a concept of physics that involves the distribution of and changes in physical quantities in space [36], and the ability to superpose fields is applicable to the model construction of multiple targets; therefore, we designed the cost, emission, and guidance fields in this section, where the cost field and emission field are functions of the economic cost and increased CO 2 emissions per unit time, and the guidance field is a function related to the distance of the target point and the “yaw” direction. The guidance field is a function related to the distance of the target point and the yaw direction (relative to the ship heading along the shortest path). The path search of the navigation module is based on the superimposed field environment, and the process of multi-objective route planning is the gradient descent process of the superimposed field. In addition, in order to prevent the path navigated by this module from affecting the collision avoidance performance of the subsequent control module when considering cost and emission reduction, we designed an event-triggering mechanism to switch between the regular navigation state and the collision avoidance state, and only the guidance field was retained to function in the latter.

3.1. Fields Based on Cost and Emission

The cost and emission fields are based on equations by [37,38] for the energy consumption of a ship while sailing at sea as a function of sea state, as follows (descriptions of parameters are given in Table 1):
P = K ( P s + P w + P a ) + P a u x K = η ( v , H 1 3 ) = m a x ( 1 η ( j + k · v v d ) , 1 η ( 1 r · H 1 3 ) ) P s = ρ · C t s · S · v 3 2 ( m · n D W T + ( 1 n ) ) P w = C w · ρ · g · ( H 1 3 2 ) 2 · B 2 L · ( v + u ) P a = C a · ρ a · A · ( v + u a ) 3 2
With known energy consumption (EC), the cost per unit time and carbon emissions (EM) can be determined by the following equation:
E C = P · k f · C f u e l + C c 24 v s
E M = P · k f · k e
where k f is the fuel consumption per KW·h, and C f u e l is the fuel price. In addition to fuel, the operating costs of a ship are expressed as C c . P is the main power of the vessel, and k e is the CO 2 emission per unit of fuel consumed.
Compared to the raster method [11], based on fields, the environment of an unmanned ship navigating at sea can be portrayed in a more continuous manner. Figure 2 shows the cost potential field; it is on the basis of the map regarding the weather data, according to Equations (1) and (2), and the construction of the cost function is the basis for the navigation module to perform path planning.

3.2. Guidance Field

The guidance field, the design of which is based on the idea of the gravitational field in the APF method [15], is an artificial virtual potential field used to describe the cost of the distance to the end point, and the potential energy value of the gravitational field is specified as a function of being proportional to the distance to the end point to ensure that the potential energy at the end point is the lowest. However, the motion of an unmanned ship has a course, and the steering of the ship will consume a lot of energy, so the concept of direction is added to the design of the guidance field. The guidance field (Figure 3) represents the time penalty of the path point, and this field drawn on the basis of Equation (4):
G = r v · ε · e ( ψ φ ) 2 2 c 2
where r indicates that the distance between the destination and other points on the map, and v indicates that ship’s speed. ε and c are constants. ψ is the angle between the line connecting the center point of the ship and the target point and the north direction, and φ is the north angle of the line between each point on the map and the end point. In Figure 3, a small value in the dark area of the color bar represents a low strength of the potential field.

3.3. Field Renewable Local Path Planning Algorithm

3.3.1. Superposition of Fields

From Equations (2) and (3), it can be seen that there were inconsistencies in magnitude between the cost, emission, and the guidance fields, so we needed to normalize the models of all three to solve the problem of the big difference in the scale. So, the normalization treatment was used:
F ¯ = F F L F U F L
In Equation (5), L is lower boundary and U is upper boundary, F ¯ means the normalized value, F L means the minimum value number in a series of F values, and F U means the maximum number in a series of F values. Correspondingly, the value of the potential energy of the superposition field can be calculated by:
U = k 1 · E C ¯ + k 2 · E M ¯ + k 3 · G ¯
In Equation (6), k 1 , k 2 , and k 3 are the weight coefficients, and k 3 is bigger than k 1 and k 2 ; EC is the form of fuel cost and charter cost; EM is emission costs; E C ¯ expresses the EC after normalization; E M ¯ expresses the EM after normalization; and G expresses the field energy of the guiding field. U expresses the potential energy of the superposition field. The cost field (Figure 2), the emission field (calculated by Equation (3) just like the cost field), and the guidance field are summed by the weights; then, we can obtain the superposition field U, which is shown in Figure 4.

3.3.2. Event Trigger Mechanism

Safety (collision avoidance) is the primary goal of MASS navigation, so we designed an event-triggering mechanism to ensure that MASSs can respond more comfortably when facing collision avoidance situations. The trigger function ET is only related to the distance k from the ship to the obstacle:
E T = 0 , k > ε 1 , k ε
As shown in Algorithm 1, steps 12–17, when the radar detects a static or dynamic obstacle within range ε , the MASS is transformed from the navigation state to the collision avoidance state, and the event-triggering mechanism gives a signal back to the navigation module to turn off this field, then re-enables it when the ship has passed the obstacle.

3.3.3. Path Planning Based on Superposition Field

In the superimposed field map, the guide field constructs a decreasing gradient to ensure that the field energy at the endpoint is the lowest, while the field energy at the location of the ship is high, and the points in the map at the line of the ship’s location and endpoint are lower than other angle. The cost and emission of the MASS can be expressed as the repulsive potential P O ( X , Y ) during the voyage, and the guide field provides the gravitational potential P R ( X , Y ) .
P O ( X , Y ) = E C ¯ + E M ¯ P R ( X , Y ) = G ¯
Superimposing the repulsive potential with the attractive potential, the total potential function is just:
P U ( X , Y ) = P O ( X , Y ) + P R ( X , Y )
The negative gradient of the potential field can be considered as a gravitational force, which guides the ship to move towards the course of the end point. By following the direction of the induced force, the energy of the cost is minimized. Since the ship navigation is attracted by the guiding potential and repelled by the cost potential [30], in a physical sense, total force F U is a combination of repulsive force F O and gravitational force F R . After the field strength of the map is determined at a specific moment, the corresponding full gradient direction and contour of the map can be found (Figure 5). Figure 5 shows the gradient map calculated from the superposition field map (Figure 4); in Figure 5, we can observe the gradient direction of each region on the map (indicated by blue arrows). The curves on the map are contour lines, and on the same curve, the potential energy of each point is the same; the darker the color of the curve, the lower its potential energy. The total force on the ship at a determined point (x,y) on the map is:
F = P U ( X , Y )
Algorithm 1 is the pseudo-code for local path planning with N steps at a time. In Algorithm 1, we use ▽(p(k)) to denote the gradient direction of the current position and α (k) to denote the previous step length of the current cyclic order. In order to make the path obtained from the search conform to the law of ship motion and allow it to be easily transformed into a trajectory, we assume that the value of step size is equal to the value of the ship’s speed v s . The flow of the algorithm can be briefly described as:
  • Calculate guide field Gk and initial superposition field U k according to Equations (1)–(6).
  • Judge whether the vessel is in the collision avoidance state. If the distance between the vessel and the obstacle is greater than or equal to danger range ε , the vessel is judged to be in the regular navigation state; if the distance between the vessel and the obstacle is less than danger range ε , the vessel is judged to be in the regular collision avoidance state. In that case, when the coordinates of the vessel on both the X and Y axes exceed the obstacle or other vessel, the vessel is transferred from the collision avoidance to regular navigation state.
  • If the ship is in the state of collision avoidance, calculate gradient ▽(p(k)) from G k ; if in the state of regular navigation, calculate the gradient from U k .
  • Obtain path points p(k + δ ) = p(k) − α (k) ∗ ▽(p(k)).
Repeat the above process until the task of path planning is completed and N + 1 path points are obtained.
Algorithm 1 Local path planning.
Input: Gradient of field
Output: Trajectory of MASS p(x)
  1:
i = 0
  2:
p ( 0 ) = p s t a r t
  3:
Calculate initial cost and emission field energy after normalization: E C 0 and E M 0
  4:
Calculate initial navigation field energy after normalization: G 0
  5:
Calculate initial superimposition field energy U 0 = k 1 · E C 0 + k 2 · E M 0 + k 3 · G 0
  6:
Procedure:
  7:
for k < N + 1 do
  8:
 Calculate initial cost and emission field energy after normalization: E C i and E M i
  9:
 Calculate initial superimposition field energy U i = k 1 · E C i + k 2 · E M i + k 3 · G i .
10:
 Calculate distance between own ship and obstacle
11:
if distance > ε (Danger range) then
12:
   = U ;
13:
  else, if distance ≤ ε (danger range) & [ x ( k ) , y ( k ) ] ≤ [ o b s _ x ( k ) , o b s _ y ( k ) ]
14:
   = G
15:
  else, if distance ≤ ε (danger range) & [ x ( k ) , y ( k ) ] > [ o b s _ x ( k ) , o b s _ y ( k ) ]
16:
   = U ;
17:
end if
18:
while  0 do
19:
  p(k + 1) = p(k) − α (k)·▽ (p(k))
20:
end while
21:
 k = k + 1
22:
 i = i + 1
23:
end for
24:
Repeat procedure

4. NMPC-Based Trajectory Tracking Control and Collision Avoidance

In the control module, the accurate trajectory tracking of MASSs needs to be completed; the reference trajectory is transformed from the reference path output by the navigation module in Section 3, which is used as the input of the control module, and the optimal control volumes are output after rolling optimization. In this section, we first impose a time constraint on the input reference path to transform the path point into a trajectory point, and then transform the trajectory into a reference state quantity via Equation (19). We describe the trajectory tracking problem as an error control problem of the ship’s state quantity, design an objective function to minimize the change in state error and control quantity, designing the ship’s collision avoidance behavior as a constraint and embedding the constraint into the MPC controller, and control whether the constraint takes effect by function ET; if ET = 1, this means the constraint is on.

4.1. Maritime Autonomous Surface Ship System Modeling

For the MASS motion model, we refer to the three-degree-of-freedom model of [39]:
x ˙ = u cos ϕ v sin ϕ y ˙ = u sin ϕ + v cos ϕ ϕ ˙ = r u ˙ = m 22 m 11 v r d 11 m 11 u + 1 m 11 τ u v ˙ = m 11 m 22 u r d 22 m 22 v r ˙ = m 11 m 22 m 33 u v d 33 m 33 r + 1 m 33 τ r
where x and y are the ship’s location, ϕ expresses the ship’s heading angle on the earth-fixed frame, u and v, respectively, express the longitudinal and transverse velocities of the ship’s fixed coordinate system, and r is the angular velocity in yaw around the ship-fixed z-axis. Parameters m 11 , m 22 , and m 33 express the ship’s Inertia coefficient; d 11 , d 22 , and d 33 are the hydrodynamic damping coefficients.
We assume that the external environmental forces caused by wind and wave currents are constant with respect to the inertial reference system and that they have three components: surge, sway, and yaw. Therefore, we could modify the ship model written in compact form as [27]:
X ˙ = f ( X ) + g ( X ) + g 2 b ( X ) w b
where X = x y ϕ u v r T R 6 is the state vector, u = τ u τ r T R 2 expresses the control vector of surge force and yaw moment only, and w b = w u w v w r T R 3 expresses the external forces and moment vectors acting in the direction of surge, sway, and yaw and performance in the ship-fixed coordinate system [27]:
f ( X ) = u cos ψ ν sin ψ u sin ψ + v cos ψ r m 22 m 11 v r d 11 m 11 u n m 11 m 22 u r d 22 m 22 ν m 11 m 22 m 33 u ν d 33 m 33 r T R 6
g ( X ) = 0 0 0 1 m 11 0 0 0 0 0 0 0 1 m 33 T R 6 × R 2
g 2 b ( X ) = 0 0 0 1 m 11 0 0 0 0 0 0 1 m 22 0 0 0 0 0 0 1 m 33 T R 6 × R 3
By using a virtual vessel that has the same dynamics described as Equation (11), we generated time-varying predicted trajectories, but the virtual vessel was independent of external forces:
X r ˙ = f ( X r ) + g ( X r ) u
The time series of state and control vectors of MASS are defined as follows:
X ( t ) X u ( t ) U
Here, X and U are sets of state and control vectors.
Combining Equations (16) and (17), we can obtain the time-varying prediction equation for the MASS state variables:
X t + 1 = f X ( t ) , u ( t ) , t > 0
where x ( t ) R 6 expresses the vector of state variables; u ( t ) R 2 expresses the vector of control variables.

4.2. Trajectory Tracking Control

The original sequence of the input signal in this section is the reference path point p ( x ) obtained in Section 3.3, and by the time constraint, we can transform it into reference trajectory point p ( t ) . Consider the reference trajectory p ( t ) = [ x d ( t ) , y d ( t ) ] , which defines the position of MASSs on the local horizontal plane. Here, we assume that the following conditions hold [32]:
Assumption 1: Trajectory p ( t ) and its derivatives are expected to be smooth and bounded, satisfying: 0 p p ( t ) p , 0 p 1 ̲ p ( t ) ˙ p 1 < , 0 p 2 ̲ p ( t ) ¨ p 2 < , 0 p 3 ̲ p ( t ) p 3 < .
To correspond to the six state quantities of MASSs in Equation (11), we can extend the desired trajectory p ( t ) to a reference state quantity X d ( t ) by Equation (17), where X d ( t ) = [ x d ( t ) , y d ( t ) , ϕ d ( t ) , u d ( t ) , v d ( t ) , r d ( t ) ] , and the four extended reference states are calculated by the following equations:
ϕ d ( t ) = a t a n 2 y ˙ d ( t ) , x ˙ d ( t ) u d ( t ) = x ˙ d 2 ( t ) + y ˙ d 2 ( t ) v d ( t ) = 0 r d ( t ) = x ˙ d ( t ) y ¨ d ( t ) y ˙ d ( t ) x ¨ d ( t ) / x ˙ d 2 ( t ) + y ˙ d 2 ( t )
where a t a n 2 is the four-quadrant arctangent operator in Matlab, and f ( · ) ˙ denotes the derivative. Then, it can be verified that X d ( t ) satisfies kinematic Equation (11).
In this way, we obtain the expressions of all reference states of MASSs. In the control module, the nonlinear MPC framework uses a time-varying motion model running online to predict the vessel’s motion state. Solving a finite-time domain nonlinear optimal control problem can be regarded as an optimization problem, and the prerequisite for solving optimization problems is to establish a suitable optimization objective function. In order to make MASSs fast-track the expected trajectory, we use the state error and control error of the finite-time domain to determine the stage cost; in addition, the vessel can contribute a terminal cost function X ( T ) to ensure the stability of the control system [29]. Then, the expression of the objective function is given by:
m i n u ^ S ( δ ) J X , u = 0 T X ( s ) Q 2 + u ( s ) R 2 s + X ( T ) p 2
where X ^ ( s ) is the predicted ship trajectory based on control variables u ^ ( s ) , which evolves from x ( t 0 ) using the ship motion model; X = X ^ X d expresses the state variable error and u = u ^ u d is the control variable error; S ( δ ) expresses the group of segmented constant functions characterized by the sampling period δ ; and T = N δ indicates the control interval. Q, R, and P express the weight matrices, and all are positive definite matrices.
Based on the dynamic principle of MASSs, we have the following constraint:
s · t · x ^ ˙ = f x ^ ( s ) , u ^ ( s ) x ^ ( 0 ) = x t 0 u m i n < u ^ ( s ) < u m a x
We treat collision avoidance as a controller-dependent planning problem, but due to unfavorable environmental conditions and neglected ship dynamics, the controller may not be able to achieve a solution to the problem. To overcome this, we utilize the ability of NMPC to systematically integrate state constraints into its optimization problem, and assuming that the obstacles are circular, autonomous collision avoidance can be transformed into an inequality constraint integrated into the design of the controller with the following [29]:
s q r t x ( t ) x 0 i ( t ) 2 + y ( t ) y 0 i ( t ) 2 R + R 0 i
where x ( t ) and y ( t ) are the predicted positions of one’s own vessel over the prediction horizon, x 0 i ( t ) and y 0 i ( t ) are the position of ith dynamic or statistic obstacles, and R and R i are the hazard radii of one’s own vessel and obstacle.
Eventually, the nonlinear optimization control problem of MASS trajectory tracking can be integrated as:
m i n u ^ S ( δ ) J x , u = 0 T x ( s ) Q 2 + u ( s ) R 2 s + x ( T ) p 2 s · t · x ^ ˙ = f x ^ ( s ) , u ^ ( s ) x ^ ( 0 ) = x t 0 u m i n < u ^ ( s ) < u m a x s q r t x ( t ) x 0 i ( t ) 2 + y ( t ) y 0 i ( t ) 2 R + R 0 i
The flow of the NMPC-based MASS trajectory tracking algorithm can be briefly described as follows:
  • The optimization problem (23) is solved with the current state error X ˜ ( t 0 ) as the initial state and u ( t 0 + k δ ) = τ u ( t 0 + k δ ) , τ r ( t 0 + k δ ) , (k = 0, 1, 2,…, N − 1) as a set of optimal solutions to the control problem.
  • The system only uses the first optimal solution as the control output for one sampling period [ t 0 , t 0 + δ ] : u ( t 0 ) = [ τ u ( t 0 ) , τ r ( t 0 ) ] , as a control decision for the MASS.
  • At moment t 0 + ϕ at the beginning of the next sampling period, the optimization problem (23) is solved again using the latest measurement data X ˜ ( t 0 + δ ) .
The above process is repeated until the MASS tracking control task is completed.

5. Collaborative Optimization of Path Planning and Tracking Control

In the traditional research of path planning and trajectory tracking control, the information transfer between navigation and control modules is often offline and one-way, which means it is non-closed-loop information transfer. This transfer mode cannot achieve online planning and control, and for the ship motion system with large inertia and time lag, online planning is more effective than offline planning. Therefore, we designed a collaborative optimization framework of path planning and trajectory tracking control to complete online planning and control and achieve the purpose of the collaborative optimization of navigation and control modules.
Based on the characteristics of NMPC data sampling, the tracking control can be easily combined with the path planning method of rolling planning proposed in the previous section, and the information transfer between the path planning module and the control module can be easily accomplished at each sampling moment through the information transfer interface. The closed-loop structure of the autonomous navigation system, composed of path planning and NMPC trajectory tracking control modules, is depicted in Figure 6.

5.1. Interface I for Path Planning

The output of the NMPC optimization framework is the control variable u = [ τ u , τ r ] , and according to the time-varying prediction model of the MASS state volume, we can calculate X R ( t + δ ) = f ( X R ( t ) , u R ( t ) ) and matrix I R 6 as the interface for information transfer between the control and navigation modules to obtain the initial parameters of the path planning algorithm:
S I ( 0 ) = I × X R ( t 0 + δ )
In Equation (24), I ( 1 , 1 ) = 1 , I ( 2 , 2 ) = 1 , I ( 3 , 3 ) = 1 , and the other values in the matrix = 0.

5.2. Process of the Closed-Loop Structure

The navigation module can generate N + 1 geometric path points after completing a path planning task at time t. Due to the design feature of the search step being equal to the ship’s speed (Section 3.3), it is easy to convert the generated geometric path into a time-dependent trajectory profile. The reference trajectory can be expressed as:
{ p ( x ) , x [ t , t + ( N + 1 ) · δ ] , x i s a n i n t e g e r m u l t i p l e o f δ }
p ( x ) can be converted to the reference state quantity in real time via Equation (19), just as follows:
X d = x d , y d , ϕ d , u d , ν d , r d T
Then, state error X ˜ ( t 0 ) is used as the input of the control module, and after the optimal solution of NMPC, the optimal control output sequence U ( T ) , T ( t 0 , t 0 + N δ ) is obtained, and the first control variable u ( t 0 ) = [ τ u ( t 0 ) , τ r ( t 0 ) ] T is taken as the control command of MASS at moment t 0 . According to Equation (24), the partially predicted state at moment t 0 + δ can be calculated by optimal control τ = u ( t ) :
X R t 0 + δ = f x R ( t 0 ) , u R ( t 0 )
S I = x t 0 + δ , y t 0 + δ , u t 0 + δ = I X R t 0 + δ
S I is used as input to the navigation module for the path search for the next sampling period [ t + δ , t + 2 δ ] , and the potential field is regenerated based on the updated starting point and the ship’s speed:
x t + δ = x t + δ , y t + δ U = U u y + δ , G = G x t + δ , y t + δ
In the updated potential field environment, path planning is performed for t + δ moments to form a new series of reference trajectories. The above process is repeated until the autonomous navigation task of the MASS is completed. The rolling-optimization-based path planning and NMPC-based trajectory tracking combined with dynamic and static collision avoidance control algorithms are summarized in Algorithm 2:
Algorithm 2 Path planning and trajectory tracking control.
Input: Field and reference trajectory
Output: Optimum control and real trajectory
  1:
i = 0
  2:
initial field U 0
  3:
initial gradient matrix G 0
  4:
Procedure
  5:
for i = 1 : s i m _ t i m do
  6:
for m = 1 : N + 1 do
  7:
  use path planning Algorithm 1 to calculate N + 1 reference position p { N + 1 }
  8:
end for
  9:
for k = 1 : N do
10:
  Transform reference position to reference trajectory and reference state X d ( i )
11:
  Use NMPC module to calculate control quantity τ
12:
end for
13:
 Calculate next state X R ( i + 1 ) by τ ; S I ( i + 1 ) = I × X R ( i + 1 ) ;
14:
 initial field U = U i , initial gradient matrix G = G i ;
15:
i = i + 1 ;
16:
end for
17:
Repeat procedure

6. Simulation

6.1. Experimental Design

6.1.1. Marine Environment

Marine meteorological data can be obtained through many channels, and in this paper, in order to simplify the process of data acquisition, multi-point fitting was used to acquire more meteorological data. In the actual marine meteorological environment, wind and wave data can be obtained separately. Due to the different timeliness of data, wind and wave data cannot be obtained accurately at the same time; to ensure the accuracy of wave data, wave height is calculated from wind speed information using the following equation [12]:
h = 0.7 · g F ν w i n d 2 d 1 3 · ν w i n d 2 g
In Equation (30), gravity acceleration g = 9.8 m/s 2 , and ν w i n d is wind speed. F is the length of wind area, which refers to the region of sea where the wind strength conditions are almost the same.
Since the magnitude of ocean currents is less affected by other factors, the current speed is simply set to a constant value throughout the map. The final constructed environment for navigation is shown in Figure 7. Figure 7 shows the numerical overlay of wind speed, wave height, and current velocity, where wind speed data are obtained via cubic spline interpolation fitting, wave height data are calculated via Equation (30), and current velocity is a constant value. The brighter the color of the area (the higher the value), the more severe the weather environment.

6.1.2. Experimental Parameters

In the simulation experiments, we chose a map range of 100 nm × 100 nm and a KCS container ship. The hydrodynamic parameters and other ship parameters are shown in Table 2. A predicted horizon length NP of 420 min and a sampling interval of 4 min were chosen in order to reduce the computation, so the prediction step Np was 105 and the control step Nc was 15.
The controller weights were as follows: Q(1,1) = 1 × 10 1 ; Q(2,2) = 1 × 10 1 ; Q(3,3) = 10; Q(4,4) = 1; Q(5,5) = 1; Q(6,6) = 1; R(1,1) = 1 × 10 2 ; R(2,2) = 1 × 10 2 ; R1(1,1) = 1 × 10 2 ; R1(2,2) = 1 × 10 2 .
The vessel control constraints of the autonomous navigation and control system are defined as follows (N·m):
2000 2000 U 2000 2000
For simplicity of calculation, the value of drag coefficient C t s was made to approximate frictional resistance C F , without considering the residual resistance. The calculation equation is as follows [40]:
C F = 0.075 log R e 2 2 , R e = v s · L ν
where v s is the speed of vessel over water, L expresses length of the vessel, and ν expresses the viscosity of water.

6.1.3. Experimental Design

In this paper, simulation experiments were performed in MATLAB, and four sets of experiments were conducted.
Experiment 1: A comparison experiment between single-objective planning with cost reduction and multi-objective planning with cost and emission reduction was designed to show the impact of adding carbon emissions to path planning.
Experiment 2: A comparison experiment was conducted between the RHNC and Offline-SPNC systems under conventional conditions to validate the effectiveness of the RHNC system in reducing economic costs and emissions.
Experiment 3: Autonomous collision avoidance experiments were conducted with the MASS controller in static collision avoidance and pair encounter scenarios to verify the control and collision avoidance performance of NMPC.
Experiment 4: A MASS autonomous navigation experiment containing collision avoidance state and regular state transition was conducted to verify the effectiveness of the event-triggering mechanism.

6.2. Simulation Results

6.2.1. Contrast Experiments Considering Carbon Emissions and No Carbon Emissions in Local Path Planning

We first conducted a series of controlled experiments to verify the effect of the local path planning algorithm presented in the previous article after adding carbon emissions as a penalty function. This set of experiments was divided into two parts: path planning considering economic cost and carbon emission, and path planning considering only economic cost without carbon emission. The coordinates of the starting point of both parts of the experiment were O(0, 0), the coordinates of the local target point were D(100, 100), the search step length of the path planning was set to 1.2 nautical miles, and the total step length NL was 110. Figure 8 shows that the paths searched by the path planning algorithm offline (blue paths) become more tortuous than the paths searched by the algorithm considering only the economic cost objective (red paths) after introducing the carbon emission cost. We can see that the potential energy of the path points obtained by the search algorithm was lower after the emission field in Figure 9 was added, which reflects the effect of emission field construction and field superposition. This shows the effectiveness of our proposed route planning algorithm in considering carbon emissions, and that the navigation module takes into account the goal of reducing costs and emissions when planning paths.

6.2.2. Simulation Experiments of Receding Horizon Navigation and Control System in Global Planning

In this subsection, we describe the simulation experiments conducted to verify the effectiveness of the proposed receding horizon navigation and control (RHNC) system for global navigation and the control of MASSs in Section 5. In the experiments, the step size of the path planning algorithm in the navigation module was 16, and the control step size of the MPC in the control module was 15. Figure 10 shows the map field strengths at six sampling moments with sim-time (Np) of 20, 40, 60, 80, 100, and 120 and the paths that MASSs navigated at these six sampling moments. We can find from the graph that the map field intensity changed at different sampling moments, which was caused by changes in ship speed and the angle between the ship’s location and the target point, which verifies the changes caused by the rolling optimization framework to the path planning algorithm. After the simulation experiment, we can verify that the proposed navigation and control modules can plan the navigation path according to the field strength on the map while controlling the autonomous ship to follow the local path planned by the navigation module, and the navigation module can obtain the state information of the autonomous ship in real time to plan the local path in the next sampling moment.
Figure 11 shows a time-varying diagram of control quantity τ . From the diagram, we can see that τ u and τ r fluctuated greatly in the range of 240–300 min, and then returned to normal, which means that the navigation module of the autonomous vessel plans a route with a relatively large turning angle during this time, and the control module controls the autonomous vessel to make a larger turn after obtaining the reference trajectory input. This phenomenon is verified in Figure 10.
In order to further verify the effectiveness of the navigation and control system with rolling optimization proposed in this paper, we designed a control experiment using offline shortest path planning with NMPC trajectory tracking control (Offline-SPNC); a trajectory diagram is shown in Figure 12.
For simplicity of calculation, we took the average of the magnitude of the economic cost field energy and emission field energy (before normalization treatment) of the path point at two consecutive sampling moments as the increase rate of economic costs and emissions for one consecutive time period. The economic costs and emissions of the navigation and control systems are shown in Table 3. The approximate coordinates of the final position A1 of a MASS under the control of the Offline-SPNC system are approximately (92.8 n mile, 92.8 n mile), and those of the final position A2 of a MASS at the end of the simulation of the RHNC system are (94.3 n mile, 89.8 n mile), and the linear mileage of both is approximately 131.24 n mile for Offline-SPNC and 129.67 n mile for RHNC. Compared with the Offline-SPNC system, per n mile of the RHNC system, the economic cost is reduced by about 9.08%, and the emissions are reduced by about 16.37%.

6.2.3. Simulation Experiments of Real-Time Path Planning and Tracking Control with Collision Avoidance

To evaluate the performance of the NMPC controller used to avoid collisions between static obstacles and dynamic objects, the control performance of one static scenario and one dynamic scenario was analyzed. The predicted trajectory of the target ship was calculated using an isokinetic model under the assumption that the other ship does not have a collision avoidance scenario. Finally, a comprehensive simulation experiment containing all elements (navigation and control, static collision avoidance, dynamic collision avoidance, and event-triggering mechanism) was performed.

Scenario: Static Collision Avoidance

The map range used in this group of experiments was 10 n miles × 10 n miles, the radius of the static obstacle hazardous collision avoidance range was set to 2 n miles, the chosen sampling interval was 20 s in consideration of reducing computation, the total prediction step N p was 110, that is, the total simulation time was 2200 s, and the control step of NMPC controller N c was 15.
The change process of the ship’s trajectory and control variables are shown in Figure 13 and Figure 14.

Scenario: Head-on

In the experiments of dynamic collision avoidance, the dangerous collision avoidance radius of the ship was set to 1 n mile, and the chosen sampling interval was 20 s in consideration of reducing computation. The total prediction step Np in this scenario was 80, so that the total simulation time was 1600 s, and the control step of the NMPC controller Nc was 15.
Supposing a ship is located at ( X T , Y T ) , its trajectory is as follows:
x T ( t ) = 4 0.05 · t y T ( t ) = 4 0.05 · t
where t represents the frequency of the sampling moment rather than the actual time T, that is, t = T / δ . For each sampling moment interval of 20 s, Equation (32) means that every 20 s along the X and Y axes, the obstacle ship travels a distance of 0.5 n miles.
The trajectory diagram is shown in Figure 15, and the surge force and yaw moments are expressed in Figure 16. In this case, the collision avoidance constraint and the longitudinal swing force and transverse swing moment constraint are satisfied, and after the collision avoidance is completed, the rolling optimized navigation module will plan a new path according to the state of the intelligent merchant vessel; then, the NMPC controller in the module will control the vessel to track the new trajectory. Compared with offline planning, a MASS under the RHNC system can save part of the journey to return to the original path.

6.2.4. RHNC System with Collision Avoidance and Event Triggering

In order to verify the effectiveness of the whole system, a comprehensive simulation experiment was conducted. Supposing a ship is located at ( X T , Y T ) , its trajectory is as follows:
x T ( t ) = 50 0.75 · t y T ( t ) = 40 0.75 · t
where t represents the frequency of the sampling moment rather than the actual time T, that is, t = T / δ . For each sampling moment interval of 4 minutes, Equation (33) means that every 4 minutes along the X and Y axes, the obstacle ship travels a distance of 0.75 n miles.
Assuming an island is located at (75 n mile, 65 n mile) with an impact radius R o 1 of 3 n miles, the hazard radius R s of the ship is set to 1.5 n miles, and the hazard warning distance of the event trigger mechanism ε 1 = 4.5 n mile (distance between a MASS and a dynamic obstacle) and ε 2 = 6 n mile (distance between a MASS and a statistic obstacle).
In the experiment, the step size of the path planning algorithm in navigation module N L was 16, and the control step size of MPC in control module N C was 15. Figure 17 shows the field strength of the six sampling moments with a simulation step ( N p ) of 20, 40, 60, 80, 100, and 120 and the trajectories that a MASS sailed at these six sampling moments. In simulation steps 1–20, the MASS sailed in the conventional state considering “cost and emission”; in simulation steps 20–40, the ship found the other ship and changed from the conventional state to the collision avoidance state, and then back to the conventional state again after the collision avoidance was completed. In simulation steps 40–60 and 60–80, autonomous navigation continued in the conventional state considering “cost and emissions”. In simulation steps 80–100 and 100–120, the ship found the static obstacle and changed from the regular state to the collision avoidance state, and then back to the regular state after avoiding and crossing the obstacle (the trajectory of the obstacle beyond the map range was not visualized). After verifying the simulation experiment, the navigation and control modules proposed in this paper can cooperate to optimize the system for real-time planning and control. In the process of control, real-time collision avoidance can be accomplished, and the event trigger mechanism can issue safety warnings for the RHNC system to keep the ship safe in the first place. Figure 18 shows a time-varying diagram of control quantity τ in the process.

7. Conclusions

In this paper, a new navigation control scheme was designed to meet economic and green objectives in navigation and safe trajectory tracking in control. The path search of the navigation module was based on the path planning method of potential field theory, and the idea of potential field construction was derived from APF [15]. The guidance field and cost emission field were constructed based on the gravitational field and repulsive field, respectively, in APF and were integrated with NMPC with rolling optimization characteristics. In addition, the closed-loop structure of information transfer was studied to design a rolling optimization navigation and control system framework. From the experimental results, it can be seen that the RHNC system proposed in this paper can plan energy-saving and emission reduction paths for MASSs in wind and wave environments and can control an intelligent merchant ship to follow the planned path. Meanwhile, through the design of an event-triggering mechanism, the system can close the cost emission field and change into a collision avoidance state when detecting obstacles or other ships. The experimental results of static and dynamic collision avoidance scenarios can also prove that the system has good dynamic and static collision avoidance performance and can re-route for MASSs after confirming that the ship is in a safe state. In our research, all obstacles are circular, circular domains are quite old. Therefore, there are some potential limitations of this paper. In future research, we will use newer and more scientific ship domains models to design the MPC controller’s collision avoidance constraints.

Author Contributions

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

Funding

This research was funded by the National Nature Science Foundation of China, grant number 51709166 and 51909155; the Scientific Research Program of Shanghai Science and Technology Commission, grant number 21692193000 and 22010501800.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Informed consent was obtained from all subjects involved in the study.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Fossen, T.I. Marine Control Systems–Guidance. Navigation, and Control of Ships, Rigs and Underwater Vehicles. Marine Cybernetics, Trondheim, Norway, Org. Number NO 985 195 005 MVA, 2002. ISBN: 8292356002. Available online: www.marinecybernetics.com (accessed on 15 December 2022).
  2. Chen, Y.; Bai, G.; Zhan, Y.; Hu, X.; Liu, J. Path planning and obstacle avoiding of the USV based on improved ACO-APF hybrid algorithm with adaptive early-warning. IEEE Access 2021, 9, 40728–40742. [Google Scholar] [CrossRef]
  3. Chen, Z.; Zhang, Y.; Zhang, Y.; Nie, Y.; Tang, J.; Zhu, S. A hybrid path planning algorithm for unmanned surface vehicles in complex environment with dynamic obstacles. IEEE Access 2019, 7, 126439–126449. [Google Scholar] [CrossRef]
  4. Sen, D.; Padhy, C.P. An approach for development of a ship routing algorithm for application in the North Indian Ocean region. Appl. Ocean Res. 2015, 50, 173–191. [Google Scholar] [CrossRef]
  5. Mannarini, G.; Coppini, G.; Oddo, P.; Pinardi, N. A prototype of ship routing decision support system for an operational oceanographic service. TransNav: Int. J. Mar. Navig. Saf. Sea Transp. 2013, 7, 53–59. [Google Scholar] [CrossRef]
  6. Jung, J.; Rhyu, K. A study on the optimal navigation route decision using A* algorithm. J. Korea Soc. Comput. Inf. 1999, 4, 38–46. [Google Scholar]
  7. Szlapczynska, J. Multi-objective weather routing with customised criteria and constraints. J. Navig. 2015, 68, 338–354. [Google Scholar] [CrossRef] [Green Version]
  8. Singh, Y.; Sharma, S.; Sutton, R.; Hatton, D.; Khan, A. A constrained A* approach towards optimal path planning for an unmanned surface vehicle in a maritime environment containing dynamic obstacles and ocean currents. Ocean Eng. 2018, 169, 187–201. [Google Scholar] [CrossRef] [Green Version]
  9. Xie, L.; Xue, S.; Zhang, J.; Zhang, M.; Tian, W.; Haugen, S. A path planning approach based on multi-direction A* algorithm for ships navigating within wind farm waters. Ocean Eng. 2019, 184, 311–322. [Google Scholar] [CrossRef]
  10. Yu, K.; Liang, X.F.; Li, M.Z.; Chen, Z.; Yao, Y.L.; Li, X.; Zhao, Z.X.; Teng, Y. USV path planning method with velocity variation and global optimisation based on AIS service platform. Ocean Eng. 2021, 236, 109560. [Google Scholar] [CrossRef]
  11. Liu, X.; Li, Y.; Zhang, J.; Zheng, J.; Yang, C. Self-adaptive dynamic obstacle avoidance and path planning for USV under complex maritime environment. IEEE Access 2019, 7, 114945–114954. [Google Scholar] [CrossRef]
  12. Wang, X.; Zhao, X.; Wang, G.; Wang, Q.; Feng, K. Weather Route Optimization Method of Unmanned Ship Based on Continuous Dynamic Optimal Control. Sustainability 2022, 14, 2165. [Google Scholar] [CrossRef]
  13. Fox, D.; Burgard, W.; Thrun, S. The dynamic window approach to collision avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef] [Green Version]
  14. Kuwata, Y.; Wolf, M.T.; Zarzhitsky, D.; Huntsberger, T.L. Safe maritime autonomous navigation with COLREGS, using velocity obstacles. IEEE J. Ocean Eng. 2013, 39, 110–119. [Google Scholar] [CrossRef]
  15. Wu, P.; Xie, S.; Liu, H.; Li, M.; Li, H.; Peng, Y.; Li, X.; Luo, J. Autonomous obstacle avoidance of an unmanned surface vehicle based on cooperative manoeuvring. Ind. Robot. Int. J. 2017, 44, 64–74. [Google Scholar] [CrossRef]
  16. Azzabi, A.; Nouri, K. An advanced potential field method proposed for mobile robot path planning. Trans. Inst. Meas. Control. 2019, 41, 3132–3144. [Google Scholar] [CrossRef]
  17. Sang, H.; You, Y.; Sun, X.; Zhou, Y.; Liu, F. The hybrid path planning algorithm based on improved A* and artificial potential field for unmanned surface vehicle formations. Ocean Eng. 2021, 223, 108709. [Google Scholar] [CrossRef]
  18. Liu, Y.; Bucknall, R. Path planning algorithm for unmanned surface vehicle formations in a practical maritime environment. Ocean Eng. 2015, 97, 126–144. [Google Scholar] [CrossRef]
  19. Li, D.; Du, L. Auv trajectory tracking models and control strategies: A review. J. Mar. Sci. Eng. 2021, 9, 1020. [Google Scholar] [CrossRef]
  20. Truong, T.N.; Vo, A.T.; Kang, H.J. A backstepping global fast terminal sliding mode control for trajectory tracking control of industrial robotic manipulators. IEEE Access 2021, 9, 31921–31931. [Google Scholar] [CrossRef]
  21. Liu, S.Q.; Sang, Y.J.; Whidborne, J.F. Adaptive sliding-mode-backstepping trajectory tracking control of underactuated airships. Aerosp. Sci. Technol. 2020, 97, 105610. [Google Scholar] [CrossRef]
  22. Liu, L.; Wang, D.; Peng, Z.; Han, Q.L. Distributed path following of multiple under-actuated autonomous surface vehicles based on data-driven neural predictors via integral concurrent learning. IEEE Trans. Neural Networks Learn. Syst. 2021, 32, 5334–5344. [Google Scholar] [CrossRef]
  23. Li, J.; Du, J.; Chen, C.P. Command-filtered robust adaptive NN control with the prescribed performance for the 3-D trajectory tracking of underactuated AUVs. IEEE Trans. Neural Networks Learn. Syst. 2021, 33, 6545–6557. [Google Scholar] [CrossRef] [PubMed]
  24. Li, H.; Yan, W. Model predictive stabilization of constrained underactuated autonomous underwater vehicles with guaranteed feasibility and stability. IEEE/Asme Trans. Mechatron. 2016, 22, 1185–1194. [Google Scholar] [CrossRef]
  25. Li, H.; Shi, Y. Distributed receding horizon control of large-scale nonlinear systems: Handling communication delays and disturbances. Automatica 2014, 50, 1264–1271. [Google Scholar] [CrossRef]
  26. Yang, K.; Tang, X.; Qin, Y.; Huang, Y.; Wang, H.; Pu, H. Comparative study of trajectory tracking control for automated vehicles via model predictive control and robust H-infinity state feedback control. Chin. J. Mech. Eng. 2021, 34, 74. [Google Scholar] [CrossRef]
  27. Abdelaal, M.; Fränzle, M.; Hahn, A. Nonlinear Model Predictive Control for trajectory tracking and collision avoidance of underactuated vessels with disturbances. Ocean Eng. 2018, 160, 168–180. [Google Scholar] [CrossRef]
  28. Zhao, B.; Zhang, X.; Liang, C.; Han, X. An Improved Model Predictive Control for Path-Following of USV Based on Global Course Constraint and Event-Triggered Mechanism. IEEE Access 2021, 9, 79725–79734. [Google Scholar] [CrossRef]
  29. Zheng, J.; Hu, J.; Li, Y. Codesign of dynamic collision avoidance and trajectory tracking for autonomous surface vessels with nonlinear model predictive control. Proc. Inst. Mech. Eng. Part M J. Eng. Marit. Environ. 2022, 236, 938–952. [Google Scholar] [CrossRef]
  30. Ji, J.; Khajepour, A.; Melek, W.W.; Huang, Y. Path planning and tracking for vehicle collision avoidance based on model predictive control with multiconstraints. IEEE Trans. Veh. Technol. 2016, 66, 952–964. [Google Scholar] [CrossRef]
  31. Wang, B.; Zhang, Y.; Zhang, W. Integrated path planning and trajectory tracking control for quadrotor UAVs with obstacle avoidance in the presence of environmental and systematic uncertainties: Theory and experiment. Aerosp. Sci. Technol. 2022, 120, 107277. [Google Scholar] [CrossRef]
  32. Shen, C.; Shi, Y.; Buckham, B. Integrated path planning and tracking control of an AUV: A unified receding horizon optimization approach. IEEE/ASME Trans. Mechatron. 2016, 22, 1163–1173. [Google Scholar] [CrossRef]
  33. Roh, M.I. Determination of an economical shipping route considering the effects of sea state for lower fuel consumption. Int. J. Nav. Archit. Ocean Eng. 2013, 5, 246–262. [Google Scholar] [CrossRef] [Green Version]
  34. Zaccone, R.; Ottaviani, E.; Figari, M.; Altosole, M. Ship voyage optimization for safe and energy-efficient navigation: A dynamic programming approach. Ocean Eng. 2018, 153, 215–224. [Google Scholar] [CrossRef]
  35. Polvara, R.; Sharma, S.; Wan, J.; Manning, A.; Sutton, R. Obstacle avoidance approaches for autonomous navigation of unmanned surface vehicles. J. Navig. 2018, 71, 241–256. [Google Scholar] [CrossRef] [Green Version]
  36. Li, Y.; Zheng, J. Real-time collision avoidance planning for unmanned surface vessels based on field theory. ISA Trans. 2020, 106, 233–242. [Google Scholar] [CrossRef]
  37. Hollenbach, U.; Friesch, J. Efficient hull forms—What can be gained. In Proceedings of the 1st International Conference on Ship Efficiency, Hamburg, Germany, 8–9 October 2007. [Google Scholar]
  38. Prpić-Oršić, J.; Faltinsen, O.M. Estimation of ship speed loss and associated CO2 emissions in a seaway. Ocean Eng. 2012, 44, 1–10. [Google Scholar] [CrossRef]
  39. Fossen, T.I. Handbook of Marine Craft Hydrodynamics and Motion Control; John Wiley & Sons: Hoboken, NJ, USA, 2011. [Google Scholar]
  40. Zis, T.P.; Psaraftis, H.N.; Ding, L. Ship weather routing: A taxonomy and survey. Ocean Eng. 2020, 213, 107697. [Google Scholar] [CrossRef]
Figure 1. Technical structure of receding horizon navigation and control system.
Figure 1. Technical structure of receding horizon navigation and control system.
Jmse 11 00127 g001
Figure 2. Three-dimensional cost field.
Figure 2. Three-dimensional cost field.
Jmse 11 00127 g002
Figure 3. Two-dimensional guidance field.
Figure 3. Two-dimensional guidance field.
Jmse 11 00127 g003
Figure 4. Two-dimensional superposition field after normalization.
Figure 4. Two-dimensional superposition field after normalization.
Jmse 11 00127 g004
Figure 5. Map gradient and contour.
Figure 5. Map gradient and contour.
Jmse 11 00127 g005
Figure 6. Closed-loop diagram.
Figure 6. Closed-loop diagram.
Jmse 11 00127 g006
Figure 7. Marine environment map (wind, wave, and flow).
Figure 7. Marine environment map (wind, wave, and flow).
Jmse 11 00127 g007
Figure 8. Path with carbon emissions added and no carbon emissions.
Figure 8. Path with carbon emissions added and no carbon emissions.
Jmse 11 00127 g008
Figure 9. Energy with carbon emissions added and no carbon emissions.
Figure 9. Energy with carbon emissions added and no carbon emissions.
Jmse 11 00127 g009
Figure 10. Field energy and trajectory.
Figure 10. Field energy and trajectory.
Jmse 11 00127 g010
Figure 11. Variability of control.
Figure 11. Variability of control.
Jmse 11 00127 g011
Figure 12. Trajectory of shortest path planning and NMPC tracking control.
Figure 12. Trajectory of shortest path planning and NMPC tracking control.
Jmse 11 00127 g012
Figure 13. Trajectory of static collision avoidance.
Figure 13. Trajectory of static collision avoidance.
Jmse 11 00127 g013
Figure 14. Variability in control in static collision avoidance.
Figure 14. Variability in control in static collision avoidance.
Jmse 11 00127 g014
Figure 15. Trajectory of dynamic collision avoidance (head-on).
Figure 15. Trajectory of dynamic collision avoidance (head-on).
Jmse 11 00127 g015
Figure 16. Variability of control in dynamic collision avoidance (head-on).
Figure 16. Variability of control in dynamic collision avoidance (head-on).
Jmse 11 00127 g016
Figure 17. Trajectory of RHNC system with collision avoidance and event triggering.
Figure 17. Trajectory of RHNC system with collision avoidance and event triggering.
Jmse 11 00127 g017
Figure 18. Variability of control in RHNC system with collision avoidance and event triggering.
Figure 18. Variability of control in RHNC system with collision avoidance and event triggering.
Jmse 11 00127 g018
Table 1. Descriptions of parameters in equations.
Table 1. Descriptions of parameters in equations.
ParametersMeanings
KPropeller efficiency
η Propulsion efficiency (0.6 to 0.7)
H 1 3 Significant wave height
P s Still water power
ρ Water density
C t s Still water drag coefficient
SWetted surface
P w Additional power for wave resistance
C w Drag coefficient for wave resistance
gVertical force
BShip width
LShip length
P a Additional power for wave resistance
C a Drag coefficient for aerodynamic
ASurface area projected for wind
uWave speed
u a Wind speed
mCargo on board the vessel
nCargo weight constant
rWave constant (0.1)
Table 2. KCS ship and weight parameters.
Table 2. KCS ship and weight parameters.
ParametersValueUnit
m 11 897.77kg
m 22 1718kg
m 33 105.34kg
d 11 42.77kg/s
d 22 863kg/s
d 33 51.88kg/s
S (wetted  surface)9424m 2
A (wind  area)2200.43m 2
L230m
B32.2m
k 1 1 
k 2 1 
k 3 16 
C w 0.57e 3  
ν 1.27e 6 m 2 /s
C a 0.1 
Table 3. Costs and emissions.
Table 3. Costs and emissions.
Navigation and Control SystemEC 10 4 (USD)EM (t)EM per n mile (USD)EM per n mile (kg)Time (min)
RHNC1.04731.264280.74241.10480
Offline-SPNC1.165637.838588.81288.31460
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

Zheng, J.; Sun, W.; Li, Y.; Hu, J. A Receding Horizon Navigation and Control System for Autonomous Merchant Ships: Reducing Fuel Costs and Carbon Emissions under the Premise of Safety. J. Mar. Sci. Eng. 2023, 11, 127. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse11010127

AMA Style

Zheng J, Sun W, Li Y, Hu J. A Receding Horizon Navigation and Control System for Autonomous Merchant Ships: Reducing Fuel Costs and Carbon Emissions under the Premise of Safety. Journal of Marine Science and Engineering. 2023; 11(1):127. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse11010127

Chicago/Turabian Style

Zheng, Jian, Wenjun Sun, Yun Li, and Jiayin Hu. 2023. "A Receding Horizon Navigation and Control System for Autonomous Merchant Ships: Reducing Fuel Costs and Carbon Emissions under the Premise of Safety" Journal of Marine Science and Engineering 11, no. 1: 127. https://0-doi-org.brum.beds.ac.uk/10.3390/jmse11010127

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