1. Introduction
The development of Maritime Autonomous Surface Ships (MASSs) has the potential to significantly enhance the safety, efficiency, and sustainability of maritime transport. The Maritime Safety Committee (MSC) of the International Maritime Organization (IMO) is currently preparing the MASS Code, which is expected to be adopted as non-mandatory in 2026 and mandatory in 2030 [
1].
Recent advancements in autonomous ship navigation have focused on compliance with the International Regulations for Preventing Collisions at Sea (COLREGs), dynamic obstacle avoidance, and path planning under environmental constraints. Since adherence to the COLREGs is fundamental for safe autonomous operation, considerable research has been devoted to rule-embedding techniques. Zhang et al. provide a comprehensive survey of collision avoidance systems and emphasize the persistent challenges in achieving fully autonomous navigation in complex maritime environments [
2]. The authors also conclude that collision-free navigation would significantly benefit the integration of MASS autonomy in various maritime scenarios. García Maza critically analyzes COLREG ambiguities, emphasizing the need for homogeneous criteria for the regulation of navigable areas to reduce the possibility of problematic encounters, especially with the emergence of MASSs [
3].
Rule-based systems, such as Constapel’s operationalized COLREG assessment framework, demonstrate how situation statements can formalize encounter scenarios [
4]. However, as Chang notes, inconsistencies persist in translating COLREGs into machine-interpretable constraints, particularly for multi-ship encounters, and while academic research has focused on developing autonomous collision avoidance (CA), it is producing inconsistent results compared to conventional navigation practices [
5]. Also, Kim and Park provided insights into the notable disparity between the understanding of COLREG rules by navigators and automated collision avoidance algorithms [
6]. As a possible solution approach, Lyu addressed these challenges by classifying multi-vessel scenarios using the velocity obstacles algorithm and coupling risk assessment with COLREG responsibilities [
7].
In terms of dynamic obstacle avoidance and path planning under environmental constraints, Model Predictive Control (MPC) provides a promising method for balancing trajectory optimization with dynamic constraints. Codesseira validates MPC’s robustness for underactuated ships in path following [
8], while Zhang integrates spatial reformulation for time-optimal obstacle avoidance in a hierarchical MPC framework [
9]. Tsolakis extends MPC to long-horizon trajectory optimization, incorporating COLREGs as traffic constraints [
10]. Xue introduces human-like MPC with adaptive risk boundaries using control barrier functions, bridging safety and computational efficiency [
11]. For coastal navigation, Fagerhaug proposes “Oceanscape”, a graph-based MPC framework that encodes maritime charts into geometric learning structures, enabling COLREG-aware pathfinding in complex environments [
12].
Various hybrid and learning-based approaches have been investigated for handling COLREG compliance in dynamic environments. Wen proposed deep reinforcement learning (DRL)-based path planning for MASSs to address collision avoidance path planning while adhering to the COLREGs, though its reliance on pre-recorded data limits adaptability [
13]. Shen proposed a novel differential evolution deep reinforcement learning algorithm to address problems of local and global path planning [
14]. He combined MPC with artificial potential fields to address local optima in complex encounters [
15], while Wang applied MPC to underwater vehicle-manipulator systems, demonstrating scalability to dynamic obstacles [
16].
Namgung and Kim proposed a neuro-fuzzy inference system for collision risk assessment, enabling early and COLREG-consistent alerts based on an enlarged ship domain model [
17]. In a follow-up study, Namgung combined fuzzy logic with velocity obstacle methods to design a local route planner that explicitly detected encounter types and applied corresponding avoidance maneuvers [
18]. Both studies rely on rule-based logic to enforce COLREG compliance.
Despite considerable progress in autonomous ship navigation, several key limitations remain. Öztürk identifies insufficient COLREG relevance in velocity obstacle and artificial potential field methods [
19], while Lyu highlights the underutilization of coupled speed–course adjustments in decision-making processes [
20]. Fu emphasizes the trade-off between real-time performance and optimality in multi-objective planners [
21]. Liu tackles this by integrating digital twins and an enhanced velocity obstacle algorithm to develop an autonomous collision avoidance framework for the ships’ routing waters [
22]. Recent research trends focus on embedding COLREG rules by formalizing them as optimization constraints (e.g., [
3,
10]), improving environmental awareness through the integration of nautical chart data (e.g., [
12]), and modeling dynamic obstacles (e.g., [
9]), and enhancing real-time adaptability by combining MPC with machine learning (e.g., [
11]) or DRL methods (e.g., [
14]).
This study advances these directions by unifying chart-aware path planning and COLREG-constrained MPC for collision avoidance in a single framework, addressing gaps in dynamic coastal navigation identified in [
2,
5,
19]. MPC is particularly well-suited for autonomous maritime applications, as it naturally accommodates motion constraints, predicts future trajectories, and supports multi-objective optimization. Compared to other MPC-related research works [
10,
11], this study integrates Model Predictive Control with global route planning based on nautical charts, and proposes a novel, simplified, and computationally efficient MPC formulation.
The proposed approach incorporates high-resolution coastline data (GSHHG) to model static obstacles such as land masses and coastal structures. These are treated within the MPC optimization in addition to the dynamic targets, enabling the simultaneous avoidance of both ships and shorelines. Global path planning algorithms are applied to generate a sequence of route waypoints based on chart data, and the MPC controller ensures accurate trajectory tracking and continuous adaptation to environmental changes.
The proposed framework is implemented in MATLAB (R2024b) as a real-time simulation environment with graphical visualization. The system supports multi-vessel scenarios and demonstrates robust performance in diverse navigation conditions, including restricted waters and open seas. The simulation environment is open-source and publicly available on GitHub [
23], providing a valuable tool for the research community to test and develop autonomous navigation strategies.
The main contributions of this paper are as follows:
The integration of GSHHG cartographic data for shoreline-aware navigation.
A two-level navigation system combining global path planning with local MPC-based collision avoidance.
A novel, simplified, and computationally efficient MPC formulation.
A unified MPC navigation framework for autonomous ships integrating COLREG-compliant collision avoidance and trajectory tracking.
An open-source, MATLAB-based multi-vessel simulation environment for the development and testing of autonomous navigation strategies.
The rest of the paper is organized as follows:
Section 2 presents the methodology, with descriptions of the ship model, navigation framework, route following, and MPC-based navigation.
Section 3 discusses the simulation results, and
Section 4 and
Section 5 provide a discussion and summarize the conclusions and future research directions.
2. Methodology
2.1. Navigation Levels
The methodology presented in this paper addresses autonomous ship navigation by combining chart-aware path planning and collision-avoidant navigation across two complementary navigation levels:
Global path planning optimizes a ship’s route from its departure point to its destination, resulting in a sequence of waypoints. A ship’s route optimization is performed in the early stages of navigation using its Electronic Chart Display and Information System (ECDIS) and aims to generate the shortest collision-free route from the starting point to the destination point by considering static obstacles and environmental constraints. The global planner operates using pre-existing cartographic data and defines the high-level route structure for the voyage.
Local collision avoidance and trajectory planning, in contrast, are responsible for dynamic decision-making during navigation. This level operates in real-time and ensures that the vessel adheres to COLREG rules while safely avoiding both static (e.g., landmasses, buoys) and dynamic obstacles (e.g., nearby vessels). The local planner must continuously adapt to unpredictable elements in the environment, such as sudden course or speed changes from other ships. To achieve this, the proposed framework utilizes a Model Predictive Control (MPC) approach, which incorporates the vessel’s basic parameters, prediction of future motion, and multi-objective optimization.
The local planner receives input from sensors and environmental models—such as AIS-based vessel tracking and the ECDIS—to construct a dynamic situational map of the environment. This information is then used in MPC to predict the trajectories of surrounding vessels over a finite time horizon and determine the optimal control actions for the own ship. This allows the ship to make context-aware navigation decisions that balance safety, rule compliance, and trajectory efficiency. The local planner also follows a series of pre-planned waypoints from the global planner and adjusts the ship’s heading accordingly, ensuring smooth and continuous operation even in dense traffic or restricted waters.
This study considers two levels (global path planning and local collision avoidance and trajectory planning) and does not take into account the layer of motion control, which refers to ship steering and closed-loop control. The motion control is considered as a physical implementation of navigation commands, issued at the higher navigation levels, which is not relevant within the scope of this study.
2.2. Global Path Planning
The global path planner operates on electronic nautical charts that include coastline geometry, restricted zones, shallow areas, and other navigational constraints. In this study, the Global Self-consistent Hierarchical High-resolution Geography (GSHHG) dataset was used to construct the situational map of the maritime environment [
24]. Based on GSHHG data, the marine space was segmented into three regions: open sea, land, and coastal areas. Route planning was restricted to the open sea region and needed to avoid land masses while maintaining safe distances from shallow coastal zones.
The global planner computes a sequence of waypoints that form the reference trajectory from the departure location to the intended destination while avoiding non-navigable zones such as land and restricted coastal waters. The planned route can be updated during the voyage in response to mission changes or updated environmental information.
Commonly used algorithms for global route planning include dynamic programming, A*, Theta*, Dijkstra, trajectory point guidance, and others [
25,
26,
27,
28,
29,
30].
Table 1 summarizes and compares the considered path planning algorithms. In this study, the Theta* algorithm was selected to implement the global route planner due to its efficient and smooth pathfinding in complex coastal conditions. The resulting route is a piecewise linear path composed of feasible waypoints that satisfy chart-based constraints and provide a structured input for the local trajectory planner.
To mathematically define the waypoint sequence, let W = [w0, w1, …, wN] denote the ordered set of waypoints, where each waypoint wi ∈ ℝ2 represents a position in a two-dimensional navigational space (latitude and longitude). The waypoint sequence must satisfy the following conditions:
- 2.
The feasibility of route segments, where F ⊆ ℝ2 denotes the set of feasible (navigable) points defined by the chart data and line(·,·) represents the straight-line path between two consecutive waypoints:
- 3.
The path optimality criterion, which corresponds to minimizing the total path length (although other cost functions may be considered depending on mission requirements and environmental factors):
This formulation ensures that the global path is safe, feasible, and structured in a way that supports local trajectory optimization and control.
2.3. Ship Model
The ship model in this study was simplified within the relevance of the upper two navigation levels (global path planning and local collision avoidance and trajectory planning) and was defined by the following parameters:
- -
Ship current location, expressed as latitude and longitude (lat, lon);
- -
Ship direction (θ) and speed over the ground (S);
- -
Max turning angle (∆θmax) (in one iteration of the simulation).
Besides the basic ship parameters, the following zones around the ship, referred to as COLREG application zones in [
31], are defined for collision avoidance assessment:
- -
Collision zone (defined by radius dCollision): objects appearing within radius dCollision from the ship are considered collision cases;
- -
COLREG zone (defined by radius dCOLREG): objects appearing within radius dCOLREG from the ship are visible in the scope of the ship’s situational awareness, and considered potentially hazardous and therefore require attention and appropriate response.
As noted in the review study by Szlapczynski and Szlapczynska [
32], the concept of a ship domain is complex and asymmetric, with safe distances varying in different directions and depending on many factors. These include the own ship’s length, speed, and maneuverability, as well as the target ship’s size and speed, encounter angle, environmental conditions, and traffic density. While there is no single IMO-mandated standard for ship safety domain size, the values of the collision zone radius dCollision = 0.5 nm and the COLREG zone radius dCOLREG = 3 nm were chosen in this study as a balance between established ship domain models and practical implementation constraints in multi-ship encounter scenarios.
Figure 1 presents the ship model and the COLREG application zones.
2.4. Navigation Framework
The proposed navigation framework consists of a hierarchically organized structure integrating global path planning and local collision avoidance into a coherent decision-making system. The core concept is that the ship continuously follows a planned route (route following) generated by the global planner, but switches to a collision avoidance mode when potential hazards are detected within the COLREG zone. During normal operation in the open sea without immediate hazards, the ship follows the pre-computed global trajectory defined by a sequence of waypoints. This process, referred to as route following, involves adjusting the vessel’s heading to remain on course while maintaining navigational efficiency. Route following assumes no immediate threat and allows for energy-efficient and direct transit.
However, when an obstacle (another vessel or landmass) is detected within the COLREG zone (defined as 3 nm in this study), the system transitions to MPC-based collision avoidance. In this regime, the local planner overrides simple waypoint following and takes full control of navigation by computing control actions using Model Predictive Control. The MPC module uses dynamic models and situational awareness data to predict the behavior of surrounding vessels, assess potential collision risks, and generate collision avoidance maneuvers that comply with COLREG rules.
Situational awareness and hazard detection are not addressed by this study; namely, modern autonomous navigation architectures rely on a dedicated module to provide real-time perception and interpretation of the maritime environment. The situational awareness module typically fuses data from multiple sources—such as AIS, radar, optical and infrared cameras, and LiDAR—to construct a reliable and up-to-date situational map. Recent studies demonstrate the effectiveness of multimodal sensor fusion using deep learning and probabilistic models for robust perception in complex maritime environments.
For example, Thombre et al. review key sensing modalities and AI techniques for autonomous ships, including abnormality detection and vessel classification [
33]. Dagdilelis et al. present a deep fusion architecture that integrates RGB, infrared, radar, and LiDAR data into a unified birds-eye view for enhanced decision-making [
34]. To improve the real-time detection and classification of maritime obstacles, Ponzini et al. propose a hybrid learning framework combining unsupervised LiDAR detection with supervised target classification [
35], and Qiao et al. summarize the use of deep learning in situational awareness of the ocean surface in their review [
36].
Furthermore, Liu et al. propose a dynamic risk assessment model to solve the problem of uncertainty and realize the fusion of multi-source information for the navigational safety evaluation of inland waterway ships under uncertain environmental conditions [
37]. And Chen et al. present an advanced ship detection framework based on ensemble generative adversarial networks to enhance perception robustness in low-visibility weather conditions [
38].
These studies provide insight into the autonomous perception layer that allows decision-making and control modules to focus on trajectory planning and collision avoidance.
The transition between route following and MPC-based collision avoidance is continuous and adaptive. The decision logic operates as a supervisory layer that monitors the environment in real time and switches between control modes depending on the proximity and type of obstacles:
If no vessel or obstacle is present within the COLREG zone, the ship remains in the route-following mode.
If an object enters the COLREG zone, the MPC-based local planner becomes active in assessing the situation and preparing corrective actions to prevent the object (or multiple objects) from entering the collision zone.
After the conflict is resolved and the environment is clear again, the system reverts to the route-following mode, resuming navigation along the global trajectory. This switching mechanism, presented in
Figure 2, ensures a safe, COLREG-compliant, and efficient autonomous navigation process that dynamically adapts to environmental changes and traffic density, particularly in constrained or high-traffic maritime areas.
2.5. Route Following
Route following represents the baseline navigation behavior in the absence of imminent collision threats. During this mode, the vessel is guided along the pre-computed global path defined by the ordered set of waypoints
W = [
w0,
w1, …,
wN], as introduced in
Section 2.2. The primary objective is to reach each waypoint sequentially while maintaining heading alignment, minimizing deviations from the nominal route and ensuring efficient transit.
At each time step
t, the ship determines the next waypoint target w
i+1 based on its current position
p(
t) ∈ ℝ
2. A guidance law computes the target heading angle
θTarget(
t), which points toward the current target waypoint:
To avoid rapid oscillation near waypoint transitions and to ensure smooth path progression, a transition radius
rtran is defined around each waypoint. The ship switches its active target from w
i to w
i+1 once it enters the circular region:
This simple logic enables robust and efficient waypoint tracking in open waters. The switching radius is, in this study, set to the collision zone radius
dCollision. The motion control system adjusts the actual heading
θ(
t) toward
θTarget(
t) using proportional control (or more-advanced heading controllers). The heading error is defined as
and the rudder or propulsion system responds accordingly to minimize
eθ over time, subject to the vessel’s dynamic constraints (maximum turning rate ∆
θmax).
Route following remains active as long as no obstacles are detected within the COLREG zone. In such conditions, the system focuses on energy-efficient and accurate progression along the planned trajectory. Once a potential hazard is detected, the supervisory navigation module suspends the route-following mode and activates the MPC-based local planner for collision avoidance.
2.6. MPC-Based Collision Avoidance
The collision avoidance mechanism within the navigation framework is activated when potential hazards are detected within the COLREG zone. This mechanism operates in two sequential steps. First, COLREG rules are applied to assess the type of encounter and ensure regulatory compliance, and the behavior of surrounding vessels in the simulation environment is adjusted based on rule-based logic. Second, the MPC-based controller computes optimal collision avoidance maneuvers for the own ship based on predicted trajectories. Rather than explicitly coding COLREG rules, the navigation logic for the own ship relies on real-time optimization to implicitly enforce collision-avoidant behavior. This approach reflects the growing trend in autonomous systems toward integrated, model-based control architectures.
2.6.1. COLREG Compliance
It is expected that the maneuverability of MASSs will far exceed that of manned ships, and the avoidance priority should be lower than manned ships under the “unmanned–manned” encounter situation. Therefore, Gao et al. proposed updating the maritime navigation regulations for MASSs as follows [
39]: “Under the maritime encounter situation of unmanned-manned, the avoidance priority of MASS is lower than manned. A MASS underway shall keep out of the way of manned ship and a MASS shall not impede the passage of any other manned navigating vessels”. In accordance with this principle, the navigation framework assumes a conservative behavior for MASSs: it always prioritizes avoiding any other vessel, manned or unmanned. As such, MPC-based collision avoidance is used as the default navigation mode.
To ensure formal compliance with COLREGs, a rule-based COLREG layer was implemented. This layer operates independently of the MPC-based navigation and modifies the behavior of surrounding vessels in the simulation environment based on rule-based logic. When another ship enters the defined COLREG zone, the rule-based layer evaluates the situation and classifies the encounter into one of the standard types defined by COLREG: head-on, overtaking, or crossing. Encounter classification is based on the relative bearing
M°, relative speed
SR, and own and target ship heading (
θO,
θT) and courses (
CO,
CT), along with their respective speeds (
SO,
ST).
Table 2 summarizes the rule formalization adapted from [
3].
These rules are enforced on the simulated behavior of other ships in the environment. When the own ship has the right of way (e.g., when being overtaken or approached from the port side), the heading of the target ship θT is adjusted to simulate compliant behavior: θT(t + 1) = θT(t) + ∆θ(t), where ∆θ = ∆θmax is chosen to gradually steer the ship away from a potential collision course.
However, to ensure safety and robustness, even when own ship has the right of way, the MPC controller continues to generate avoidance maneuvers if the predicted trajectories over the horizon show an imminent risk of collision (e.g., distance less than a safety threshold. While explicit COLREG rule classification is not implemented in the proposed system for the own ship (MASS), compliance is achieved implicitly through conservative navigation and continuous conflict resolution. The MPC-based control prioritizes safety in complex multi-ship scenarios, where traditional pairwise rule logic may become ambiguous or conflicting.
2.6.2. General MPC Formulation
Following the COLREG assessment, the MPC-based collision avoidance strategy is executed for the own ship. At each control step, the MPC module solves an optimization problem over a finite prediction horizon
H, where the objective is to determine the optimal control inputs (ship headings) that minimize a cost function while satisfying dynamic constraints. The MPC formulation is based on a general MPC algorithm [
40] and was adapted to the ship navigation in this study by appropriately defining the state vector, control, objective function, and constraints.
The state vector
x and control
u in this study are defined as
where
t denotes the discrete time step, (
lat, lon) position coordinates,
θ heading,
S speed over ground, and Δ
θ the change in heading. The vessel’s motion is described by a simplified kinematic model:
In a general MPC formulation, objective function
J is defined over a finite prediction horizon
H, and can be represented by terms describing adherence to the reference trajectory (i.e., route following toward the next waypoint
wi+1), minimizing control effort, and avoiding collisions with static obstacles
and nearby vessels
:
where
- -
xh is the predicted state of the own ship at prediction step h;
- -
uh = Δθh is the control input (change in heading);
- -
wi+1 is the position of the next waypoint;
- -
is the predicted state of vessel i ∈ at step h;
- -
PObstacle is a penalty function for proximity to a static obstacle;
- -
PCollision is a penalty function for proximity to another vessel,
- -
λu, λo, and λc are weighting parameters that determine the relative importance of control effort, obstacle avoidance, and collision avoidance.
The cost function is minimized at each control step, subject to the following constraints:
- -
Ship dynamics: As defined above (Equations (9)–(11));
- -
Control limits: |Δθh| ≤ Δθmax;
- -
Collision avoidance (static): ∀j ∈ , dCollision;
- -
Collision avoidance (dynamic): ∀i ∈ , dCollision.
By solving this constrained optimization problem at each time step using updated situational data, the MPC framework provides adaptive, rule-compliant navigation that accounts for both static and dynamic obstacles. This enables the ship to adapt in real-time to dynamic environmental changes, such as course or speed variations from nearby vessels, and ensures that the ship remains compliant with COLREG rules throughout the navigation.
The predicted trajectories of nearby vessels can be calculated based on situational awareness data (AIS, radar, etc.) and extrapolated using a constant velocity model, though more advanced motion prediction models can be integrated. At each control step, the optimal control sequence {Δθ1, Δθ2, …, ΔθH} is computed, and only the first control input Δθ1 is applied to the ship model. The process is then repeated at the next time step using updated environmental data (receding horizon approach).
2.6.3. Simplified MPC Formulation
While the general MPC formulation provides a powerful framework for collision avoidance, it may be computationally demanding for real-time applications in resource-constrained systems. Therefore, this study proposes a simplified, heuristic-based version that preserves the predictive control approach and safety guarantees while reducing the computational burden. The proposed simplified MPC strategy consists of the following steps, executed at each control interval:
Generation of candidate trajectories:
A discrete set of
M fan-shaped trajectories is generated from the current ship state
x(
t), each corresponding to a fixed heading increment Δ
θm ∈ [−Δ
θmax, Δ
θmax], where
m = 1, …,
M. Each trajectory
τm is simulated over the prediction horizon
H using the kinematic model (Equations (9)–(11)):
Feasibility filtering:
Each trajectory τm is evaluated for potential collisions with
- -
Static obstacles ;
- -
The predicted positions of nearby vessels .
A binary feasibility function
F(
τm) is defined as
Only trajectories with F(τm) = 1 are retained for further evaluation.
Selection of optimal trajectory:
Let wi+1 be the next waypoint and θTarget (Equation (4)) be the bearing to the waypoint. If the vessel’s current heading θ(t) is within [−90, 90°] of the direction to the next waypoint (the ship is approaching the waypoint), the trajectory whose initial segment most closely aligns with the bearing to the waypoint is selected. Otherwise, the trajectory that ends closest to the next waypoint is chosen. This selection rule is expressed as follows:
If the current ship heading
θ(
t) satisfies
then select
This rule-based trajectory filtering and selection strategy significantly reduces the number of candidate solutions to be evaluated, allowing real-time operation even on low-power systems. Despite its simplicity, the approach preserves key features of MPC, such as receding horizon control and predictive situational awareness. This simplified controller is particularly suitable for near-shore navigation or congested traffic areas, where computational efficiency and rapid response are essential.
To ensure COLREG-compliant behavior, the collision avoidance formulation was designed to favor conservative maneuvers that prioritize yielding to surrounding vessels. This strategy aligns with current regulatory recommendations for MASSs and is embedded in the feasibility filtering of the MPC optimization.
An illustrative example of the proposed simplified MPC-based formulation is presented in
Figure 3. The own ship is depicted in blue, along with its current set of candidate trajectories. Infeasible trajectories (
F(
τm) = 0), which are discarded, are shown in red, while feasible ones (
F(
τm) = 1), retained for further evaluation, are shown in green. The optimal trajectory
τ*, selected according to Equation (16), is highlighted in blue. The magenta line indicates the reference direction toward the next waypoint. Surrounding vessels are shown in red, with their headings and velocities represented as forward-pointing vectors.
2.7. Simulation Setup
To evaluate the performance of the proposed MPC-based navigation strategy, a multi-vessel simulation environment was implemented in MATLAB (R2024b) and Mapping Toolbox (Version 24.2). The simulation framework modeled vessel dynamics, environmental constraints, rule-based interactions in accordance with COLREGs, and the proposed route following and MCP-based collision avoidance methods. It supported the real-time visualization of vessel motion, including heading vectors, the safety zone of the own ship, and predicted trajectories. The simulation environment entitled “MPC-Autonomous-Ship-Navigation” is provided as open source on GitHub [
23].
The simulation area was geographically defined in the Adriatic Sea and included the port of Split and the surrounding islands (Šolta, Vis, Brač, Hvar). Within this area, three initial waypoints (WP1, WP2, WP3) were set to define required stopovers, and a circular route—starting from the port of Split, passing Vis Island, continuing around Hvar Island, and returning to Split—was computed using the Theta* path planner (see
Section 2.2). All vessels in the simulation were modeled as point masses with discrete-time kinematic updates.
The own ship was controlled using the simplified MPC formulation described in
Section 2.6.3, while the other ships (target ships) follow predefined trajectories with constant velocities and headings and are subject to COLREG compliance as described in
Section 2.6.1. When a target ship encountered the coastline, its heading was reversed to maintain motion within the simulation bounds. This resulted in a highly dynamic and challenging marine environment, well suited for evaluating the proposed method. The key parameters of the simulation are summarized in
Table 3.
Ship speed was adjusted in the simulation proportionally so that the path traveled within the specified prediction horizon H matched the borders of the COLREG zone. To achieve this, the prediction horizon H = 16 was selected so that the total predicted travel distance within the MPC time window corresponded to the 3 nm radius of the COLREG zone. This design ensured that the controller anticipated all relevant encounters within the active COLREG zone. The choice of prediction horizon length is an open simulation parameter and can be adjusted for different simulation scenarios. The computation cost of the algorithm increases linearly with the length of H, allowing scalability depending on the required foresight range.
The initial positions and headings of the surrounding vessels were randomized for each simulation run, yielding diverse and unpredictable encounter scenarios. All scenarios were executed until the ship reached the final waypoint or until a violation of safety constraints (e.g., collision) was detected. The simulation area, along with the route of the own ship and the positions and headings of the surrounding vessels, is illustrated in
Figure 4.
4. Discussion
The simulation results demonstrate that the proposed MPC-based navigation framework effectively handles a broad range of maritime scenarios, ranging from simple rule-based encounters (e.g., head-on, crossing, overtaking) to more complex multi-ship interactions in coastal environments. The system demonstrates real-time decision-making and adaptability to dynamic conditions by continuously optimizing the ship’s trajectory within a predictive horizon. A link to the simulation example video is provided in the
Supplementary Materials.
Although rule classification is not explicitly performed, the resulting behavior remains conservative and compliant with COLREG principles. One of the key advantages of the MPC approach lies in its ability to resolve conflicting objectives—such as safety, rule compliance, and navigation efficiency—within a unified framework. For example, in both head-on and crossing scenarios, the own ship adjusts its course only as much as is necessary, minimizing deviation from the intended path while still achieving collision avoidance. Similarly, in overtaking situations, the controller ensures that the maneuver is not only safe but also efficient in terms of path length and energy expenditure.
The MPC-based navigation becomes especially relevant in multi-ship scenarios, where the complexity of applying COLREG rules increases significantly. Traditional rule-based systems may fail to coordinate interactions involving more than two vessels or may generate overly conservative behavior. In contrast, the MPC controller evaluates the future trajectories of all surrounding vessels and selects efficient avoidance strategies that are both collision-free and optimal with respect to route following.
It should be noted that increasing the number of ships in the simulation only partially increases the computational load of the local MPC-based guidance system for the own ship, since only vessels within the COLREG zone are considered potentially hazardous and included in the MPC optimization. Furthermore, the computational time related to feasibility checking, as expressed in Equation (14), increases linearly with the number of ships present within the COLREG zone.
The proposed framework provides a promising foundation for further development toward safe, autonomous maritime operations in both constrained and unconstrained environments.
However, some limitations of the proposed approach can be noted. First, the MPC-based controller operates within a finite prediction horizon
H, which does not take into account long-term interactions or global obstacles (e.g., long coastlines or traffic separation schemes). As discussed in
Section 3.1, local planning alone may fail in complex environments, underscoring the need for integration with a global route planner. In this simulation study, a predictive horizon of
H = 16 was used; however, its length can be adjusted to match the complexity of the navigation context.
Second, this approach assumes that the motion of surrounding vessels can be reasonably predicted over the control horizon. In real-world conditions, where ships may behave unpredictably or violate COLREGs, additional mechanisms—such as intent inference or probabilistic modeling—may be required to ensure safety.
Finally, while the simulations rely on predefined ship dynamics and perfect state estimation, real-world deployment would necessitate robustness to sensor noise, environmental disturbances (e.g., wind, current), and communication delays. Future work may focus on incorporating environmental uncertainty, validating the approach in hardware-in-the-loop simulations, and extending the framework to mixed-traffic scenarios involving human-operated and autonomous vessels.
5. Conclusions
A Model Predictive Control-based approach for autonomous ship navigation, combined with chart-based route planning, is proposed in this paper. The framework integrates dynamic trajectory tracking with COLREG-compliant MPC-based collision avoidance, enabling Maritime Autonomous Surface Ships (MASSs) to navigate safely and efficiently in complex maritime environments. Using predefined waypoints and maritime charts, the system generates feasible reference paths, while the MPC controller ensures accurate path following and reactive maneuvering in response to dynamic vessels and coastal obstacles. Landmasses are modeled using GSHHG data, and other ships are treated as COLREG-compliant dynamic agents. Simulations demonstrate successful and robust collision avoidance and regulatory compliance across multi-vessel scenarios. The main novelties of the proposed approach include the following:
The seamless integration of MPC, chart-based planning, and COLREG rules in a unified framework.
A simplified MPC formulation that retains a predictive control approach while reducing computational demands, making it suitable for real-world implementation.
The implementation of an open-source simulation environment for demonstrating and testing the proposed autonomous ship navigation, supporting multi-ship scenarios, real-time visualization, and decision-making analysis.
These contributions highlight the potential of the proposed system in addressing the challenges of autonomous navigation for MASSs. The simplified MPC formulation reduces the computational burden while maintaining the integrity of the control approach, thus making it suitable for practical deployment in a variety of autonomous vessels. Additionally, the open-source simulation platform developed in this study [
23] provides valuable insights into the performance of the navigation system, allowing for further testing and refinement in different operational settings.
Future work will focus on expanding the simulation framework to include more realistic environmental factors, as well as enhancing the adaptability of the system to more complex, real-time decision-making scenarios. Furthermore, future research will address multi-MASS scenarios, where multiple autonomous ships utilize the same MPC-based navigation approach, requiring detailed analysis of their interactions. The current implementation operates under assumptions about the predictability of surrounding traffic and ideal sensing, and is limited by the finite prediction horizon. Therefore, these limitations also point to additional directions for future work, including integration with global route planners that incorporate environmental uncertainty and validation in real-world or hardware-in-the-loop settings.
The presented MPC framework provides a promising foundation for the development of intelligent, autonomous navigation systems capable of operating safely and efficiently in complex maritime environments. Extending the framework to support heterogeneous traffic—combining global planning, data-driven prediction models, and vessel-to-vessel communication—will be crucial for the practical deployment of autonomous maritime operations.