ObjectFFRFreducedOrder

This object is used to represent modally reduced flexible bodies using the FFRF and the CMS. It can be used to model real-life mechanical systems imported from finite element codes or Python tools such as NETGEN/NGsolve, see the FEMinterface in Section Class function: __init__. It contains a RigidBodyNode (always node 0) and a NodeGenericODE2 representing the modal coordinates. Currently, equations must be defined within user functions, which are available in the FEM module, see class ObjectFFRFreducedOrderInterface, especially the user functions UFmassFFRFreducedOrder and UFforceFFRFreducedOrder, Section Class function: AddObjectFFRFreducedOrderWithUserFunctions.

Authors: Gerstmayr Johannes, Zwölfer Andreas

Additional information for ObjectFFRFreducedOrder:

  • This Object has/provides the following types = Body, MultiNoded, SuperElement
  • Requested Node type: read detailed information of item
  • Short name for Python = CMSobject
  • Short name for Python visualization object = VCMSobject

The item ObjectFFRFreducedOrder with type = ‘FFRFreducedOrder’ has the following parameters:

  • name [type = String, default = ‘’]:
    objects’s unique name
  • nodeNumbers [\(\mathbf{n} = [n_0,\,n_1]\tp\), type = ArrayNodeIndex, default = []]:
    node numbers of rigid body node and NodeGenericODE2 for modal coordinates; the global nodal position needs to be reconstructed from the rigid-body motion of the reference frame, the modal coordinates and the mode basis
  • massMatrixReduced [\({\mathbf{M}}\indred \in \Rcal^{n_m \times n_m}\), type = PyMatrixContainer, default = PyMatrixContainer[]]:
    body-fixed and ONLY flexible coordinates part of reduced mass matrix; provided as MatrixContainer(sparse/dense matrix)
  • stiffnessMatrixReduced [\({\mathbf{K}}\indred \in \Rcal^{n_m \times n_m}\), type = PyMatrixContainer, default = PyMatrixContainer[]]:
    body-fixed and ONLY flexible coordinates part of reduced stiffness matrix; provided as MatrixContainer(sparse/dense matrix)
  • dampingMatrixReduced [\({\mathbf{D}}\indred \in \Rcal^{n_m \times n_m}\), type = PyMatrixContainer, default = PyMatrixContainer[]]:
    body-fixed and ONLY flexible coordinates part of reduced damping matrix; provided as MatrixContainer(sparse/dense matrix)
  • forceUserFunction [\({\mathbf{f}}\induser \in \Rcal^{n_{ODE2}}\), type = PyFunctionVectorMbsScalarIndex2Vector, default = 0]:
    A Python user function which computes the generalized user force vector for the ODE2 equations; see description below
  • massMatrixUserFunction [\({\mathbf{M}}\induser \in \Rcal^{n_{ODE2}\times n_{ODE2}}\), type = PyFunctionMatrixMbsScalarIndex2Vector, default = 0]:
    A Python user function which computes the TOTAL mass matrix (including reference node) and adds the local constant mass matrix; see description below
  • computeFFRFterms [type = Bool, default = True]:
    flag decides whether the standard FFRF/CMS terms are computed; use this flag for user-defined definition of FFRF terms in mass matrix and quadratic velocity vector
  • modeBasis [\(\LU{b}{\tPsi} \in \Rcal^{n\indf \times n_{m}}\), type = NumpyMatrix, default = Matrix[]]:
    mode basis, which transforms reduced coordinates to (full) nodal coordinates, written as a single vector \([u_{x,n_0},\,u_{y,n_0},\,u_{z,n_0},\,\ldots,\,u_{x,n_n},\,u_{y,n_n},\,u_{z,n_n}]\tp\)
  • outputVariableModeBasis [\(\LU{b}{\tPsi}_{OV} \in \Rcal^{n_n \times (n_{m}\cdot s_{OV})}\), type = NumpyMatrix, default = Matrix[]]:
    mode basis, which transforms reduced coordinates to output variables per mode and per node; \(s_{OV}\) is the size of the output variable, e.g., 6 for stress modes (\(S_{xx},...,S_{xy}\))
  • outputVariableTypeModeBasis [type = OutputVariableType, default = OutputVariableType::_None]:
    this must be the output variable type of the outputVariableModeBasis, e.g. exu.OutputVariableType.Stress
  • referencePositions [\(\LU{b}{{\mathbf{x}}}\cRef \in \Rcal^{n\indf}\), type = NumpyVector, default = []]:
    vector containing the reference positions of all flexible nodes, needed for graphics
  • objectIsInitialized [type = Bool, default = False]:
    ALWAYS set to False! flag used to correctly initialize all FFRF matrices; as soon as this flag is False, some internal (constant) FFRF matrices are recomputed during Assemble()
  • physicsMass [\(m\), type = UReal, default = 0.]:
    total mass [SI:kg] of FFRFreducedOrder object
  • physicsInertia [\({\mathbf{J}}_r \in \Rcal^{3 \times 3}\), type = Matrix3D, default = [[1,0,0], [0,1,0], [0,0,1]]]:
    inertia tensor [SI:kgm\(^2\)] of rigid body w.r.t. to the reference point of the body
  • physicsCenterOfMass [\(\LU{b}{{\mathbf{b}}}_{COM}\), type = Vector3D, size = 3, default = [0.,0.,0.]]:
    local position of center of mass (COM)
  • mPsiTildePsi [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • mPsiTildePsiTilde [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • mPhitTPsi [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • mPhitTPsiTilde [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • mXRefTildePsi [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • mXRefTildePsiTilde [type = NumpyMatrix, default = Matrix[]]:
    special FFRFreducedOrder matrix, computed in ObjectFFRFreducedOrderInterface
  • physicsCenterOfMassTilde [\(\LU{b}{\tilde {\mathbf{b}}}_{COM}\), type = Matrix3D, default = [[0,0,0], [0,0,0], [0,0,0]]]:
    tilde matrix from local position of COM; autocomputed during initialization
  • tempUserFunctionForce [\({\mathbf{f}}_{temp} \in \Rcal^{n_{ODE2}}\), type = NumpyVector, default = []]:
    temporary vector for UF force
  • visualization [type = VObjectFFRFreducedOrder]:
    parameters for visualization of item

The item VObjectFFRFreducedOrder has the following parameters:

  • show [type = Bool, default = True]:
    set true, if item is shown in visualization and false if it is not shown; use visualizationSettings.bodies.deformationScaleFactor to draw scaled (local) deformations; the reference frame node is shown with additional letters RF
  • color [type = Float4, size = 4, default = [-1.,-1.,-1.,-1.]]:
    RGBA color for object; 4th value is alpha-transparency; R=-1.f means, that default color is used
  • triangleMesh [type = NumpyMatrixI, default = MatrixI[]]:
    a matrix, containg node number triples in every row, referring to the node numbers of the GenericODE2 object; the mesh uses the nodes to visualize the underlying object; contour plot colors are still computed in the local frame!
  • showNodes [type = Bool, default = False]:
    set true, nodes are drawn uniquely via the mesh, eventually using the floating reference frame, even in the visualization of the node is show=False; node numbers are shown with indicator ‘NF’

DESCRIPTION of ObjectFFRFreducedOrder

The following output variables are available as OutputVariableType in sensors, Get…Output() and other functions:

  • Coordinates:
    all ODE2 coordinates
  • Coordinates\_t:
    all ODE2 velocity coordinates
  • Force:
    generalized forces for all coordinates (residual of all forces except mass*accleration; corresponds to ComputeODE2LHS)

Super element output variables

Functions like GetObjectOutputSuperElement(...), see Section MainSystem: Object, or SensorSuperElement, see Section MainSystem: Sensor, directly access special output variables (OutputVariableType) of the mesh nodes of the superelement. Additionally, the contour drawing of the object can make use the OutputVariableType of the meshnodes.

super element output variables
symbol
description
DisplacementLocal (mesh node \(i\))
\(\LU{b}{{\mathbf{u}}\indf^{(i)}} = \left( \LU{b}{\tPsi} \tzeta\right)_{3\cdot i \ldots 3\cdot i+2}= \vr{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+1}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+2}}}\)
local nodal mesh displacement in reference (body) frame, measuring only flexible part of displacement
VelocityLocal (mesh node \((i)\))
\(\LU{b}{\dot {\mathbf{u}}_\mathrm{f}^{(i)}} = \left( \LU{b}{\tPsi} \dot \tzeta\right)_{3\cdot i \ldots 3\cdot i+2}\)
local nodal mesh velocity in reference (body) frame, only for flexible part of displacement
Displacement (mesh node \((i)\))
\(\LU{0}{{\mathbf{u}}\cConfig^{(i)}} = \LU{0}{{\mathbf{q}}_{\mathrm{t,config}}} + \LU{0b}{{\mathbf{A}}_\mathrm{config}} \LU{b}{{\mathbf{p}}_\mathrm{f,config}^{(i)}} - (\LU{0}{{\mathbf{q}}_{\mathrm{t,ref}}} + \LU{0b}{{\mathbf{A}}_{ref}} \LU{b}{{\mathbf{x}}\cRef^{(i)}})\)
nodal mesh displacement in global coordinates
Position (mesh node \((i)\))
\(\LU{0}{{\mathbf{p}}^{(i)}} = \LU{0}{\pRef} + \LU{0b}{{\mathbf{A}}} \LU{b}{{\mathbf{p}}\indf^{(i)}}\)
nodal mesh position in global coordinates
Velocity (mesh node \((i)\))
\(\LU{0}{\dot {\mathbf{u}}^{(i)}} = \LU{0}{\dot {\mathbf{q}}\indt} + \LU{0b}{{\mathbf{A}}} (\LU{b}{\dot {\mathbf{u}}\indf^{(i)}} + \LU{b}{\tilde \tomega} \LU{b}{{\mathbf{p}}\indf^{(i)}})\)
nodal mesh velocity in global coordinates
Acceleration (mesh node \((i)\))
\(\LU{0}{{\mathbf{a}}^{(i)}} = \LU{0}{\ddot {\mathbf{q}}\indt} + \LU{0b}{\Rot} \LU{b}{\ddot {\mathbf{u}}\indf^{(i)}} + 2\LU{0}{\tomega} \times \LU{0b}{\Rot} \LU{b}{\dot {\mathbf{u}}\indf^{(i)}} + \LU{0}{\talpha} \times \LU{0}{{\mathbf{p}}\indf^{(i)}} + \LU{0}{\tomega} \times (\LU{0}{\tomega} \times \LU{0}{{\mathbf{p}}\indf^{(i)}})\)
global acceleration of mesh node \(n_i\) including rigid body motion and flexible deformation; note that \(\LU{0}{{\mathbf{x}}}(n_i) = \LU{0b}{\Rot} \LU{b}{{\mathbf{x}}}(n_i)\)
StressLocal (mesh node \((i)\))
\(\LU{b}{\tsigma^{(i)}} = (\LU{b}{\tPsi_{OV}} \tzeta)_{3\cdot i \ldots 3\cdot i+5}\)
linearized stress components of mesh node \((i)\) in reference frame; \(\tsigma=[\sigma_{xx},\,\sigma_{yy},\,\sigma_{zz},\,\sigma_{yz},\,\sigma_{xz},\,\sigma_{xy}]\tp\); ONLY available, if \(\LU{b}{\tPsi}_{OV}\) is provided and outputVariableTypeModeBasis== exu.OutputVariableType.StressLocal
StrainLocal (mesh node \((i)\))
\(\LU{b}{\teps^{(i)}} = (\LU{b}{\tPsi}_{OV} \tzeta)_{3\cdot i \ldots 3\cdot i+5}\)
linearized strain components of mesh node \((i)\) in reference frame; \(\teps=[\varepsilon_{xx},\,\varepsilon_{yy},\,\varepsilon_{zz},\,\varepsilon_{yz},\,\varepsilon_{xz},\,\varepsilon_{xy}]\tp\); ONLY available, if \(\LU{b}{\tPsi}_{OV}\) is provided and outputVariableTypeModeBasis== exu.OutputVariableType.StrainLocal
intermediate variables
symbol
description
reference frame
\(b\)
the body-fixed / local frame is always denoted by \(b\)
number of rigid body coordinates
\(n\indrigid\)
number of rigid body node coordinates: 6 in case of Euler angles (not fully available for ObjectFFRFreducedOrder) and 7 in case of Euler parameters
number of flexible / mesh coordinates
\(n\indf = 3 \cdot n_n\)
with number of nodes \(n_n\); relevant for visualization
number of modal coordinates
\(n_m \ll n\indf\)
the number of reduced or modal coordinates, computed from number of columns given in modeBasis
total number object coordinates
\(n_{ODE2} = n_m + n_{rigid}\)

reference frame origin
\(\LU{0}{\pRef} = \LU{0}{{\mathbf{q}}_{\mathrm{t}}} + \LU{0}{{\mathbf{q}}_{\mathrm{t,ref}}}\)
reference frame position (origin)
reference frame rotation
\(\ttheta\cConfig = \ttheta\cConfig + \ttheta_{ref}\)
reference frame rotation parameters in any configuration except reference
reference frame orientation
\(\LU{0b}{\Rot}\cConfig = \LU{0b}{\Rot}\cConfig(\ttheta\cConfig)\)
transformation matrix for transformation of local (reference frame) to global coordinates, given by underlying rigid body node \(n_0\)
local vector of flexible coordinates
\(\LU{b}{{\mathbf{q}}\indf} = \LU{b}{\tPsi} \tzeta\)
represents mesh displacements; vector of alternating x,y, an z coordinates of local (in body frame) mesh displacements reconstructed from modal coordinates \(\tzeta\); only evaluated for selected node points (e.g., sensors) during computation; corresponds to same vector in ObjectFFRF
local nodal positions
\(\LU{b}{{\mathbf{p}}\indf} = \LU{b}{{\mathbf{q}}\indf} + \LU{b}{{\mathbf{x}}\cRef}\)
vector of all body-fixed nodal positions including flexible part; only evaluated for selected node points during computation
local position of node (i)
\(\LU{b}{{\mathbf{p}}\indf^{(i)}} = \LU{b}{{\mathbf{u}}\indf^{(i)}} + \LU{b}{{\mathbf{x}}^{(i)}\cRef} = \vr{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+1}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+2}}} + \vr{\LU{b}{{\mathbf{x}}_{\mathrm{ref},i\cdot 3}}}{\LU{b}{{\mathbf{x}}_{\mathrm{ref},i\cdot 3+1}}}{\LU{b}{{\mathbf{x}}_{\mathrm{ref},i\cdot 3+2}}}\)
body-fixed, deformed nodal mesh position (including flexible part)
vector of modal coordinates
\(\tzeta = [\zeta_0,\,\ldots,\zeta_{n_m-1}]\tp\)
vector of modal or reduced coordinates; these coordinates can either represent amplitudes of eigenmodes, static modes or general modes, depending on your mode basis
coordinate vector
\({\mathbf{q}} = [\LU{0}{{\mathbf{q}}\indt},\,\tpsi,\,\tzeta]\)
vector of object coordinates; \({\mathbf{q}}\indt\) and \(\tpsi\) are the translation and rotation part of displacements of the reference frame, provided by the rigid body node (node number 0)
flexible coordinates transformation matrix
\(\LU{0b}{{\mathbf{A}}_{bd}} = \mathrm{diag}([\LU{0b}{{\mathbf{A}}},\;\ldots,\;\LU{0b}{{\mathbf{A}}}])\)
block diagonal transformation matrix, which transforms all flexible coordinates from local to global coordinates

Equations of motion

Equations of motion, in case that computeFFRFterms = True:

\[\begin{split}\left({\mathbf{M}}_{user}(mbs, t,{\mathbf{q}},\dot {\mathbf{q}}) + \mr{{\mathbf{M}}\indtt}{{\mathbf{M}}\indtr}{{\mathbf{M}}\indtf} {}{{\mathbf{M}}\indrr}{{\mathbf{M}}\indrf} {\mathrm{sym.}}{}{{\mathbf{M}}\indff} \right) \ddot {\mathbf{q}} + \mr{0}{0}{0} {0}{0}{0} {0}{0}{{\mathbf{D}}\indff} \dot {\mathbf{q}} + \mr{0}{0}{0} {0}{0}{0} {0}{0}{{\mathbf{K}}\indff} {\mathbf{q}} = &&\\ \nonumber {\mathbf{f}}_v({\mathbf{q}},\dot {\mathbf{q}}) + {\mathbf{f}}_{user}(mbs, t,{\mathbf{q}},\dot {\mathbf{q}}) &&\end{split}\]

(NOTE that currently the internal (C++) computed terms are zero,

\[\mr{{\mathbf{M}}\indtt}{{\mathbf{M}}\indtr}{{\mathbf{M}}\indtf} {}{{\mathbf{M}}\indrr}{{\mathbf{M}}\indrf} {\mathrm{sym.}}{}{{\mathbf{M}}\indff} = \Null \quad \mathrm{and} \quad {\mathbf{f}}_v({\mathbf{q}},\dot {\mathbf{q}}) = \Null ,\]

but they are implemented in predefined user functions, see FEM.py, Section Class function: AddObjectFFRFreducedOrderWithUserFunctions. In near future, these terms will be implemented in C++ and replace the user functions.) Note that in case of Euler parameters for the parameterization of rotations for the reference frame, the Euler parameter constraint equation is added automatically by this object. The single terms of the mass matrix are defined as

\[\begin{split}{\mathbf{M}}\indtt &=& m \mathbf{I}_{3 \times 3} \\ {\mathbf{M}}\indtr &=& -\LU{0b}{\Rot} \left[ m \LU{b}{\tilde \tchi\indu} + {\mathbf{M}}_{\Phi\indt\!{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{{\mathbf{G}}}\\ {\mathbf{M}}\indtf &=& \LU{0b}{\Rot} {\mathbf{M}}_{\Phi\indt\!\Psi} \\ {\mathbf{M}}\indrr &=& \LU{b}{{\mathbf{G}}\tp} \left[\LU{b}{\tTheta}\indu + {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}}\tp + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{{\widetilde\Psi}{\widetilde\Psi}}\left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{{\mathbf{G}}}\\ {\mathbf{M}}\indrf &=& -\LU{b}{{\mathbf{G}}\tp} \left[ {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef\Psi} + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{{\widetilde\Psi}\Psi} \right] \\ {\mathbf{M}}\indff &=& {\mathbf{M}}_{\Psi\Psi}\end{split}\]

with the Kronecker product(In Python numpy module this is computed by numpy.kron(zeta, Im).T),

\[\tzeta \otimes {\mathbf{I}} = \vr{\zeta_0 {\mathbf{I}}}{\vdots}{\zeta_{m-1} {\mathbf{I}}}\]

The quadratic velocity vector \({\mathbf{f}}_v({\mathbf{q}},\dot {\mathbf{q}}) = \left[ {\mathbf{f}}_{v\mathrm{t}}\tp,\; {\mathbf{f}}_{v\mathrm{r}}\tp,\; {\mathbf{f}}_{v\mathrm{f}}\tp \right]\tp\) reads

\[\begin{split}{\mathbf{f}}_{v\mathrm{t}} &=& \LU{0b}{\Rot} \LU{b}{\tilde \tomega}\left[ m \LU{b}{\tilde \tchi\indu} + {\mathbf{M}}_{\Phi\indt\!{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\tomega} + 2 \LU{0b}{\Rot} {\mathbf{M}}_{\Phi\indt\!{\widetilde\Psi}} \left( \dot \tzeta \otimes {\mathbf{I}} \right) \LU{b}{\tomega} \nonumber \\ && + \LU{0b}{\Rot} \left[ m \LU{b}{\tilde \tchi\indu} + {\mathbf{M}}_{\Phi\indt\!{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\dot {\mathbf{G}}} \dot \ttheta , \\ {\mathbf{f}}_{v\mathrm{r}} &=& -\LU{b}{{\mathbf{G}}\tp} \LU{b}{\tilde \tomega} \left[\LU{b}{\tTheta}\indu + {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}}\tp + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{{\widetilde\Psi}{\widetilde\Psi}}\left( \tzeta \otimes {\mathbf{I}} \right) \right]\LU{b}{\tomega} \nonumber \\ && -2 \LU{b}{{\mathbf{G}}\tp} \left[ {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}} \left( \dot \tzeta \otimes {\mathbf{I}} \right) + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{{\widetilde\Psi}{\widetilde\Psi}}\left( \dot \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\tomega} \nonumber \\ && -\LU{b}{{\mathbf{G}}\tp}\left[\LU{b}{\tTheta}\indu + {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}} \left( \tzeta \otimes {\mathbf{I}} \right) + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{\tilde {\mathbf{x}}\cRef{\widetilde\Psi}}\tp + \left( \tzeta \otimes {\mathbf{I}} \right)\tp {\mathbf{M}}_{{\widetilde\Psi}{\widetilde\Psi}}\left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\dot {\mathbf{G}}} \dot \ttheta , \\ {\mathbf{f}}_{v\mathrm{f}} &=& \left( {\mathbf{I}}_\zeta \otimes \LU{b}{\tomega} \right)\tp \left[ {\mathbf{M}}_{\tilde{\mathbf{x}}\cRef{\widetilde\Psi}}\tp + {\mathbf{M}}_{{\widetilde\Psi}{\widetilde\Psi}}\left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\tomega} +2 {\mathbf{M}}_{{\widetilde\Psi}{\Psi}}\tp\left( \dot\tzeta \otimes {\mathbf{I}} \right) \LU{b}{\tomega} \nonumber \\ && + \left[ {\mathbf{M}}_{\tilde{\mathbf{x}}\cRef{\Psi}}\tp + {\mathbf{M}}_{{\widetilde\Psi}{\Psi}}\tp\left( \tzeta \otimes {\mathbf{I}} \right) \right] \LU{b}{\dot {\mathbf{G}}} \dot \ttheta .\end{split}\]

Note that terms including \(\LU{b}{\dot {\mathbf{G}}} \dot \ttheta\) vanish in case of Euler parameters or in case that \(\LU{b}{\dot {\mathbf{G}}} = \Null\), and we use another Kronecker product with the unit matrix \({\mathbf{I}}_\zeta \in \Rcal^{n_m \times n_m}\),

\[{\mathbf{I}}_\zeta \otimes \LU{b}{\tomega} = \mr{\LU{b}{\tomega}}{}{} {}{\ddots}{} {}{}{\LU{b}{\tomega}} \in \Rcal^{3n_m \times n_m}\]

In case that computeFFRFterms = False, the mass terms \({\mathbf{M}}\indtt \ldots {\mathbf{M}}\indff\) are zero (not computed) and the quadratic velocity vector \({\mathbf{f}}_Q = \Null\). Note that the user functions \({\mathbf{f}}_{user}(mbs, t,{\mathbf{q}},\dot {\mathbf{q}})\) and \({\mathbf{M}}_{user}(mbs, t,{\mathbf{q}},\dot {\mathbf{q}})\) may be empty (=0). The detailed equations of motion for this element can be found in .

Position Jacobian

For joints and loads, the position jacobian of a node is needed in order to compute forces applied to averaged displacements and rotations at nodes. Recall that the modal coordinates \(\tzeta\) are transformed to node coordinates by means of the mode basis \(\LU{b}{\tPsi}\),

\[\LU{b}{{\mathbf{q}}\indf} = \LU{b}{\tPsi} \tzeta .\]

The local displacements \(\LU{b}{{\mathbf{u}}\indf^{(i)}}\) of a specific node \(i\) can be reconstructed in this way by means of

\[\LU{b}{{\mathbf{u}}\indf^{(i)}} = \vr{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+1}}}{\LU{b}{{\mathbf{q}}_{\mathrm{f},i\cdot 3+2}}} ,\]

and the global position of a node, see tables above, reads

\[\LU{0}{{\mathbf{p}}^{(i)}} = \LU{0}{{\mathbf{p}}\indt} + \LU{0b}{{\mathbf{A}}} \left( \LU{b}{{\mathbf{u}}\indf^{(i)}} + \LU{b}{{\mathbf{x}}^{(i)}\cRef} \right)\]

Thus, the jacobian of the global position reads

\[\LU{0}{{\mathbf{J}}_\mathrm{pos}^{(i)}} = \frac{\partial \LU{0}{{\mathbf{p}}^{(i)}}}{\partial [{\mathbf{q}}\indt, \;\ttheta, \;\tzeta]} = \left[\mathbf{I}_{3 \times 3}, \; -\LU{0b}{\Rot} \left(\LU{b}{\tilde{\mathbf{u}}\indf^{(i)}} + \LU{b}{\tilde{\mathbf{x}}^{(i)}\cRef} \right) \LU{b}{{\mathbf{G}}},\; \LU{0b}{\Rot} \vr{\LU{b}{\tPsi_{r=3i}\tp}}{\LU{b}{\tPsi_{r=3i+1}\tp}}{\LU{b}{\tPsi_{r=3i+2}\tp}}\right] ,\]

in which \(\LU{b}{\tPsi_{r=...}}\) represents the row \(r\) of the mode basis (matrix) \(\LU{b}{\Psi}\), and the matrix

\[\vr{\LU{b}{\tPsi_{r=3i}\tp}}{\LU{b}{\tPsi_{r=3i+1}\tp}}{\LU{b}{\tPsi_{r=3i+2}\tp}} \in \Rcal^{3 \times n_m}\]

Furthermore, the jacobian of the local position reads

\[\LU{b}{{\mathbf{J}}_\mathrm{pos}^{(i)}} = \frac{\partial \LU{b}{{\mathbf{p}}\indf^{(i)}}}{\partial [{\mathbf{q}}\indt, \;\ttheta, \;\tzeta]} = \left[\Null, \; \Null, \; \vr{\LU{b}{\tPsi_{r=3i}\tp}}{\LU{b}{\tPsi_{r=3i+1}\tp}}{\LU{b}{\tPsi_{r=3i+2}\tp}}\right] ,\]

which is used in MarkerSuperElementRigid.

Joints and Loads

Use special MarkerSuperElementPosition to apply forces, SpringDampers or spherical joints. This marker can be attached to a single node of the underlying mesh or to a set of nodes, which is then averaged, see the according marker description.

Use special MarkerSuperElementRigid to apply torques or special joints (e.g., JointGeneric). This marker must be attached to a set of nodes which can represent rigid body motion. The rigid body motion is then averaged for all of these nodes, see the according marker description.

For application of mass proportional loads (gravity), you can use conventional MarkerBodyMass. However, do not use MarkerBodyPosition or MarkerBodyRigid for ObjectFFRFreducedOrder, unless wanted, because it only attaches to the floating frame. This means, that a force to a MarkerBodyPosition would only be applied to the (rigid) floating frame, but not onto the deformable body and results depend strongly on the choice of the reference frame (or the underlying mode shapes).

CoordinateLoads are added for each ODE2 coordinate on the RHS of the equations of motion.


Userfunction: forceUserFunction(mbs, t, itemNumber, q, q_t)

A user function, which computes a force vector depending on current time and states of object. Can be used to create any kind of mechanical system by using the object states. Note that itemNumber represents the index of the ObjectFFRFreducedOrder object in mbs, which can be used to retrieve additional data from the object through mbs.GetObjectParameter(itemNumber, ...), see the according description of GetObjectParameter.

arguments / return
type or size
description
mbs
MainSystem
provides MainSystem mbs to which object belongs
t
Real
current time in mbs
itemNumber
Index
integer number of the object in mbs, allowing easy access to all object data via mbs.GetObjectParameter(itemNumber, …)
q
Vector \(\in \Rcal^n_{ODE2}\)
FFRF object coordinates (rigid body coordinates and reduced coordinates in a list) in current configuration, without reference values
q_t
Vector \(\in \Rcal^n_{ODE2}\)
object velocity coordinates (time derivatives of q) in current configuration
returnValue
Vector \(\in \Rcal^{n_{ODE2}}\)
returns force vector for object

Userfunction: massMatrixUserFunction(mbs, t, itemNumber, q, q_t)

A user function, which computes a mass matrix depending on current time and states of object. Can be used to create any kind of mechanical system by using the object states.

arguments / return
type or size
description
mbs
MainSystem
provides MainSystem mbs to which object belongs
t
Real
current time in mbs
itemNumber
Index
integer number of the object in mbs, allowing easy access to all object data via mbs.GetObjectParameter(itemNumber, …)
q
Vector \(\in \Rcal^n_{ODE2}\)
FFRF object coordinates (rigid body coordinates and reduced coordinates in a list) in current configuration, without reference values
q_t
Vector \(\in \Rcal^n_{ODE2}\)
object velocity coordinates (time derivatives of q) in current configuration
returnValue
NumpyMatrix \(\in \Rcal^{n_{ODE2} \times n_{ODE2}}\)
returns mass matrix for object

Relevant Examples and TestModels with weblink:

The web version may not be complete. For details, consider also the Exudyn PDF documentation : theDoc.pdf