Dynamics

Used for attaching Fossen Dynamics to Holocean Conversion between the two coordinate systems

Classes:

FossenDynamics(vehicle, sample_period[, ...])

Class for handling the connection between a holocean agent and the fossen dynamic model to control the motion of the vehicle

class holoocean.dynamics.FossenDynamics(vehicle, sample_period, initial_u_actual=None)

Class for handling the connection between a holocean agent and the fossen dynamic model to control the motion of the vehicle

Methods:

R2euler(R)

Computes the Euler angles from the rotation matrix R.

convert_NED_to_NWU(x, accel)

Calculates rotation to world frame and changes the coordinate system from NED to NWU Rotates linear and angular accelaration from body to world

convert_NWU_to_NED(x)

Converts position and velocity from NWU to NED and world frame velocities to body frame

set_u_control_rad(u_control)

Set the control surface commands for the vehicle control surfaces with angles in radians

update(state)

Update state of the vehicle to return the acceleartion of the vehicle in holoocean world frame

R2euler(R)

Computes the Euler angles from the rotation matrix R.

Parameters:

R (numpy.ndarray) – 3x3 rotation matrix

Returns:

Euler angles (in radians)

Return type:

phi, theta, psi (float)

convert_NED_to_NWU(x, accel)

Calculates rotation to world frame and changes the coordinate system from NED to NWU Rotates linear and angular accelaration from body to world

Parameters:
  • x – Holoocean Dynamic Sensor return of position (with quaternion), velocity, and acceleration (len = 19)

  • accel (np.ndarray) –

Returns:

[accelx, accely, accelz, pdot, qdot, rdot] - World frame in NWU

Return type:

accel (np.ndarray - float)

convert_NWU_to_NED(x)

Converts position and velocity from NWU to NED and world frame velocities to body frame

Parameters:

x – Holoocean Dynamic Sensor return of position (with quaternion), velocity, and acceleration (len = 19)

Returns:

[x, y, z, roll, pitch, yaw], [xdot, ydot, zdot, p, q, r]

Return type:

eta, nu (np.ndarray - float)

set_u_control_rad(u_control)

Set the control surface commands for the vehicle control surfaces with angles in radians

update(state)

Update state of the vehicle to return the acceleartion of the vehicle in holoocean world frame

Torpedo Dynamics

Classes:

TAUV([scenario, vehicle_name, ...])

Parent class of the torpedo-shaped vehicle.

fourFinDep([scenario, vehicle_name, ...])

Torpedo Vehicle with four fins where two fins move together on same plane (Rudder, Stern)

fourFinInd([scenario, vehicle_name, ...])

Torpedo vehicle with four independetly controlled fins (Rudder Top, Rudder Bottom, Stern left, Stern Right)

threeFinInd([scenario, vehicle_name, ...])

Torpedo vehicle with four independetly controlled fins (Rudder Top, Rudder Bottom, Stern left, Stern Right)

class holoocean.vehicle_dynamics.torpedo.TAUV(scenario=None, vehicle_name=None, controlSystem='stepInput', r_z=0, r_psi=0, r_rpm=0, r_surge=0, V_current=0, beta_current=0)

Parent class of the torpedo-shaped vehicle. General parameters and calculations for all torpedo vehicles. Actuator parameters and calculations are implemented in subclasses.

Parameters:
  • scenario (dict) – scenario dictionary for holoocean

  • vehicle_name (str) – name of vehicle to initialize that matches agent in scenario dictionary

  • controlSystem (str) – autopilot method for controlling the actuators

  • r_z (float) – desired depth (m), positive downwards

  • r_psi (float) – desired yaw angle (deg)

  • r_rpm (float) – desired propeller revolution (rpm)

  • r_rpm – desired surge speed (m/s)

  • V_current (float) – current speed (m/s)

  • beta_current (float) – current direction (deg)

Methods:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

calculate_additional_parameters()

After updating the vehicle parameters calculations will be run to update other variables related to these parameters

configure_from_scenario(scenario, vehicle_name)

Dynamics Parameters:

depthHeadingAutopilot(eta, nu, sampleTime[, imu])

Simultaneously control the heading and depth of the AUV using control laws of PID type.

dynamics(eta, nu, u_actual, u_control, ...)

Integrates the AUV equations of motion using Euler's method.

set_actuator_parameters(actuator_parameters)

Set fin area limits, time constants, and lift coefficients for control surfaces

set_autopilot_parameters(autopilot)

Set depth and heading parameters from a configuration dictionary.

set_control_mode(controlSystem[, init_depth])

Sets the control mode for the vehicle.

set_depth_goal(depth)

Set the depth goals for the autopilot.

set_goal([depth, heading, rpm, surge])

Set the goals for the autopilot.

set_heading_goal(heading)

Set the heading goals for the autopilot.

set_rpm_goal(rpm)

Set the rpm goals for the autopilot.

set_surge_goal(surge)

Set the surge goals for the autopilot.

set_vehicle_parameters(dynamics)

Set vehicle dynamics parameters.

stepInput(t)

Generates step inputs.

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

Note: For Torpedo Vehicles, positive fin deflection will pitch the vehicle up and yaw to the starboard side.

Parameters:
  • u_actual (array-like) – Current control surface position.

  • nu_r (array-like) – Reference velocity of the vehicle in the body frame.

Returns:

two arrays: forces and moments

calculate_additional_parameters()

After updating the vehicle parameters calculations will be run to update other variables related to these parameters

configure_from_scenario(scenario, vehicle_name)

Dynamics Parameters:

Parameters:
  • mass (float) – Mass of vehicle in kilograms

  • length (float) – length of vehicle in meters

  • rho (float) – density of water in kg/m^3

  • diam (float) – diameter of vehicle in m

  • r_bg (float) – Center of gravity of the vehicle (x, y, z) in body frame x forward, y right, z down

  • r_bb (float) – Center of boyancy of the vehicle (x, y, z) in body frame x forward, y right, z down

  • r44 (float) –

  • Cd (float) – Coefficient of drag

  • T_surge (float) –

  • T_sway (float) –

  • T_yaw (float) –

  • zeta_roll (float) –

  • zeta_ptich (float) –

  • K_nomoto (float) –

Autopilot Paramters:

  • Depth

Parameters:
  • wn_d_z (float) – damped natural frequency for low pass filter for depth commands

  • Kp_z (float) – Portional gain for depth controller

  • T_z (float) –

  • Kp_theta (float) – Porportional gain for pitch angle for depth controller

  • Ki_theta (float) – Integral gain for pitch angle for depth controller

  • Kd_theta (float) – Derivative gain for pitch angle for depth controller

  • K_w (float) –

  • theta_max_deg (float) – Max output of pitch controller inner loop

  • Heading

Parameters:
  • wn_d (float) – Damped natural frequency of input commands for low pass filter

  • zeta_d – Damping coefficient

  • r_max

  • lam

  • phi_b

  • K_d

  • K_sigma

  • Surge

Parameters:
  • kp_surge – Porportional gain for surge

  • ki_surge – Integral gain for surge

  • kd_surge – Derivative gain for surge

Acutator Parameters:

Parameters:
  • fin_area – Surface area of one side of a fin

  • fin_center – Positive Z distance from center of mass to center of pressure

  • deltaMax_fin_deg – Max deflection of the fin (degrees)

  • nMax – Max rpm of the thruster

  • T_delta – Time constant for fin actuation. (s)

  • T_n – Time constant for thruster actuation. (s)

  • CL_delta_r – Coefficient of lift for rudder

  • CL_delta_r – Coefficient of lift for stern

depthHeadingAutopilot(eta, nu, sampleTime, imu=True)

Simultaneously control the heading and depth of the AUV using control laws of PID type. Propeller rpm is given as a step command.

Parameters:
  • eta (array-like) – State/pose of the vehicle in the world frame. (RPY - Euler angle order zyx in radians)

  • nu (array-like) – Velocity of the vehicle in the body frame.

  • sampleTime (float) – Time since the last step.

Returns:

The control input u_control.

dynamics(eta, nu, u_actual, u_control, sampleTime)

Integrates the AUV equations of motion using Euler’s method.

Parameters:
  • eta (array-like) – State/pose of the vehicle in the world frame.

  • nu (array-like) – Velocity of the vehicle in the body frame.

  • nu_dot (array-like) – Acceleration of the vehicle in the body frame.

  • u_actual (array-like) – Current control surface position.

  • u_control (array-like) – Commanded control surface position.

  • sampleTime (float) – Time since the last step.

Returns:

Three arrays: nu, u_actual, and nu_dot.

set_actuator_parameters(actuator_parameters)

Set fin area limits, time constants, and lift coefficients for control surfaces

set_autopilot_parameters(autopilot)

Set depth and heading parameters from a configuration dictionary.

Parameters:

cfg – Dictionary containing ‘depth’ and ‘heading’ sections with their respective parameters.

set_control_mode(controlSystem, init_depth=False)

Sets the control mode for the vehicle.

Parameters:

controlSystem (str) – The control system to use. Possible values are:

  • "depthHeadingAutopilot": Depth and heading autopilots.

  • "manualControl": Manual input control with set_u_control().

  • "stepInput": Step inputs for stern planes, rudder, and propeller

  • Any other value: controlSystem is set to “stepInput”.

Parameters:

init_depth (bool) – Whether to initialize depth (default is False).

Returns:

None

set_depth_goal(depth)

Set the depth goals for the autopilot.

Parameters:

depth (float) – Desired depth (m), positive downward in world frame.

Returns:

None

set_goal(depth=None, heading=None, rpm=None, surge=None)

Set the goals for the autopilot.

Parameters:
  • depth (float) – Desired depth (m), positive downwards.

  • heading (float) – Desired yaw angle (deg). (-180 to 180)

  • rpm (float) – Desired propeller revolution (rpm).

  • surge (float) – Desired body frame x velocity (m/s).

Returns:

None

set_heading_goal(heading)

Set the heading goals for the autopilot.

Parameters:

depth (float) – Desired heading (deg), -180 to 180 in NED frame

Returns:

None

set_rpm_goal(rpm)

Set the rpm goals for the autopilot.

Parameters:

depth (float) – Desired rpm for thruster

Returns:

None

set_surge_goal(surge)

Set the surge goals for the autopilot.

Parameters:

depth (float) – Desired surge (m/s), positive forward in body frame.

Returns:

None

set_vehicle_parameters(dynamics)

Set vehicle dynamics parameters. If not provided, will default to previous value

stepInput(t)

Generates step inputs.

Parameters:

t (float) – Time parameter.

Returns:

The control input u_control.

class holoocean.vehicle_dynamics.torpedo.fourFinDep(scenario=None, vehicle_name=None, controlSystem='stepInput', r_z=0, r_psi=0, r_rpm=0, V_current=0, beta_current=0)

Torpedo Vehicle with four fins where two fins move together on same plane (Rudder, Stern)

Methods:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

depthHeadingAutopilot(eta, nu, sampleTime[, imu])

returns:

The control input u_control as a list: [delta_r, delta_s, n], where:

stepInput(t)

returns:

The control input u_control as a list: [delta_r, delta_s, n], where:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

Note: For Torpedo Vehicles, positive fin deflection will pitch the vehicle up and yaw to the starboard side.

Parameters:
  • u_actual (array-like) – Current control surface position.

  • nu_r (array-like) – Reference velocity of the vehicle in the body frame.

Returns:

two arrays: forces and moments

depthHeadingAutopilot(eta, nu, sampleTime, imu=True)
Returns:

The control input u_control as a list: [delta_r, delta_s, n], where:

  • delta_r (float): Rudder angle (rad)

  • delta_s (float): Stern plane angle (rad)

  • n (float): Propeller revolution (rpm)

Return type:

list

stepInput(t)
Returns:

The control input u_control as a list: [delta_r, delta_s, n], where:

  • delta_r (float): Rudder angle (rad)

  • delta_s (float): Stern plane angle (rad)

  • n (float): Propeller revolution (rpm)

Return type:

list

class holoocean.vehicle_dynamics.torpedo.fourFinInd(scenario=None, vehicle_name=None, controlSystem='stepInput', r_z=0, r_psi=0, r_rpm=0, V_current=0, beta_current=0)

Torpedo vehicle with four independetly controlled fins (Rudder Top, Rudder Bottom, Stern left, Stern Right)

Methods:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

depthHeadingAutopilot(eta, nu, sampleTime[, imu])

returns:

The control input u_control as a list: [delta_rt, delta_rb, delta_sl, delta_sr, n], where:

stepInput(t)

returns:

The control input u_control as a list: [delta_rt, delta_rb, delta_sl, delta_sr, n], where:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

Note: For Torpedo Vehicles, positive fin deflection will pitch the vehicle up and yaw to the starboard side.

Parameters:
  • u_actual (array-like) – Current control surface position.

  • nu_r (array-like) – Reference velocity of the vehicle in the body frame.

Returns:

two arrays: forces and moments

depthHeadingAutopilot(eta, nu, sampleTime, imu=True)
Returns:

The control input u_control as a list: [delta_rt, delta_rb, delta_sl, delta_sr, n], where:

  • delta_rt: Rudder top angle (rad).

  • delta_rb: Rudder bottom angle (rad).

  • delta_sl: Stern left angle (rad).

  • delta_sr: Stern right angle (rad).

  • n: Propeller revolution (rpm).

Return type:

list

stepInput(t)
Returns:

The control input u_control as a list: [delta_rt, delta_rb, delta_sl, delta_sr, n], where:

  • delta_rt: Rudder top angle (rad).

  • delta_rb: Rudder bottom angle (rad).

  • delta_sl: Stern left angle (rad).

  • delta_sr: Stern right angle (rad).

  • n: Propeller revolution (rpm).

Return type:

list

class holoocean.vehicle_dynamics.torpedo.threeFinInd(scenario=None, vehicle_name=None, controlSystem='stepInput', r_z=0, r_psi=0, r_rpm=0, V_current=0, beta_current=0)

Torpedo vehicle with four independetly controlled fins (Rudder Top, Rudder Bottom, Stern left, Stern Right)

Methods:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

depthHeadingAutopilot(eta, nu, sampleTime[, imu])

returns:

[delta_r, delta_rb, delta_sl, delta_sr, n], where:

stepInput(t)

returns:

[delta_r, delta_rb, delta_sl, delta_sr, n], where:

actuator_dynamics(u_actual, nu_r)

Vehicle-specific calculations for dynamics of the actuators (fins and thruster).

Note: For Torpedo Vehicles, positive fin deflection will pitch the vehicle up and yaw to the starboard side.

Parameters:
  • u_actual (array-like) – Current control surface position.

  • nu_r (array-like) – Reference velocity of the vehicle in the body frame.

Returns:

two arrays: forces and moments

depthHeadingAutopilot(eta, nu, sampleTime, imu=True)
Returns:

[delta_r, delta_rb, delta_sl, delta_sr, n], where:

  • delta_r: Rudder top angle (rad).

  • delta_re: right elevator angle (rad).

  • delta_le: left elevator angle (rad).

  • n: Propeller revolution (rpm).

Return type:

list

stepInput(t)
Returns:

[delta_r, delta_rb, delta_sl, delta_sr, n], where:

  • delta_r: Rudder top angle (rad).

  • delta_re: right elevator angle (rad).

  • delta_le: left elevator angle (rad).

  • n: Propeller revolution (rpm).

Return type:

list