proteus.mbd.CouplingFSI module

Coupling between Chrono and Proteus is done in this file.

Objects (classes) starting with ‘ProtCh’ (e.g. ProtChBody) are objects that have logic specifically developed for communication between Proteus and Chrono.

Objects starting with ‘Ch’ (e.g. ChBody) are objects that only have Chrono logic associated to them.

Some ProtCh objects give access to the Chrono object: my_protchsystem = ProtChSystem() my_protchbody = ProtChBody(system=my_protchsystem) my_chbody = my_protchbody.ChBody my_chbody.SetPos(…) my_chbody.SetRot(…)

# pass the index of the boundaries (or particle index) where forces must be integrated my_protchbody.setIndexBoundary([0, 1, 2, 3]) # alternatively, if you use a Shape instance from proteus.SpatialTools # the boundaries indice will be set automatically after calling SpatialTools.assembleDomain() my_protchbody.setShape(my_shape)

class proteus.mbd.CouplingFSI.ProtChSystem[source]

Bases: object

ChSystem[source]

object

Type

ChSystem

ChSystemSMC[source]

object

Type

ChSystemSMC

ProtChAddedMass[source]

mbd.CouplingFSI.ProtChAddedMass

Type

ProtChAddedMass

addProtChBody(self, ProtChBody body)[source]
addProtChMesh(self, ProtChMesh mesh)[source]
addSubcomponent(self, subcomponent)[source]

Adds subcomponent to system calculate_init() of subcomponent called before initial timestep prestep() and poststep of subcomponent() called at all timestep

Parameters

subcomponent (class instance) – class instance of subcomponent

attachAuxiliaryVariables(self, avDict)[source]
attachModel(self, model, ar)[source]

Attaches Proteus model to auxiliary variable

build_kdtree[source]

‘bool’

Type

build_kdtree

calculate(self, proteus_dt=None)[source]

Does chrono system calculation for a Proteus time step Calls prestep and poststep on all subcomponents (bodies, moorings, etc) attached to the system.

Parameters

proteus_dt (Optional[proteus_dt]) – Manually sets a time step. The time step is set automatically when coupled with a Proteus simulation

calculate_init(self)[source]

Does chrono system initialisation (!) Must be called before the first calculate() call. Calls calculate_init and poststep on all subcomponents (bodies, moorings, etc) attached to the system.

chrono_dt[source]

‘double’

Type

chrono_dt

‘bool’

Type

dist_search

dt_fluid[source]

‘double’

Type

dt_fluid

dt_fluid_last[source]

‘double’

Type

dt_fluid_last

dt_init[source]

‘double’

Type

dt_init

findElementContainingCoordsDist(self, coords, node_guess, eN_guess, rank_guess)[source]

Distance search of nearest node, element containing coords, and owning rank.

Parameters
  • coords (array_like) – global coordinates to look for

  • node_guess (int) – first guess of closest node

  • eN_guess (int) – first guess of element containing coords

  • rank_guess (int) – first guess of rank containing coords

Returns

  • xi – local coordinates

  • node (int) – nearest node

  • eN (int) – (local) element number

  • rank (int) – processor rank containing element

findElementContainingCoordsKD(self, coords)[source]

k-d tree search of nearest node, element containing coords, and owning rank.

Parameters

coords (array_like) – global coordinates to look for

Returns

  • xi – local coordinates

  • node (int) – nearest node

  • eN (int) – (local) element number

  • rank (int) – processor rank containing element

first_step[source]

‘bool’

Type

first_step

getChronoObject(self)[source]
getFluidVelocityGradientLocalCoords(self, xi, element, rank)[source]
getFluidVelocityLocalCoords(self, xi, element, rank)[source]
Parameters
  • xi – local coords in element

  • element (int) – element number (local to processor ‘rank’)

  • rank (int) – rank of processor owning the element

getGravitationalAcceleration(self)[source]
initialized[source]

‘bool’

Type

initialized

log_bodies_h5(self, l_logging_info)[source]

Logs the chrono information into a h5 file at each timestep :param self: ProtChSystem being referenced :type self: object :param l_logging_info: Contains the information to be logged. Structure is [body number, type]

with multiple entries being included as a 2d list. Valid types are ‘position’, ‘rotation’, ‘force’, and ‘torque’.

Return type

None. Data is saved to an h5 file.

log_bodies_text(self, d_time, l_logging_info)[source]
Logs the chrono information into a text file at each timestep

Parameters

self: object

ProtChSystem being referenced

d_time: float

Simulation time

l_logging_info: list

Contains the information to be logged. Structure is [body number, type] with multiple entries being included as a 2d list. Valid types are ‘position’, ‘rotation’, ‘force’, and ‘torque’.

Return type

None. Data is logged to a text file

log_chrono_bodies[source]

object

Type

log_chrono_bodies

log_chrono_format[source]

‘string’

Type

log_chrono_format

log_chrono_residuals[source]

object

Type

log_chrono_residuals

log_chrono_springs[source]

object

Type

log_chrono_springs

log_residuals_h5(self, l_linklocks)[source]

Logs chrono spring information to an h5 file :param self: ProtChSystem object being referenced. :type self: object :param l_linklocks: Link lock objects for which the residual information is desired. :type l_linklocks: list

Return type

None. Data is logged to an h5 file.

log_residuals_text(self, d_time, l_linklocks)[source]

Logs the chrono information into a text file at each timestep :param self: ProtChSystem being referenced :type self: object :param d_time: Current simulation time :type d_time: float :param l_linklocks: Link lock objects for which the residual information is desired. :type l_linklocks: list

Return type

None. Data is saved to a text file.

log_springs_h5(self, l_springs)[source]

Logs chrono spring information to an h5 file :param self: ProtChSystem object being referenced. :type self: object :param l_springs: Spring objects for which the data is being logged :type l_springs: list

Return type

None. Data is logged to an h5 file.

log_springs_text(self, d_time, l_springs)[source]

Logs the chrono information into a text file at each timestep :param self: ProtChSystem being referenced :type self: object :param d_time: Current simulation time :type d_time: float :param l_springs: Spring objects for which data is being stored :type l_springs: list

Return type

None. Data is saved to a text file.

log_times_h5(self, d_time)[source]

Creates a log of the Proteus timestep within the h5 log file :param self: ProtChSystem being referenced :type self: object :param d_time: Time within the simulation :type d_time: float

Return type

None. Data is logged to the disk.

model[source]

object

Type

model

model_addedmass[source]

object

Type

model_addedmass

model_mesh[source]

object

Type

model_mesh

model_module[source]

object

Type

model_module

nBodiesIBM[source]

‘int’

Type

nBodiesIBM

next_sample[source]

‘double’

Type

next_sample

prediction[source]

‘string’

Type

prediction

record_values[source]

‘bool’

Type

record_values

sampleRate[source]

‘double’

Type

sampleRate

scheme[source]

‘string’

Type

scheme

setCollisionEnvelopeMargin(self, double envelope, double margin)[source]
setCouplingScheme(self, string scheme, string prediction='backwardEuler')[source]
setGravitationalAcceleration(self, g)[source]
setMinimumSubsteps(self, int nb)[source]

Sets the minimum nb of chrono substeps per proteus step if prot_dt=0.001 and ch_dt=0.002, there will be <nb> substeps of chrono instead of just 1.

Parameters

nb (int) – Minimum number of chrono substeps.

setSampleRate(self, sampleRate)[source]
setTimeStep(self, double dt)[source]

Sets time step for Chrono solver. Calculations in Chrono will use this time step within the Proteus time step (if bigger) :param dt: Chrono time step size :type dt: float

setTimestepperType(self, string tstype, bool verbose=False)[source]

Change timestepper (default: Euler)

Parameters

tstype (str) – type of timestepper (‘Euler’ or ‘HHT’)

step(self, dt)[source]
step_nb[source]

‘int’

Type

step_nb

step_start[source]

‘int’

Type

step_start

subcomponents[source]

object

Type

subcomponents

tCount[source]

‘int’

Type

tCount

update_substeps[source]

‘bool’

Type

update_substeps

class proteus.mbd.CouplingFSI.ProtChBody[source]

Bases: object

Aij[source]

numpy.ndarray

Type

Aij

Aij_factor[source]

‘double’

Type

Aij_factor

Aij_transform_local[source]

‘bool’

Type

Aij_transform_local

Aij_updated_global[source]

‘bool’

Type

Aij_updated_global

ChBody[source]

object

Type

ChBody

ChBodyAddedMass[source]

mbd.CouplingFSI.ChBodyAddedMass

Type

ChBodyAddedMass

F[source]

numpy.ndarray

Type

F

F_Aij[source]

numpy.ndarray

Type

F_Aij

F_Aij_last[source]

numpy.ndarray

Type

F_Aij_last

F_applied[source]

numpy.ndarray

Type

F_applied

F_applied_last[source]

numpy.ndarray

Type

F_applied_last

F_last[source]

numpy.ndarray

Type

F_last

F_prot[source]

numpy.ndarray

Type

F_prot

F_prot_last[source]

numpy.ndarray

Type

F_prot_last

M[source]

numpy.ndarray

Type

M

M_Aij[source]

numpy.ndarray

Type

M_Aij

M_Aij_last[source]

numpy.ndarray

Type

M_Aij_last

M_applied[source]

numpy.ndarray

Type

M_applied

M_applied_last[source]

numpy.ndarray

Type

M_applied_last

M_last[source]

numpy.ndarray

Type

M_last

M_prot[source]

numpy.ndarray

Type

M_prot

M_prot_last[source]

numpy.ndarray

Type

M_prot_last

ProtChSystem[source]

mbd.CouplingFSI.ProtChSystem

Type

ProtChSystem

Shape[source]

object

Type

Shape

acceleration[source]

numpy.ndarray

Type

acceleration

acceleration_last[source]

numpy.ndarray

Type

acceleration_last

adams_vel[source]

numpy.ndarray

Type

adams_vel

addPrismaticLinkX(self, double[:] pris1)[source]
addPrismaticLinksWithSpring(self, ndarray pris1, ndarray pris2, double stiffness, double damping, double rest_length)[source]

fairlead: barycenter coords pris: absolute coords pris1——-fairlead(barycenter) | | | | pris2

addSpring(self, double stiffness, double damping, ndarray fairlead, ndarray anchor, double rest_length)[source]
addTriangleMeshFromShape(self, shape=None, double[:] pos=None, double[:, :] rot=None, bool is_static=False, bool is_convex=False, double sphereswept_thickness=0.005)[source]

Adds triangle mesh to collision model and for IBM calculations

ang_acceleration[source]

numpy.ndarray

Type

ang_acceleration

ang_acceleration_last[source]

numpy.ndarray

Type

ang_acceleration_last

ang_vel_norm[source]

‘double’

Type

ang_vel_norm

ang_vel_norm_last[source]

‘double’

Type

ang_vel_norm_last

ang_velocity[source]

numpy.ndarray

Type

ang_velocity

ang_velocity_last[source]

numpy.ndarray

Type

ang_velocity_last

applyAddedMass[source]

‘bool’

Type

applyAddedMass

attachAuxiliaryVariables(self, avDict)[source]
attachShape(self, shape, take_shape_name=True)[source]

Attach proteus.SpatialTools shape to body. Used for automatic calculation of external forces from Proteus. Called automatically when creating a body and passing a shape instance.

Parameters

shape (SpatialTools.Shape) – instance of shape from proteus.SpatialTools or proteus.mprans.SpatialTools

barycenter0[source]

numpy.ndarray

Type

barycenter0

boundaryFlags[source]

numpy.ndarray

Type

boundaryFlags

calculate(self)[source]
calculate_init(self)[source]

Called from self.ProtChSystem.calculate_init() before simulation starts

dt[source]

‘double’

Type

dt

dt_predict[source]

‘double’

Type

dt_predict

getChronoObject(self)[source]
getDynamicSDF(self, t, x)[source]
getInertia(self)[source]
getMass(self)[source]
getMoments(self)[source]

Gives moments from fluid (Proteus) acting on body (!) Only works during proteus simulation

Returns

M – moments (x, y, z) as provided by Proteus

Return type

array_like

getPosition(self)[source]
getPressureForces(self)[source]

Gives pressure forces from fluid (Proteus) acting on body. (!) Only works during proteus simulation

Returns

F_p – pressure forces (x, y, z) as provided by Proteus

Return type

array_like

getRotationMatrix(self)[source]

Gives current rotation (matrix) of body

Returns

rot – current rotation (matrix) of body

Return type

array_like

getShearForces(self)[source]

Gives shear forces from fluid (Proteus) acting on body (!) Only works during proteus simulation

Returns

F_v – shear forces (x, y, z) as provided by Proteus

Return type

array_like

getTriangleMeshInfo(self)[source]
getValues(self)[source]

Get values (pos, vel, acc, etc.) from C++ to python

getVelocity(self)[source]
h_ang_predict[source]

‘double’

Type

h_ang_predict

h_ang_predict_last[source]

‘double’

Type

h_ang_predict_last

h_ang_vel_predict[source]

numpy.ndarray

Type

h_ang_vel_predict

h_ang_vel_predict_last[source]

numpy.ndarray

Type

h_ang_vel_predict_last

h_predict[source]

numpy.ndarray

Type

h_predict

h_predict_last[source]

numpy.ndarray

Type

h_predict_last

hdfFileName[source]

‘string’

Type

hdfFileName

hx(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (x component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hx_rotation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (x component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hx_translation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (x component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hxyz(self, ndarray x, double t, debug=False)[source]
hy(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (y component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hy_rotation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (y component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hy_translation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (y component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hz(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (z component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hz_rotation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (z component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

hz_translation(self, ndarray x, double t)[source]

BC function for mesh nodes displacement (z component)

Parameters
  • x (array_like) – coordinates of the node before displacement

  • t (double) – simulation time

model[source]

object

Type

model

name[source]

‘string’

Type

name

nd[source]

‘int’

Type

nd

position[source]

numpy.ndarray

Type

position

position_last[source]

numpy.ndarray

Type

position_last

poststep(self)[source]

Called after Chrono system step. Records values to csv, broadcast new position and rotation from calculating processor to all processors for moving mesh BC.

predicted[source]

‘bool’

Type

predicted

prediction(self)[source]
prescribed_motion_function[source]

object

Type

prescribed_motion_function

prestep(self)[source]

Called before Chrono system step. Sets external forces automatically from Proteus solution.

radiusIBM[source]

‘double’

Type

radiusIBM

record_dict[source]

object

Type

record_dict

record_file[source]

str

Type

record_file

rotation_init[source]

numpy.ndarray

Type

rotation_init

rotm[source]

numpy.ndarray

Type

rotm

rotm_last[source]

numpy.ndarray

Type

rotm_last

rotq[source]

numpy.ndarray

Type

rotq

rotq_last[source]

numpy.ndarray

Type

rotq_last

sdfIBM[source]

object

Type

sdfIBM

setAddedMass(self, ndarray Aij)[source]

Sets the added mass matrix of the body

Parameters

added_mass (array_like) – Added mass matrix (must be 6x6 array!)

setBoundaryFlags(self, flags)[source]

Sets the flags of the boundaries of the body numbers must be gloabal (from domain.segmentFlags or domain.facetFlags).

Parameters

flags (array_like) – list of flags that belong to this body

setCollisionOptions(self, double envelope=0.001, double margin=0.0005, bool collide=True)[source]
setConstraints(self, ndarray free_x, ndarray free_r)[source]

Sets constraints on the body (!) Only acts on Proteus and gravity forces

Parameters
  • free_x (array_like) – Translational constraints.

  • free_r (array_like) – Rotational constraints.

setExternalForces(self, ndarray forces=None, ndarray moments=None)[source]

Sets external forces to body. Called during prestep or can be called manually. If called manually, must be a Chrono only simulation.

Parameters
  • forces (array_like) – forces array (length 3)

  • moments (array_like) – moments array (length 3)

setIBM(self, useIBM=True, radiusIBM=0., sdfIBM=None)[source]

Sets IBM mode for retrieving fluid forces

Parameters
  • useIBM (bool) – set if IBM should be used

  • radiusIBM (double) – radius of the particle for IBM

  • radiusIBM – sdf relative to barycentre of body for IBM

setInertiaXX(self, ndarray inertia)[source]
setInertiaXY(self, ndarray inertia)[source]
setInitialRot(self, rot)[source]
setMass(self, double mass)[source]
setName(self, string name)[source]

Sets name of body (used for csv file)

Parameters

name (str) – name of the body

setPosition(self, ndarray pos)[source]
setPrescribedMotion(self, function)[source]

Sets custom prescribed motion function (!) should be preferably set only if body is free and not linked to other bodies or other elements (such as moorings) as this is used only for setting moving mesh BC by enforcing position of the body at each time step. Use setPrescribedMotionPoly or setPrescribedMotionSine for functions that are safe to use with a body linked with other elements.

Parameters

function – must be a function of time returning an array of the absolute position of the body (numpy array of length 3: x, y, z)

setPrescribedMotionCustom(self, double[:] t, double[:] x=None, double[:] y=None, double[:] z=None, double[:] ang=None, double[:] ang2=None, double[:] ang3=None, double t_max=0)[source]

Sets custom prescribed motion for body. Parameters must have the same length as the time array t

Parameters
  • t (array_like) – time array

  • x (array_like) – x coordinates of body

  • y (array_like) – y coordinates of body

  • z (array_like) – z coordinates of body

  • ang (array_like) – rotation of body

  • ang2 (array_like) – rotation of body

  • ang3 (array_like) – rotation coordinates of body

  • t_max (double) – prescribed motion is released when t > t_max. if t_max=0, the prescribed motion is never released.

setPrescribedMotionPoly(self, double coeff1)[source]

Sets polynomial prescribed motion for body

Parameters

coeff1 (double) – coeff1 of polynomial

setPrescribedMotionSine(self, double a, double f)[source]

Sets sinusoidal prescribed motion for body

Parameters
  • a (double) – amplitude of sinusoid

  • f (double) – frequency of sinusoid

setRecordValues(self, all_values=False, pos=False, rot=False, ang_disp=False, F=False, M=False, inertia=False, vel=False, acc=False, ang_vel=False, ang_acc=False, h_predict=False)[source]

Sets the body attributes that are to be recorded in a csv file during the simulation.

Parameters
  • all_values (bool) – Set to True to record all values listed below.

  • time (bool) – Time of recorded row (default: True).

  • pos (bool) – Position of body (default: False. Set to True to record).

  • rot (bool) – Rotation of body (default: False. Set to True to record).

  • ang_disp (array) – Angular displecement calculated during rigid body calculation step. Applied on the body in order to make it rotating.

  • F (bool) – Forces applied on body (default: False. Set to True to record).

  • M (bool) – Moments applied on body (default: False. Set to True to record).

  • inertia (bool) – Inertia of body (default: False. Set to True to record).

  • vel (bool) – Velocity of body (default: False. Set to True to record).

  • acc (bool) – Acceleration of body (default: False. Set to True to record).

  • ang_vel (array) – Angular velocity of body (default: False. Set to True to record).

  • ang_acc (bool) – Angular acceleration of body (default: False. Set to True to record).

Notes

To add another value manually, add to dictionary self.record_dict: key: header of the column in .csv value: list of length 2: [variable name, index within variable]

(if no index, use None)

e.g. self.record_dict[‘m’][‘mass’, None]

setVelocity(self, ndarray vel)[source]
setWidth2D(self, width)[source]

Sets width of 2D body (for forces and moments calculation)

Parameters

width (float) – width of the body

storeValues(self)[source]
updateIBM(self)[source]
useIBM[source]

‘bool’

Type

useIBM

velocity[source]

numpy.ndarray

Type

velocity

velocity_last[source]

numpy.ndarray

Type

velocity_last

width_2D[source]

‘double’

Type

width_2D

class proteus.mbd.CouplingFSI.ProtChMesh[source]

Bases: object

ChMeshh[source]

object

Type

ChMeshh

ProtChSystem[source]

mbd.CouplingFSI.ProtChSystem

Type

ProtChSystem

getChronoObject(self)[source]
class proteus.mbd.CouplingFSI.ProtChMoorings[source]

Bases: object

Class for building mooring cables

Parameters
  • system (System) – Class instance of the system.

  • mesh (Mesh) – Class instance of the mesh.

  • length (np.ndarray) – Length of cable segments. Must be an array, if the cable only has one type of segment (e.g. only one type of chain), an array of length 1 can be passed.

  • nb_elems (np.ndarray) – Number of elements per segments.

  • d (np.ndarray) – Diameter of segments.

  • rho (np.ndarray) – Density of segments.

  • E (np.ndarray) – Young’s modulus of segments.

  • beam_type (str) – Type of elements (default: “CableANCF”).

Mesh[source]

object

Type

Mesh

ProtChSystem[source]

mbd.CouplingFSI.ProtChSystem

Type

ProtChSystem

attachBackNodeToBody(self, ProtChBody body)[source]

Attaches back node to a body with ChLinkLockLock

Parameters

body (ProtChBody) – body to which the node will be attached

attachFrontNodeToBody(self, ProtChBody body)[source]

Attaches front node to a body with ChLinkLockLock

Parameters

body (ProtChBody) – body to which the node will be attached

back_body[source]

‘bool’

Type

back_body

beam_type[source]

‘string’

Type

beam_type

body_back[source]

mbd.CouplingFSI.ProtChBody

Type

body_back

body_front[source]

mbd.CouplingFSI.ProtChBody

Type

body_front

buildNodes(self)[source]
calculate_init(self)[source]
containing_element_array[source]

]’

Type

containing_element_array

Type

‘int[

elements[source]

object

Type

elements

external_forces_from_ns[source]

‘bool’

Type

external_forces_from_ns

external_forces_manual[source]

‘bool’

Type

external_forces_manual

fixBackNode(self, bool fixed)[source]

Fix back node of cable

Parameters

fixed (bool) – Fixes node if True

fixFrontNode(self, bool fixed)[source]

Fix front node of cable

Parameters

fixed (bool) – Fixes node if True

fluid_acceleration_array[source]

numpy.ndarray

Type

fluid_acceleration_array

fluid_density_array[source]

numpy.ndarray

Type

fluid_density_array

fluid_velocity_array[source]

numpy.ndarray

Type

fluid_velocity_array

fluid_velocity_array_previous[source]

numpy.ndarray

Type

fluid_velocity_array_previous

fluid_velocity_function[source]

object

Type

fluid_velocity_function

front_body[source]

‘bool’

Type

front_body

getAddedMassForces(self)[source]
getDragForces(self)[source]
getNodesAcceleration(self)[source]

Gives array of nodes acceleration

Returns

pos – Array of nodes acceleration.

Return type

np.ndarray

getNodesD(self)[source]

Gives direction of nodes

Returns

dire – Array of nodes direction.

Return type

np.ndarray

getNodesPosition(self)[source]

Gives array of nodes position

Returns

pos – Array of nodes position.

Return type

np.ndarray

getNodesTension(self, eta=0.)[source]
getNodesVelocity(self)[source]

Gives array of nodes velocity

Returns

pos – Array of nodes velocity.

Return type

np.ndarray

getTensionBack(self)[source]

Get Tension at the back of the cable

getTensionElement(self, int i=0, eta=0.)[source]
getTensionFront(self)[source]

Get Tension at the front of the cable

hdfFileName[source]

‘string’

Type

hdfFileName

initialized[source]

‘bool’

Type

initialized

model[source]

object

Type

model

name[source]

‘string’

Type

name

nb_elems[source]

numpy.ndarray

Type

nb_elems

nd[source]

‘int’

Type

nd

nearest_node_array[source]

]’

Type

nearest_node_array

Type

‘int[

nodes[source]

object

Type

nodes

nodes_built[source]

‘bool’

Type

nodes_built

nodes_function[source]

object

Type

nodes_function

nodes_function_tangent[source]

object

Type

nodes_function_tangent

nodes_nb[source]

‘int’

Type

nodes_nb

owning_rank[source]

]’

Type

owning_rank

Type

‘int[

poststep(self)[source]

Records values

prestep(self)[source]

Sets external forces on the cable (if any)

recordStrainEta(self, double[:] etas)[source]
record_file[source]

str

Type

record_file

setAddedMassCoefficients(self, double tangential, double normal, int segment_nb)[source]

Sets added mass coefficients of cable

Parameters
  • tangential (double) – Tangential added mass coefficient.

  • normal (double) – Normal added mass coefficient.

  • segment_nb (int) – Segment number to which these coefficients apply.

setApplyAddedMass(self, bool boolval)[source]
setApplyBuoyancy(self, bool boolval)[source]
setApplyDrag(self, bool boolval)[source]
setContactMaterial(self, mat)[source]

Sets contact material of the cable

Parameters

mat (ChMaterialSurfaceSMC) – Material of cable.

setDragCoefficients(self, double tangential, double normal, int segment_nb)[source]

Sets drag coefficients of cable

Parameters
  • tangential (double) – Tangential drag coefficient.

  • normal (double) – Normal drag coefficient.

  • segment_nb (int) – Segment number to which these coefficients apply.

setExternalForces(self, fluid_velocity_array=None, fluid_density_array=None, fluid_acceleration_array=None)[source]

Sets external forces acting on cables Pass fluid velocity_array as argument only for debugging (must be an array as long as the number of nodes)

setFluidAccelerationAtNodes(self, ndarray acceleration_array)[source]
setFluidDensityAtNodes(self, ndarray density_array)[source]
setFluidVelocityAtNodes(self, ndarray velocity_array)[source]
setFluidVelocityFunction(self, function)[source]

Function to build nodes

Parameters

function – Must be a function taking two arguments (3D coordinates and time), and returning velocity (x, y, z).

setIyy(self, double Iyy, int cable_nb)[source]
setName(self, string name)[source]

Sets name of cable, used for csv file

Parameters

name (str) – Name of cable.

setNodesPosition(self, double[:, :, :] positions=None, tangents=None)[source]

Builds the nodes of the cable.

(!) Must be called after setNodesPositionFunction()

setNodesPositionFunction(self, function_position, function_tangent=None)[source]

Function to build nodes

Parameters
  • function_position (Optional) – Must be a function taking one argument (e.g. distance along cable) and returning 3 arguments (x, y, z) coords.

  • function_position – Must be a function taking one argument (e.g. distance along cable) and returning 3 arguments (x, y, z) tangents at coords.

setRestLengthPerElement(self, double[:] length_array, int segment_nb)[source]

Sets rest length per element of cable

Parameters
  • length_array (array_like[double]) – Rest length of each element of cable.

  • segment_nb (int) – Segment number to which these rest lengths apply.

tCount[source]

‘int’

Type

tCount

tCount_value[source]

]’

Type

tCount_value

Type

‘double[

updateForces(self)[source]
class proteus.mbd.CouplingFSI.ProtChAddedMass[source]

Bases: object

Class (hack) to attach added mass model to ProtChSystem This auxiliary variable is ONLY used to attach the AddedMass model to a ProtChSystem

ProtChSystem[source]

mbd.CouplingFSI.ProtChSystem

Type

ProtChSystem

attachAuxiliaryVariables(self, avDict)[source]
attachModel(self, model, ar)[source]

Attaches Proteus model to auxiliary variable

calculate(self)[source]
calculate_init(self)[source]
model[source]

object

Type

model