A differentiable 6-DOF underwater vehicle dynamics, with tooling for system identification, estimation, and control.
The core library provides symbolic kinematics and dynamics derived from Fossen's formulations. All major terms are represented as CasADi expressions, enabling analytic derivatives (gradients, Jacobians, Hessians) for optimization, estimation, and control workflows.
- Low-speed regime: less than 2 m/s, lift forces neglected.
- Symmetry: port-starboard and fore-aft symmetry; CG in symmetry planes.
- Hydrodynamic decoupling: symmetric 6-DOF motions treated independently.
- Below wave zone: wave disturbances are negligible.
- Symbolic kinematics and dynamics (body, NED, quaternion).
- Forward and inverse dynamics.
- Added mass, damping, Coriolis/centripetal, and restoring force models.
- System identification utilities (CVXPY-based estimator).
- EKF and nonlinear PID helpers.
- CasADi code generation for C++/MATLAB/Python.
- Gymnasium environment and RL training script.
- JIT support.
from diffUV import dyn_body, dyned_eul, kin
uv_dyn = dyn_body()
uv_dyned = dyned_eul()
inertia_mat = uv_dyn.body_inertia_matrix()
coriolis_mat = uv_dyn.body_coriolis_centripetal_matrix()
restoring_vec = uv_dyn.body_restoring_vector()
dampn_mat = uv_dyn.body_damping_matrix()
v_dot = uv_dyn.body_forward_dynamics()from casadi import jacobian
accel_jacobian = jacobian(v_dot, uv_dyn.body_state_vector)import os
from casadi import Function
from diffUV.utils.symbols import *
I_o = vertcat(I_x, I_y, I_z, I_xz) # rigid body inertia wrt body origin
decoupled_added_m = vertcat(X_du, Y_dv, Z_dw, K_dp, M_dq, N_dr) # added mass in diagonals
coupled_added_m = vertcat(X_dq, Y_dp, N_dp, M_du, K_dv) # effective added mass in non diagonals
M_func = Function('M_b', [m, I_o, z_g, decoupled_added_m, coupled_added_m], [inertia_mat])
M_func.generate("M_b.c")
os.system("gcc -fPIC -shared M_b.c -o libM_b.so")The core implementation is in diffUV/system_id.py (MarineVehicleEstimator).
The estimator formulates a convex fit in CVXPY with physical constraints; MOSEK is
used by default, but can be replaced in the solver call.
The identification notebook expects a single CSV with the following columns:
timestampimu_roll_unwrap,imu_pitch_unwrap,imu_yaw_unwrapimu_ang_vel_x,imu_ang_vel_y,imu_ang_vel_zdvl_speed_x,dvl_speed_y,dvl_speed_zdepth_from_pressure2base_x_force,base_y_force,base_z_forcebase_x_torque,base_y_torque,base_z_torque
Fossen, T.I. (2011) Handbook of Marine Craft Hydrodynamics and Motion Control. John Wiley & Sons, Inc., Chichester, UK. https://doi.org/10.1002/9781119994138

