API reference
This page lists the main public types and functions, grouped by purpose. See the other pages for motivation, theory, and examples.
Types
MarineSystemsSim.AbstractVesselModel — Type
abstract type AbstractVesselModel{N, T}Abstract supertype for vessel models with N degrees of freedom and scalar type T.
Concrete subtypes represent a specific dynamic vessel model (for example a cached 3-DOF or 6-DOF model) and are expected to implement at least the following interface:
mass_matrix(model::AbstractVesselModel): return the generalized mass matrixM.damping_forces(nu, model::AbstractVesselModel): return the damping termD(ν) ν.coriolis_forces(nu, model::AbstractVesselModel): return the Coriolis/centripetal termC(ν) ν.kinematics(eta, nu, model::AbstractVesselModel): return the kinematic relationη̇.
The high-level routines body_dynamics, vessel_dynamics, and vessel_rhs! use these functions to assemble the equations of motion in a DOF-agnostic way.
MarineSystemsSim.RigidBody3DOF — Type
struct RigidBody3DOF{T<:Real}Rigid-body parameters for 3-DOF motion in the horizontal plane.
Fields
m::T: Mass of the vessel [kg].Iz::T: Yaw moment of inertia about the z-axis [kg*m^2].xG::T: x-position of the center of gravity in the body-fixed frame [m].
Notes
The 3-DOF rigid-body mass matrix is
[ m 0 0
0 m m*xG
0 m*xG Iz ]MarineSystemsSim.QuadraticDamping3DOF — Type
struct QuadraticDamping3DOF{T<:Real}Quadratic (velocity-dependent) damping parameters for the 3-DOF model.
This type stores Fossen-style manoeuvring derivatives for the diagonal approximation to the nonlinear damping matrix. They appear in the velocity-dependent damping term
D_n(ν) ν = -diag(X_uu * |u|, Y_vv * |v|, N_rr * |r|) ν.Sign convention:
Xuu,Yvv,Nrrcorrespond to the hydrodynamic derivativesX_uu, Y_vv, N_rrin Fossen's notation.- In many identification schemes these are non-positive so that the effective damping is dissipative, but this is not enforced here.
MarineSystemsSim.HydroParams3DOF — Type
struct HydroParams3DOF{T<:Real}Hydrodynamic parameters for 3-DOF surge–sway–yaw motion.
The 3-DOF vessel model is written as
M ν̇ + C(ν) ν + D(ν) ν = τ,where M = M_RB + M_A and D = D_lin + D_n(ν).
HydroParams3DOF stores the hydrodynamic contribution in matrix form:
M_A— the 3×3 added-mass matrix.D_lin— the 3×3 linear manoeuvring damping matrix.D_quad— quadratic damping coefficients used to build the velocity-dependent matrixD_n(ν).
In the standard Fossen 3-DOF surface craft model these matrices have a particular structure. That structure is not required by the core routines in this package, but it is enforced if you construct HydroParams3DOF via hydroparams_fossen3dof.
MarineSystemsSim.VesselParams3DOF — Type
struct VesselParams3DOF{T<:Real}Collects all 3-DOF vessel parameters: rigid-body and hydrodynamics.
This is the main input data structure for the rest of the 3-DOF MSS.
MarineSystemsSim.Vessel3DOF — Type
struct Vessel3DOF{T<:Real} <: MarineSystemsSim.AbstractVesselModel{3, T<:Real}3-DOF vessel model with cached mass matrices.
This type stores the physical parameters together with the assembled inertia and linear damping matrices to avoid recomputing them inside tight simulation loops.
Fossen-style helpers
MarineSystemsSim.hydroparams_fossen3dof — Function
hydroparams_fossen3dof(
Xudot::Real,
Yvdot::Real,
Yrdot::Real,
Nrdot::Real,
Xu::Real,
Yv::Real,
Yr::Real,
Nv::Real,
Nr::Real,
Xuu::Real,
Yvv::Real,
Nrr::Real;
Xv,
Xr,
Yu,
Nu
) -> HydroParams3DOF
Construct hydrodynamic parameters for the 3-DOF model from Fossen-style manoeuvring derivatives.
This helper maps the usual surge–sway–yaw derivatives
- Added mass:
Xudot,Yvdot,Yrdot,Nrdot - Linear damping:
Xu,Yv,Yr,Nv,Nrplus optional cross-termsXv,Xr,Yu,Nu - Quadratic damping:
Xuu,Yvv,Nrr
into the internal representation HydroParams3DOF, i.e. the added-mass matrix M_A, the linear damping matrix D_lin, and the quadratic coefficients D_quad.
All derivatives are given with Fossen's sign convention; no sign flips are applied.
MarineSystemsSim.vesselparams_fossen3dof — Function
vesselparams_fossen3dof(
m::Real,
Iz::Real,
xG::Real,
Xudot::Real,
Yvdot::Real,
Yrdot::Real,
Nrdot::Real,
Xu::Real,
Yv::Real,
Yr::Real,
Nv::Real,
Nr::Real,
Xuu::Real,
Yvv::Real,
Nrr::Real;
Xv,
Xr,
Yu,
Nu
) -> VesselParams3DOF
Convenience constructor for 3-DOF vessel parameters from Fossen-style manoeuvring derivatives.
This wraps hydroparams_fossen3dof and VesselParams3DOF into a single call:
- builds
HydroParams3DOFfrom added-mass and damping derivatives, and - returns
VesselParams3DOF(rb, hydro).
All derivatives use Fossen's sign convention (linear and quadratic drag derivatives are typically ≤ 0).
MarineSystemsSim.build_vessel3dof_fossen — Function
build_vessel3dof_fossen(
args...;
check_physical,
kwargs...
) -> Vessel3DOF
Convenience constructor for a cached 3-DOF vessel model from Fossen-style rigid-body and manoeuvring derivatives.
Wraps vesselparams_fossen3dof and Vessel3DOF into a single call.
All derivatives are given with Fossen's sign convention; no sign flips are applied.
Keyword:
check_physical::Bool = true: run heuristic checks and emit warnings if the resulting model looks suspicious.
Kinematics and frames
MarineSystemsSim.rotation_body_to_earth — Function
rotation_body_to_earth(ψ::Real) -> Any
Rotation matrix from body-fixed to Earth-fixed frame in the horizontal plane.
The mapping is
η̇ = R(ψ) ν
η = [x, y, ψ]ᵀ
ν = [u, v, r]ᵀ.MarineSystemsSim.kinematics — Function
Return the kinematic relation η̇ for the given vessel model, based on position/orientation η and body-fixed velocity ν.
Concrete subtypes of AbstractVesselModel must implement this method.
kinematics(
eta::StaticArraysCore.SArray{Tuple{3}, S<:Real, 1, 3},
nu::StaticArraysCore.SArray{Tuple{3}, S<:Real, 1, 3}
) -> Any
Compute the kinematic relation
η̇ = R(ψ) νfor 3-DOF motion in the horizontal plane.
- η = [x, y, ψ]ᵀ is the position and yaw angle,
- ν = [u, v, r]ᵀ is the body-fixed velocity vector.
Returns an SVector{3} representing η̇.
kinematics(
eta::StaticArraysCore.SVector{3},
nu::StaticArraysCore.SVector{3},
_::Vessel3DOF
) -> Any
3-DOF kinematics η̇ = R(ψ) ν for the cached vessel model.
This method dispatches to the 3-DOF kinematic relation defined in kinematics(η, ν) and exists to satisfy the interface defined for AbstractVesselModel.
Core dynamics and ODE helpers
MarineSystemsSim.dofs — Function
Return the number of degrees of freedom for a vessel model.
MarineSystemsSim.mass_matrix — Function
Return the generalized mass matrix for the given vessel model model.
Concrete subtypes of AbstractVesselModel must implement this method.
mass_matrix(params::VesselParams3DOF{T<:Real}) -> Any
Build the 3×3 rigid-body + added-mass inertia matrix in surge–sway–yaw:
M = M_RB + M_Awhere M_RB is built from RigidBody3DOF and M_A from HydroParams3DOF.
mass_matrix(
model::Vessel3DOF
) -> StaticArraysCore.SMatrix{3, 3, T} where T<:Real
Return the constant 3×3 inertia matrix M for the cached 3-DOF model.
MarineSystemsSim.damping_forces — Function
Return the damping term D(ν) ν for the given vessel model and body-fixed velocity ν.
Concrete subtypes of AbstractVesselModel must implement this method.
damping_forces(
nu::StaticArraysCore.SArray{Tuple{3}, S<:Real, 1, 3},
model::Vessel3DOF{T<:Real}
) -> Any
Compute hydrodynamic damping forces/moments in surge, sway and yaw.
Given body-fixed velocity
ν = [u, v, r]ᵀ,this function evaluates the total damping matrix
D(ν) = D_lin + D_n(ν),and returns the product
D(ν) ν.Here D_lin is the cached linear damping matrix from the model and D_n(ν) is constructed from the quadratic coefficients stored in model.params.hydro.D_quad.
Returns an SVector{3} containing the damping forces/moment [X_d, Y_d, N_d]ᵀ.
MarineSystemsSim.coriolis_forces — Function
Return the Coriolis/centripetal term C(ν) ν for the given vessel model and body-fixed velocity ν.
Concrete subtypes of AbstractVesselModel must implement this method.
coriolis_forces(
nu::StaticArraysCore.SArray{Tuple{3}, S<:Real, 1, 3},
model::Vessel3DOF{T<:Real}
) -> Any
Compute the Coriolis/centripetal term C(ν) ν for the 3-DOF model.
The implementation constructs both the rigid-body part CRB(ν) and the added-mass part CA(ν) as 3×3 matrices following the standard Fossen 3-DOF surface craft model, and returns
C(ν) ν = (C_RB(ν) + C_A(ν)) ν.Returns an SVector{3} representing C(ν) ν.
MarineSystemsSim.body_dynamics — Function
Compute the body-fixed acceleration ν̇ for a vessel model given the generalised forces τ.
The default implementation uses the interface functions damping_forces, coriolis_forces and mass_solve:
M ν̇ + C(ν) ν + D(ν) ν = τ
ν̇ = M⁻¹ (τ - C(ν) ν - D(ν) ν).MarineSystemsSim.vessel_dynamics — Function
Compute the full state derivative [η̇; ν̇] for a vessel model.
The state vector is ordered as
X = [η; ν],where both η and ν have length N = dofs(model).
The default implementation splits X, calls kinematics and body_dynamics, and concatenates the results. Concrete vessel models can provide more specialised methods if needed.
MarineSystemsSim.vessel_rhs! — Function
In-place ODE right-hand side for a vessel model.
Evaluates the generalized forces τ = τfun(X, t) and computes the state derivative dX using vessel_dynamics. This function is intended for use with time integrators such as DifferentialEquations.jl.
If additional modules (e.g. for thrusters, controllers, or 6-DOF extensions) are added later, their public API can be listed in separate sections here.
Internal helpers (advanced)
MarineSystemsSim.mass_solve — Function
Solve M ν̇ = rhs for ν̇, using the mass matrix associated with the vessel model.
The default implementation calls mass_matrix(model) \ rhs. Concrete vessel models can override this method to use cached inverses or factorisations for efficiency.