munetauvsim.gnc

Utility functions supporting GNC algorithms and vehicle dynamics.

Provides mathematical and computational support for guidance, navigation, and control algorithms. Includes angle normalization, matrix transformations, hydrodynamic force calculations, and system utilities based on Fossen’s marine vehicle dynamics framework.

Functions

Angle and Matrix Operations

ssa(angle) : Produces shortest signed angle to [-pi to pi). Smtrx(a) : Create 3x3 skew-symmetric matrix from vector. Hmtrx(r) : Compute 6x6 system transformation matrix. m2c(M, nu) : Converts mass matrix and velocity to Coriolis matrix.

Hydrodynamic Forces

Hoerner(B, T) : Compute 2D Hoerner cross-flow drag coefficient. crossFlowDrag(L, B, T, nu) : Calculates cross-flow drag forces. forceLiftDrag(b, S, CD_0, alpha, U_r) : Computes lift and drag forces. gvect(W, B, theta, phi, r_bg, r_bb) : Computes restoring forces.

Utilities

saturation(value, limit, maxLimit) : clamp value to interval.

References

[1] Fossen, T. I. and Perez, T. (2004). Marine Systems Simulator (MSS). https://github.com/cybergalactic/MSS

[2] Fossen, T.I. Python Vehicle Simulator. GitHub repository. https://github.com/cybergalactic/PythonVehicleSimulator

Functions

Hmtrx(r)

Compute 6x6 system transformation matrix.

Hoerner(B, T)

Compute 2D Hoerner cross-flow drag coefficient.

Smtrx(a)

Create 3x3 skew-symmetric matrix from vector.

crossFlowDrag(L, B, T, nu_r)

Compute cross-flow drag forces using strip theory.

forceLiftDrag(b, S, CD_0, alpha, U_r)

Compute lift and drag forces on submerged wing profile.

gvect(W, B, theta, phi, r_bg, r_bb)

Compute restoring force vector for submerged body.

m2c(M, nu)

Compute Coriolis-centripetal matrix from mass matrix and velocity.

saturation(value, limit[, maxLimit])

Clamp value to specified interval.

ssa(angle)

Compute the smallest signed angle to range [-pi, pi).

Classes

NDArray

alias of ndarray[Any, dtype[ScalarType]]

NPFltArr

alias of ndarray[Any, dtype[float64]]

munetauvsim.gnc.ssa(angle)[source]

Compute the smallest signed angle to range [-pi, pi).

Two angles define two points on a circle and the smallest signed angle (SSA) is the smaller of the two arcs created between them. The sign corresponds to the direction taken around the circle with the clock-wise direction being positive.

Parameters:

angle (float) – Angle in radians (any value).

Returns:

ssa_angle (float) – Angle wrapped to [-pi, pi).

Return type:

float

Notes

If the angle provided is the difference between two angles, then this function computes the smallest signed angle, and in other cases the result is to normalize the input angle to the range [-pi, pi).

munetauvsim.gnc.Smtrx(a)[source]

Create 3x3 skew-symmetric matrix from vector.

Parameters:

a (array_like, shape (3,)) – Input vector [a1, a2, a3].

Returns:

S (ndarray, shape (3, 3)) – Skew-symmetric matrix satisfying a x b = S(a)b.

Return type:

ndarray[Any, dtype[float64]]

Notes

  • S(a) = -S(a)’ (antisymmetric property).

  • Used in cross product and Coriolis matrix calculations.

munetauvsim.gnc.Hmtrx(r)[source]

Compute 6x6 system transformation matrix.

Parameters:

r (array_like, shape (3,)) – Position vector [x, y, z] in meters.

Returns:

H (ndarray, shape (6, 6)) – System transformation matrix.

Return type:

ndarray[Any, dtype[float64]]

Notes

H = [ eye(3), S’

zeros(3,3), eye(3) ]

With the property: inv(H(r)) = H(-r)

If r = r_bg is the vector from the CO to the CG, the model matrices in CO and CG are related by: M_CO = H(r_bg)’ * M_CG * H(r_bg).

Generalized position and force satisfy:

eta_CO = H(r_bg)’ * eta_CG and tau_CO = H(r_bg)’ * tau_CG

munetauvsim.gnc.m2c(M, nu)[source]

Compute Coriolis-centripetal matrix from mass matrix and velocity.

Parameters:
  • M (ndarray, shape (n, n)) – Mass matrix (n = 3 or 6 DOF).

  • nu (ndarray, shape (n,)) – Body-frame velocity [u, v, w, p, q, r] (6-DOF) or [u, v, r] (3-DOF).

Returns:

C (ndarray, shape (n, n)) – Coriolis-centripetal matrix.

Return type:

ndarray[Any, dtype[float64]]

Notes

  • For 6-DOF: C computed from velocity-dependent skew-symmetric terms.

  • For 3-DOF: Simplified yaw-only formulation.

  • Used in dynamics: M d/dt nu + C(nu)*nu + D(nu)*nu + g(eta) = tau.

munetauvsim.gnc.Hoerner(B, T)[source]

Compute 2D Hoerner cross-flow drag coefficient.

Parameters:
  • B (float) – Beam (width of hull at it’s widest point) in meters.

  • T (float) – Draft (depth of hull’s deepest point below waterline) in meters.

Returns:

CY_2D (float) – Cross-flow drag coefficient (dimensionless).

Return type:

float

Notes

Uses interpolation of Hoerner’s empirical curve based on B/(2T) ratio.

munetauvsim.gnc.crossFlowDrag(L, B, T, nu_r)[source]

Compute cross-flow drag forces using strip theory.

Parameters:
  • L (float) – Hull length in meters.

  • B (float) – Beam (width of hull at it’s widest point) in meters.

  • T (float) – Draft (depth of hull’s deepest point below waterline) in meters.

  • nu_r (ndarray, shape (6,)) – Relative linear and angular velocity [u, v, w, p, q, r] in body frame.

Returns:

tau_crossflow (ndarray, shape (6,)) – Generalized force vector [X, Y, Z, K, M, N]. Only Y (sway) and N (yaw) components nonzero.

Return type:

ndarray[Any, dtype[float64]]

Notes

  • Divides hull into 20 strips and integrates drag along length.

  • Apply as: M d/dt nu + C(nu)*nu + D(nu)*nu + g(eta) = tau + tau_crossflow.

munetauvsim.gnc.forceLiftDrag(b, S, CD_0, alpha, U_r)[source]

Compute lift and drag forces on submerged wing profile.

Parameters:
  • b (float) – Wing span in meters.

  • S (float) – Wing area in m^2.

  • CD_0 (float) – Parasitic drag coefficient (at alpha=0), typically 0.1-0.2.

  • alpha (float) – Angle of attack in radians.

  • U_r (float) – Relative flow speed in m/s.

Returns:

tau_liftdrag (ndarray, shape (6,)) – Generalized force [X, Y, Z, K, M, N] in body frame. Only X (surge) and Z (heave) components nonzero.

Return type:

ndarray[Any, dtype[float64]]

Notes

  • Lift: CL(alpha) = CL_alpha * alpha (linear model)

  • Drag: CD(alpha) = CD_0 + CL^2 / (pi * e * AR)

  • Forces: F = 1/2 rho U^2 * S * C

  • Apply as: M d/dt nu + C(nu)nu + D(nu)nu + g(eta) = tau + tau_liftdrag.

  • Based on Beard & McLain (2012) aerodynamic model.

munetauvsim.gnc.gvect(W, B, theta, phi, r_bg, r_bb)[source]

Compute restoring force vector for submerged body.

Parameters:
  • W (float) – Weight in kg.

  • B (float) – Buoyancy in kg.

  • theta (float) – Pitch angle in radians.

  • phi (float) – Roll angle in radians.

  • r_bg (array_like, shape (3,)) – Position [x_g, y_g, z_g] of CG relative to CO (meters).

  • r_bb (array_like, shape (3,)) – Position [x_b, y_b, z_b] of CB relative to CO (meters).

Returns:

g (ndarray, shape (6,)) – Restoring force vector [X, Y, Z, K, M, N] about CO.

Return type:

ndarray[Any, dtype[float64]]

Notes

  • Accounts for weight, buoyancy, and moment arms.

  • Neutral buoyancy: W = B -> only moment terms nonzero.

  • Apply as: M d/dt nu + C(nu)nu + D(nu)nu + g(eta) = tau.

munetauvsim.gnc.saturation(value, limit, maxLimit=None)[source]

Clamp value to specified interval.

Parameters:
  • value (float) – Value to limit.

  • limit (float) – Lower limit if maxLimit provided, else absolute limit for symmetric interval.

  • maxLimit (float, optional) – Upper limit. If None, uses symmetric interval [-limit, +limit].

Returns:

clamped (float) – Value restricted to [limit, maxLimit] or [-limit, +limit].

Return type:

float

Examples

>>> saturation(5.0, 2.0)         # interval [-2, 2]
2.0
>>> saturation(5.0, 0.0, 10.0)   # interval [0, 10]
5.0
>>> saturation(-5.0, -3.0, 3.0)  # interval [-3, 3]
-3.0