rigidBodyModel Class Reference

Basic rigid-body model representing a system of rigid-bodies connected by 1-6 DoF joints. More...

Inheritance diagram for rigidBodyModel:
Collaboration diagram for rigidBodyModel:

Public Member Functions

 TypeName ("rigidBodyModel")
 Runtime type information. More...
 
 rigidBodyModel ()
 Null-constructor which adds the single root-body at the origin. More...
 
 rigidBodyModel (const dictionary &dict)
 Construct from dictionary. More...
 
virtual ~rigidBodyModel ()
 Destructor. More...
 
label nBodies () const
 Return the number of bodies in the model (bodies().size()) More...
 
PtrList< rigidBodybodies () const
 Return the list of the bodies in the model. More...
 
const DynamicList< label > & lambda () const
 List of indices of the parent of each body. More...
 
const PtrList< joint > & joints () const
 Return the list of joints in the model. More...
 
label nDoF () const
 Return the number of degrees of freedom of the model. More...
 
bool unitQuaternions () const
 Return true if any of the joints using quaternions. More...
 
const vectorg () const
 Return the acceleration due to gravity. More...
 
vectorg ()
 Allow the acceleration due to gravity to be set. More...
 
const wordname (const label bodyID) const
 Return the name of body with the given ID. More...
 
wordList movingBodyNames () const
 Return the names of the moving bodies. More...
 
const rigidBodyInertiaI (const label i) const
 Return the inertia of body i. More...
 
const spatialVectorv (const label i) const
 Return the spatial velocity of the bodies. More...
 
virtual label join (const label parentID, const spatialTransform &XT, autoPtr< joint > jointPtr, autoPtr< rigidBody > bodyPtr)
 Join the given body to the parent with ID parentID via the given. More...
 
label join (const label parentID, const spatialTransform &XT, autoPtr< joints::composite > cJoint, autoPtr< rigidBody > bodyPtr)
 Join the given body to the parent with ID parentID via the given. More...
 
label merge (const label parentID, const spatialTransform &X, autoPtr< rigidBody > bodyPtr)
 Merge the given body with transform X into the parent with ID. More...
 
bool merged (label bodyID) const
 Return true if the body with given ID has been merged with a parent. More...
 
label master (label bodyID) const
 Return the ID of the master body for a sub-body otherwise. More...
 
label mergedBodyIndex (const label mergedBodyID) const
 Return the index of the merged body in the mergedBody list. More...
 
label mergedBodyID (const label mergedBodyIndex) const
 Return the merged body ID for the given merged body index. More...
 
const subBodymergedBody (label mergedBodyID) const
 Return the merged body for the given body ID. More...
 
label bodyID (const word &name) const
 Return the ID of the body with the given name. More...
 
spatialTransform X0 (const label bodyId) const
 Return the current transform to the global frame for the given body. More...
 
vector masterPoint (const label bodyID, const vector &p) const
 
spatialVector v (const label bodyID, const vector &p) const
 Return the velocity of the given point on the given body. More...
 
void applyRestraints (scalarField &tau, Field< spatialVector > &fx) const
 Apply the restraints and accumulate the internal joint forces. More...
 
void forwardDynamics (rigidBodyModelState &state, const scalarField &tau, const Field< spatialVector > &fx) const
 Calculate the joint acceleration qDdot from the joint state q,. More...
 
void forwardDynamicsCorrection (const rigidBodyModelState &state) const
 Correct the velocity and acceleration of the bodies in the model. More...
 
virtual void write (Ostream &) const
 Write. More...
 
bool read (const dictionary &dict)
 Read coefficients dictionary and update system parameters,. More...
 

Protected Member Functions

virtual label join_ (const label parentID, const spatialTransform &XT, autoPtr< joint > jointPtr, autoPtr< rigidBody > bodyPtr)
 Join the given body to the parent with ID parentID via the given. More...
 

Protected Attributes

PtrList< rigidBodybodies_
 List of the bodies. More...
 
PtrList< subBodymergedBodies_
 Bodies may be merged into existing bodies, the inertia of which is. More...
 
HashTable< label, wordbodyIDs_
 Lookup-table of the IDs of the bodies. More...
 
DynamicList< labellambda_
 List of indices of the parent of each body. More...
 
PtrList< jointjoints_
 Each body it attached with a joint which are held on this list. More...
 
DynamicList< spatialTransformXT_
 Transform from the parent body frame to the joint frame. More...
 
label nDoF_
 The number of degrees of freedom of the model. More...
 
bool unitQuaternions_
 True if any of the joints using quaternions. More...
 
PtrList< restraintrestraints_
 Motion restraints. More...
 
vector g_
 Acceleration due to gravity. More...
 
DynamicList< spatialTransformXlambda_
 Transform from the parent body to the current body. More...
 
DynamicList< spatialTransformX0_
 Transform for external forces to the bodies reference frame. More...
 
DynamicList< spatialVectorv_
 The spatial velocity of the bodies. More...
 
DynamicList< spatialVectora_
 The spatial acceleration of the bodies. More...
 
DynamicList< spatialVectorc_
 The velocity dependent spatial acceleration of the joints. More...
 
DynamicList< spatialTensorIA_
 Velocity-product acceleration. More...
 
DynamicList< spatialVectorpA_
 Articulated body bias force. More...
 
DynamicList< compactSpatialTensorS_
 Motion subspace for joints with 3 degrees of freedom. More...
 
DynamicList< spatialVectorS1_
 Motion subspace for joints with 1 degrees of freedom. More...
 
DynamicList< compactSpatialTensorU_
 Sub-expression IA.S in the forward-dynamics algorithm. More...
 
DynamicList< spatialVectorU1_
 Sub-expression IA.S1 in the forward-dynamics algorithm. More...
 
DynamicList< tensorDinv_
 Sub-expression (S^T.U)^-1 in the forward-dynamics algorithm. More...
 
DynamicList< vectoru_
 Sub-expression tau - S^T.pA in the forward-dynamics algorithm. More...
 

Friends

Ostreamoperator<< (Ostream &, const rigidBodyModel &)
 

Detailed Description

Basic rigid-body model representing a system of rigid-bodies connected by 1-6 DoF joints.

This class holds various body and joint state fields needed by the kinematics and forward-dynamics algorithms presented in

reference:

    Featherstone, R. (2008).
    Rigid body dynamics algorithms.
    Springer.
    Chapter 4.
Source files

Definition at line 76 of file rigidBodyModel.H.

Constructor & Destructor Documentation

◆ rigidBodyModel() [1/2]

Null-constructor which adds the single root-body at the origin.

Definition at line 166 of file rigidBodyModel.C.

◆ rigidBodyModel() [2/2]

◆ ~rigidBodyModel()

~rigidBodyModel ( )
virtual

Destructor.

Definition at line 214 of file rigidBodyModel.C.

References rigidBodyModel::join().

Here is the call graph for this function:

Member Function Documentation

◆ join_()

Foam::label join_ ( const label  parentID,
const spatialTransform XT,
autoPtr< joint jointPtr,
autoPtr< rigidBody bodyPtr 
)
protectedvirtual

Join the given body to the parent with ID parentID via the given.

joint with transform from the parent frame to the joint frame XT.

Definition at line 120 of file rigidBodyModel.C.

References subBody::masterID(), subBody::masterXT(), rigidBody::name(), joint::nDoF(), and joint::unitQuaternion().

Referenced by rigidBodyModel::join().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ TypeName()

TypeName ( "rigidBodyModel"  )

Runtime type information.

◆ nBodies()

Foam::label nBodies ( ) const
inline

Return the number of bodies in the model (bodies().size())

Definition at line 28 of file rigidBodyModelI.H.

References rigidBodyModel::bodies_.

Referenced by rigidBodyModel::movingBodyNames(), rigidBodyMeshMotionSolver::solve(), rigidBodyMeshMotion::solve(), and rigidBodyModel::write().

Here is the caller graph for this function:

◆ bodies()

Foam::PtrList< Foam::RBD::rigidBody > bodies ( ) const
inline

Return the list of the bodies in the model.

Definition at line 35 of file rigidBodyModelI.H.

References rigidBodyModel::bodies_.

◆ lambda()

const Foam::DynamicList< Foam::label > & lambda ( ) const
inline

List of indices of the parent of each body.

Definition at line 42 of file rigidBodyModelI.H.

References rigidBodyModel::lambda_.

Referenced by rigidBodyMotion::transformPoints().

Here is the caller graph for this function:

◆ joints()

const Foam::PtrList< Foam::RBD::joint > & joints ( ) const
inline

Return the list of joints in the model.

Definition at line 49 of file rigidBodyModelI.H.

References rigidBodyModel::joints_.

Referenced by rigidBodySolver::correctQuaternionJoints().

Here is the caller graph for this function:

◆ nDoF()

Foam::label nDoF ( ) const
inline

Return the number of degrees of freedom of the model.

used to set the size of the of joint state fields q, qDot and qDdot.

Definition at line 55 of file rigidBodyModelI.H.

References rigidBodyModel::nDoF_.

Referenced by rigidBodyMeshMotionSolver::solve(), and rigidBodyMeshMotion::solve().

Here is the caller graph for this function:

◆ unitQuaternions()

bool unitQuaternions ( ) const
inline

Return true if any of the joints using quaternions.

Definition at line 61 of file rigidBodyModelI.H.

References rigidBodyModel::unitQuaternions_.

Referenced by rigidBodySolver::correctQuaternionJoints().

Here is the caller graph for this function:

◆ g() [1/2]

const Foam::vector & g ( ) const
inline

Return the acceleration due to gravity.

Definition at line 67 of file rigidBodyModelI.H.

References rigidBodyModel::g_.

Referenced by rigidBodyMotion::rigidBodyMotion(), rigidBodyMeshMotionSolver::solve(), and rigidBodyMeshMotion::solve().

Here is the caller graph for this function:

◆ g() [2/2]

Foam::vector & g ( )
inline

Allow the acceleration due to gravity to be set.

after model construction

Definition at line 73 of file rigidBodyModelI.H.

References rigidBodyModel::g_, and rigidBodyModel::name().

Here is the call graph for this function:

◆ name()

const Foam::word & name ( const label  bodyID) const
inline

Return the name of body with the given ID.

Definition at line 80 of file rigidBodyModelI.H.

References rigidBodyModel::bodies_, rigidBodyModel::bodyID(), rigidBodyModel::merged(), rigidBodyModel::mergedBody(), and subBody::name().

Referenced by rigidBodyModel::bodyID(), rigidBodyModel::g(), rigidBodyModel::merge(), rigidBodyMotion::status(), and rigidBodyModel::write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ movingBodyNames()

Foam::wordList movingBodyNames ( ) const

Return the names of the moving bodies.

Definition at line 387 of file rigidBodyModel.C.

References rigidBodyModel::bodies_, rigidBodyModel::nBodies(), and List< T >::setSize().

Here is the call graph for this function:

◆ I()

const Foam::RBD::rigidBodyInertia & I ( const label  i) const
inline

Return the inertia of body i.

Definition at line 96 of file rigidBodyModelI.H.

References rigidBodyModel::bodies_.

◆ v() [1/2]

const Foam::spatialVector & v ( const label  i) const
inline

Return the spatial velocity of the bodies.

Definition at line 103 of file rigidBodyModelI.H.

References rigidBodyModel::v_.

Referenced by rigidBodyModel::masterPoint(), rigidBodyMotion::status(), and rigidBodyState::write().

Here is the caller graph for this function:

◆ join() [1/2]

Foam::label join ( const label  parentID,
const spatialTransform XT,
autoPtr< joint jointPtr,
autoPtr< rigidBody bodyPtr 
)
virtual

Join the given body to the parent with ID parentID via the given.

joint with transform from the parent frame to the joint frame XT.

Definition at line 221 of file rigidBodyModel.C.

References rigidBodyModel::join_(), and autoPtr< T >::ptr().

Referenced by rigidBodyModel::rigidBodyModel(), and rigidBodyModel::~rigidBodyModel().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ join() [2/2]

Foam::label join ( const label  parentID,
const spatialTransform XT,
autoPtr< joints::composite cJoint,
autoPtr< rigidBody bodyPtr 
)

Join the given body to the parent with ID parentID via the given.

composite joint (specified as a list of co-located joints) with transform from the parent frame to the joint frame XT. Composite joins are useful to represent complex joints with degrees of freedom other than 1 or 3 which are directly supported.

Definition at line 255 of file rigidBodyModel.C.

References rigidBodyModel::bodies_, rigidBodyModel::bodyID(), Foam::clone(), rigidBodyModel::join_(), rigidBodyModel::merge(), autoPtr< T >::ptr(), and UPtrList< T >::size().

Here is the call graph for this function:

◆ merge()

Foam::label merge ( const label  parentID,
const spatialTransform X,
autoPtr< rigidBody bodyPtr 
)

Merge the given body with transform X into the parent with ID.

parentID. The parent body assumes the properties of the combined body (inertia etc.) and the merged body is held on a separate list for reference.

Definition at line 313 of file rigidBodyModel.C.

References rigidBodyModel::bodies_, rigidBodyModel::bodyIDs_, subBody::masterID(), subBody::masterXT(), rigidBodyModel::merged(), rigidBodyModel::mergedBodies_, rigidBodyModel::mergedBody(), rigidBodyModel::mergedBodyID(), subBody::name(), rigidBodyModel::name(), autoPtr< T >::set(), and rigidBodyModel::X0().

Referenced by rigidBodyModel::join(), and rigidBodyModel::rigidBodyModel().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ merged()

bool merged ( label  bodyID) const
inline

Return true if the body with given ID has been merged with a parent.

Definition at line 109 of file rigidBodyModelI.H.

Referenced by rigidBodyModel::masterPoint(), rigidBodyModel::merge(), rigidBodyModel::mergedBody(), rigidBodyModel::name(), rigidBodyModel::X0(), and rigidBodyMotion::X00().

Here is the caller graph for this function:

◆ master()

Foam::label master ( label  bodyID) const
inline

Return the ID of the master body for a sub-body otherwise.

return the given body ID

Definition at line 115 of file rigidBodyModelI.H.

References rigidBodyModel::bodyID(), subBody::masterID(), and rigidBodyModel::mergedBody().

Referenced by rigidBodyModel::v().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mergedBodyIndex()

Foam::label mergedBodyIndex ( const label  mergedBodyID) const
inline

Return the index of the merged body in the mergedBody list.

from the given body ID

Definition at line 136 of file rigidBodyModelI.H.

References rigidBodyModel::mergedBodyID().

Referenced by rigidBodyModel::mergedBody(), and rigidBodyModel::mergedBodyID().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mergedBodyID()

Foam::label mergedBodyID ( const label  mergedBodyIndex) const
inline

Return the merged body ID for the given merged body index.

in the mergedBody list

Definition at line 129 of file rigidBodyModelI.H.

References rigidBodyModel::mergedBodyIndex().

Referenced by rigidBodyModel::merge(), and rigidBodyModel::mergedBodyIndex().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mergedBody()

const Foam::RBD::subBody & mergedBody ( label  mergedBodyID) const
inline

Return the merged body for the given body ID.

Definition at line 143 of file rigidBodyModelI.H.

References Foam::abort(), Foam::FatalError, FatalErrorInFunction, rigidBodyModel::merged(), rigidBodyModel::mergedBodies_, and rigidBodyModel::mergedBodyIndex().

Referenced by rigidBodyModel::master(), rigidBodyModel::masterPoint(), rigidBodyModel::merge(), rigidBodyModel::name(), rigidBodyModel::X0(), and rigidBodyMotion::X00().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ bodyID()

Foam::label bodyID ( const word name) const
inline

◆ X0()

Foam::spatialTransform X0 ( const label  bodyId) const

Return the current transform to the global frame for the given body.

Definition at line 371 of file rigidBodyModel.C.

References subBody::masterID(), subBody::masterXT(), rigidBodyModel::merged(), rigidBodyModel::mergedBody(), and rigidBodyModel::X0_.

Referenced by rigidBodyModel::merge(), rigidBodyMotion::status(), rigidBodyMotion::transformPoints(), and rigidBodyState::write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ masterPoint()

Foam::vector masterPoint ( const label  bodyID,
const vector p 
) const
inline

Definition at line 163 of file rigidBodyModelI.H.

References Foam::inv(), rigidBodyModel::merged(), rigidBodyModel::mergedBody(), p, rigidBodyModel::v(), and Foam::Zero.

Referenced by rigidBodyModel::bodyID(), and rigidBodyModel::v().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ v() [2/2]

Foam::spatialVector v ( const label  bodyID,
const vector p 
) const
inline

Return the velocity of the given point on the given body.

Definition at line 184 of file rigidBodyModelI.H.

References rigidBodyModel::master(), rigidBodyModel::masterPoint(), Foam::T(), rigidBodyModel::v_, and rigidBodyModel::X0_.

Here is the call graph for this function:

◆ applyRestraints()

void applyRestraints ( scalarField tau,
Field< spatialVector > &  fx 
) const

Apply the restraints and accumulate the internal joint forces.

into the tau field and external forces into the fx field

Definition at line 33 of file forwardDynamics.C.

References DebugInfo, forAll, and rigidBodyModel::forwardDynamics().

Here is the call graph for this function:

◆ forwardDynamics()

void forwardDynamics ( rigidBodyModelState state,
const scalarField tau,
const Field< spatialVector > &  fx 
) const

Calculate the joint acceleration qDdot from the joint state q,.

velocity qDot, internal force tau (in the joint frame) and external force fx (in the global frame) using the articulated body algorithm (Section 7.3 and Table 7.1)

Definition at line 54 of file forwardDynamics.C.

References Field< Type >::block(), joint::XSvc::c, DebugInfo, DebugInFunction, Foam::endl(), rigidBodyModel::forwardDynamicsCorrection(), Foam::I, Foam::inv(), joint::jcalc(), joint::nDoF(), Foam::nl, rigidBodyModelState::q(), rigidBodyModelState::qDdot(), rigidBodyModelState::qDot(), joint::XSvc::S, joint::XSvc::S1, List< Type >::size(), T, joint::XSvc::v, x, Vector< Cmpt >::x(), joint::XSvc::X, Vector< Cmpt >::y(), Vector< Cmpt >::z(), and Foam::Zero.

Referenced by rigidBodyModel::applyRestraints(), and rigidBodyMotion::forwardDynamics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ forwardDynamicsCorrection()

void forwardDynamicsCorrection ( const rigidBodyModelState state) const

Correct the velocity and acceleration of the bodies in the model.

from the given joint state fields following an integration step of the forwardDynamics

Definition at line 226 of file forwardDynamics.C.

References Field< Type >::block(), joint::XSvc::c, DebugInfo, DebugInFunction, Foam::endl(), joint::jcalc(), joint::nDoF(), rigidBodyModelState::qDdot(), joint::XSvc::S, joint::XSvc::S1, joint::XSvc::v, joint::XSvc::X, and Foam::Zero.

Referenced by rigidBodyModel::forwardDynamics(), and rigidBodyMotion::solve().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write()

◆ read()

bool read ( const dictionary dict)

Read coefficients dictionary and update system parameters,.

restraints but not the current state

Definition at line 471 of file rigidBodyModel.C.

References rigidBodyModel::restraints_.

Referenced by rigidBodyMotion::read(), and rigidBodyModel::rigidBodyModel().

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ operator<<

Ostream& operator<< ( Ostream ,
const rigidBodyModel  
)
friend

Member Data Documentation

◆ bodies_

PtrList<rigidBody> bodies_
protected

List of the bodies.

The 0'th body represents the fixed origin and is constructed automatically. The subsequent (moving) bodies are appended by the join member function.

Definition at line 101 of file rigidBodyModel.H.

Referenced by rigidBodyModel::bodies(), rigidBodyModel::I(), rigidBodyModel::join(), rigidBodyModel::merge(), rigidBodyModel::movingBodyNames(), rigidBodyModel::name(), rigidBodyModel::nBodies(), and rigidBodyModel::write().

◆ mergedBodies_

PtrList<subBody> mergedBodies_
protected

Bodies may be merged into existing bodies, the inertia of which is.

updated to represent the combined body which is more efficient than attaching them with fixed joints. These 'merged' bodies are held on this list.

Definition at line 107 of file rigidBodyModel.H.

Referenced by rigidBodyModel::merge(), rigidBodyModel::mergedBody(), and rigidBodyModel::write().

◆ bodyIDs_

HashTable<label, word> bodyIDs_
protected

Lookup-table of the IDs of the bodies.

Definition at line 110 of file rigidBodyModel.H.

Referenced by rigidBodyModel::bodyID(), and rigidBodyModel::merge().

◆ lambda_

DynamicList<label> lambda_
protected

List of indices of the parent of each body.

Definition at line 113 of file rigidBodyModel.H.

Referenced by rigidBodyModel::lambda(), and rigidBodyModel::write().

◆ joints_

PtrList<joint> joints_
protected

Each body it attached with a joint which are held on this list.

Definition at line 116 of file rigidBodyModel.H.

Referenced by rigidBodyModel::joints(), and rigidBodyModel::write().

◆ XT_

DynamicList<spatialTransform> XT_
protected

Transform from the parent body frame to the joint frame.

Definition at line 119 of file rigidBodyModel.H.

Referenced by rigidBodyModel::write().

◆ nDoF_

label nDoF_
protected

The number of degrees of freedom of the model.

used to set the size of the of joint state fields q, qDot and qDdot.

Definition at line 123 of file rigidBodyModel.H.

Referenced by rigidBodyModel::nDoF().

◆ unitQuaternions_

bool unitQuaternions_
protected

True if any of the joints using quaternions.

Definition at line 126 of file rigidBodyModel.H.

Referenced by rigidBodyModel::unitQuaternions().

◆ restraints_

PtrList<restraint> restraints_
protected

Motion restraints.

Definition at line 129 of file rigidBodyModel.H.

Referenced by rigidBodyModel::read(), and rigidBodyModel::write().

◆ g_

vector g_
protected

Acceleration due to gravity.

Definition at line 135 of file rigidBodyModel.H.

Referenced by rigidBodyModel::g().

◆ Xlambda_

DynamicList<spatialTransform> Xlambda_
mutableprotected

Transform from the parent body to the current body.

Definition at line 141 of file rigidBodyModel.H.

◆ X0_

DynamicList<spatialTransform> X0_
mutableprotected

Transform for external forces to the bodies reference frame.

Definition at line 144 of file rigidBodyModel.H.

Referenced by rigidBodyModel::v(), and rigidBodyModel::X0().

◆ v_

DynamicList<spatialVector> v_
mutableprotected

The spatial velocity of the bodies.

Definition at line 150 of file rigidBodyModel.H.

Referenced by rigidBodyModel::v().

◆ a_

DynamicList<spatialVector> a_
mutableprotected

The spatial acceleration of the bodies.

Definition at line 153 of file rigidBodyModel.H.

◆ c_

DynamicList<spatialVector> c_
mutableprotected

The velocity dependent spatial acceleration of the joints.

Definition at line 156 of file rigidBodyModel.H.

◆ IA_

DynamicList<spatialTensor> IA_
mutableprotected

Velocity-product acceleration.

Articulated body inertia

Definition at line 164 of file rigidBodyModel.H.

◆ pA_

DynamicList<spatialVector> pA_
mutableprotected

Articulated body bias force.

Definition at line 167 of file rigidBodyModel.H.

◆ S_

DynamicList<compactSpatialTensor> S_
mutableprotected

Motion subspace for joints with 3 degrees of freedom.

Definition at line 173 of file rigidBodyModel.H.

◆ S1_

DynamicList<spatialVector> S1_
mutableprotected

Motion subspace for joints with 1 degrees of freedom.

Definition at line 176 of file rigidBodyModel.H.

◆ U_

DynamicList<compactSpatialTensor> U_
mutableprotected

Sub-expression IA.S in the forward-dynamics algorithm.

Definition at line 179 of file rigidBodyModel.H.

◆ U1_

DynamicList<spatialVector> U1_
mutableprotected

Sub-expression IA.S1 in the forward-dynamics algorithm.

Definition at line 182 of file rigidBodyModel.H.

◆ Dinv_

DynamicList<tensor> Dinv_
mutableprotected

Sub-expression (S^T.U)^-1 in the forward-dynamics algorithm.

Definition at line 185 of file rigidBodyModel.H.

◆ u_

DynamicList<vector> u_
mutableprotected

Sub-expression tau - S^T.pA in the forward-dynamics algorithm.

Definition at line 188 of file rigidBodyModel.H.


The documentation for this class was generated from the following files: