Robotics Library  0.7.0
Public Member Functions | Protected Attributes | List of all members
rl::mdl::Dynamic Class Reference

#include <Dynamic.h>

Inheritance diagram for rl::mdl::Dynamic:
Inheritance graph
[legend]

Public Member Functions

 Dynamic ()
 
virtual ~Dynamic ()
 
void calculateCentrifugalCoriolis ()
 Calculate centrifugal and Coriolis vector. More...
 
void calculateCentrifugalCoriolis (::rl::math::Vector &V)
 Calculate centrifugal and Coriolis vector. More...
 
void calculateGravity ()
 Calculate gravity vector. More...
 
void calculateGravity (::rl::math::Vector &G)
 Calculate gravity vector. More...
 
void calculateMassMatrix ()
 Calculate joint space mass matrix. More...
 
void calculateMassMatrix (::rl::math::Matrix &M)
 Calculate joint space mass matrix. More...
 
void calculateMassMatrixInverse ()
 Calculate joint space mass matrix inverse. More...
 
void calculateMassMatrixInverse (::rl::math::Matrix &invM)
 Calculate joint space mass matrix inverse. More...
 
void calculateOperationalMassMatrixInverse ()
 Calculate operational space mass matrix inverse. More...
 
void calculateOperationalMassMatrixInverse (const ::rl::math::Matrix &J, const ::rl::math::Matrix &invM, ::rl::math::Matrix &invMx) const
 Calculate operational space mass matrix inverse. More...
 
Modelclone () const
 
void eulerCauchy (const ::rl::math::Real &dt)
 Integration via Euler-Cauchy. More...
 
void forwardDynamics ()
 Forward dynamics via articulated-body algorithm. More...
 
const ::rl::math::VectorgetCentrifugalCoriolis () const
 Access calculated centrifugal and Coriolis vector. More...
 
const ::rl::math::VectorgetGravity () const
 Access calculated gravity vector. More...
 
const ::rl::math::MatrixgetMassMatrixInverse () const
 Access calculated joint space mass matrix inverse. More...
 
const ::rl::math::MatrixgetMassMatrix () const
 Access calculated joint space mass matrix. More...
 
const ::rl::math::MatrixgetOperationalMassMatrixInverse () const
 Access calculated operational space mass matrix inverse. More...
 
void getWorldGravity (::rl::math::Real &x, ::rl::math::Real &y, ::rl::math::Real &z) const
 
void getWorldGravity (::rl::math::Vector &xyz) const
 
void inverseDynamics ()
 Inverse dynamics via recursive Newton-Euler algorithm. More...
 
void inverseForce ()
 
void rungeKuttaNystrom (const ::rl::math::Real &dt)
 Integration via Runge-Kutta-Nyström. More...
 
void setWorldGravity (const ::rl::math::Real &x, const ::rl::math::Real &y, const ::rl::math::Real &z)
 
void setWorldGravity (const ::rl::math::Vector &xyz)
 
virtual void update ()
 
- Public Member Functions inherited from rl::mdl::Kinematic
 Kinematic ()
 
virtual ~Kinematic ()
 
Modelclone () const
 
bool calculateInversePosition (const ::rl::math::Transform &x, const ::std::size_t &leaf=0, const ::rl::math::Real &delta=::std::numeric_limits< ::rl::math::Real >::infinity(), const ::rl::math::Real &epsilon=1.0e-3f, const ::std::size_t &iterations=1000)
 Resolved motion rate control. More...
 
void calculateJacobian (const bool &inWorldFrame=true)
 Calculate Jacobian matrix. More...
 
void calculateJacobian (::rl::math::Matrix &J, const bool &inWorldFrame=true)
 Calculate Jacobian matrix. More...
 
void calculateJacobianDerivative (const bool &inWorldFrame=true)
 Calculate Jacobian derivative vector. More...
 
void calculateJacobianDerivative (::rl::math::Vector &Jdqd, const bool &inWorldFrame=true)
 Calculate Jacobian derivative vector. More...
 
void calculateJacobianInverse (const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true)
 Calculate Jacobian matrix inverse. More...
 
void calculateJacobianInverse (const ::rl::math::Matrix &J, ::rl::math::Matrix &invJ, const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true) const
 Calculate Jacobian matrix inverse. More...
 
::rl::math::Real calculateManipulabilityMeasure () const
 Calculate manipulability measure. More...
 
::rl::math::Real calculateManipulabilityMeasure (const ::rl::math::Matrix &J) const
 Calculate manipulability measure. More...
 
void forwardAcceleration ()
 
void forwardPosition ()
 
void forwardVelocity ()
 
const ::rl::math::MatrixgetJacobian () const
 Access calculated Jacobian matrix. More...
 
const ::rl::math::VectorgetJacobianDerivative () const
 Access calculated Jacobian derivative vector. More...
 
const ::rl::math::MatrixgetJacobianInverse () const
 Access calculated Jacobian matrix inverse. More...
 
bool isSingular () const
 Check if current configuration is singular. More...
 
bool isSingular (const ::rl::math::Matrix &J) const
 Check if current configuration is singular. More...
 
- Public Member Functions inherited from rl::mdl::Metric
 Metric ()
 
virtual ~Metric ()
 
void clip (::rl::math::Vector &q) const
 
Modelclone () const
 
::rl::math::Real distance (const ::rl::math::Vector &q1, const ::rl::math::Vector &q2) const
 
void interpolate (const ::rl::math::Vector &q1, const ::rl::math::Vector &q2, const ::rl::math::Real &alpha, ::rl::math::Vector &q) const
 
::rl::math::Real inverseOfTransformedDistance (const ::rl::math::Real &d) const
 
bool isValid (const ::rl::math::Vector &q) const
 
::rl::math::Real maxDistanceToRectangle (const ::rl::math::Vector &q, const ::rl::math::Vector &min, const ::rl::math::Vector &max) const
 
::rl::math::Real minDistanceToRectangle (const ::rl::math::Vector &q, const ::rl::math::Vector &min, const ::rl::math::Vector &max) const
 
::rl::math::Real minDistanceToRectangle (const ::rl::math::Real &q, const ::rl::math::Real &min, const ::rl::math::Real &max, const ::std::size_t &cuttingDimension) const
 
::rl::math::Real newDistance (const ::rl::math::Real &dist, const ::rl::math::Real &oldOff, const ::rl::math::Real &newOff, const int &cuttingDimension) const
 
void normalize (::rl::math::Vector &q) const
 
void step (const ::rl::math::Vector &q1, const ::rl::math::Vector &qdot, ::rl::math::Vector &q2) const
 
::rl::math::Real transformedDistance (const ::rl::math::Real &d) const
 
::rl::math::Real transformedDistance (const ::rl::math::Vector &q1, const ::rl::math::Vector &q2) const
 
::rl::math::Real transformedDistance (const ::rl::math::Real &q1, const ::rl::math::Real &q2, const ::std::size_t &i) const
 
- Public Member Functions inherited from rl::mdl::Model
 Model ()
 
virtual ~Model ()
 
void add (Compound *compound, const Frame *a, const Frame *b)
 
void add (Frame *frame)
 
void add (Transform *transform, const Frame *a, const Frame *b)
 
bool areColliding (const ::std::size_t &i, const ::std::size_t &j) const
 
Modelclone () const
 
::rl::math::Vector generatePositionGaussian (const ::rl::math::Vector &rand, const ::rl::math::Vector &mean, const ::rl::math::Vector &sigma) const
 
::rl::math::Vector generatePositionUniform (const ::rl::math::Vector &rand) const
 
::rl::math::Vector getAcceleration () const
 
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > getAccelerationUnits () const
 
::std::size_t getBodies () const
 
BodygetBody (const ::std::size_t &i) const
 
::std::size_t getDof () const
 
::std::size_t getDofPosition () const
 
const ::rl::math::TransformgetFrame (const ::std::size_t &i) const
 
const ::rl::math::MatrixgetGammaPosition () const
 
const ::rl::math::MatrixgetGammaVelocity () const
 
const ::rl::math::MatrixgetGammaPositionInverse () const
 
const ::rl::math::MatrixgetGammaVelocityInverse () const
 
::rl::math::Vector getHomePosition () const
 
JointgetJoint (const ::std::size_t &i) const
 
::std::size_t getJoints () const
 
const ::rl::math::MotionVectorgetOperationalAcceleration (const ::std::size_t &i) const
 
::std::size_t getOperationalDof () const
 
const ::rl::math::ForceVectorgetOperationalForce (const ::std::size_t &i) const
 
const ::rl::math::TransformgetOperationalPosition (const ::std::size_t &i) const
 
const ::rl::math::MotionVectorgetOperationalVelocity (const ::std::size_t &i) const
 
const ::std::string & getManufacturer () const
 
::rl::math::Vector getMaximum () const
 
::rl::math::Vector getMinimum () const
 
const ::std::string & getName () const
 
::rl::math::Vector getPosition () const
 
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > getPositionUnits () const
 
::rl::math::Vector getTorque () const
 
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > getTorqueUnits () const
 
::rl::math::Vector getSpeed () const
 
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > getSpeedUnits () const
 
::rl::math::Vector getVelocity () const
 
::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1 > getVelocityUnits () const
 
bool isColliding (const ::std::size_t &i) const
 
void replace (Compound *compound, Transform *transform)
 
void replace (Transform *transform, Compound *compound)
 
void remove (Compound *compound)
 
void remove (Frame *frame)
 
void remove (Transform *transform)
 
void setAcceleration (const ::rl::math::Vector &qdd)
 
void setGammaPosition (const ::rl::math::Matrix &gammaPosition)
 
void setGammaVelocity (const ::rl::math::Matrix &gammaVelocity)
 
void setHomePosition (const ::rl::math::Vector &home)
 
void setManufacturer (const ::std::string &manufacturer)
 
void setName (const ::std::string &name)
 
void setOperationalVelocity (const ::std::size_t &i, const ::rl::math::MotionVector &v) const
 
void setPosition (const ::rl::math::Vector &q)
 
void setTorque (const ::rl::math::Vector &tau)
 
void setVelocity (const ::rl::math::Vector &qd)
 
::rl::math::Transformtool (const ::std::size_t &i=0)
 
const ::rl::math::Transformtool (const ::std::size_t &i=0) const
 
::rl::math::Transformworld ()
 
const ::rl::math::Transformworld () const
 

Protected Attributes

::rl::math::Vector G
 Gravity vector. More...
 
::rl::math::Matrix invM
 Joint space mass matrix inverse. More...
 
::rl::math::Matrix invMx
 Operational space mass matrix inverse. More...
 
::rl::math::Matrix M
 Joint space mass matrix. More...
 
::rl::math::Vector V
 Centrifugal and Coriolis vector. More...
 
- Protected Attributes inherited from rl::mdl::Kinematic
::rl::math::Matrix invJ
 Jacobian matrix inverse. More...
 
::rl::math::Matrix J
 Jacobian matrix. More...
 
::rl::math::Vector Jdqd
 Jacobian derivative vector. More...
 
- Protected Attributes inherited from rl::mdl::Model
::std::vector< Body * > bodies
 
::std::vector< Element * > elements
 
::std::vector< Frame * > frames
 
::rl::math::Matrix gammaPosition
 
::rl::math::Matrix gammaVelocity
 
::rl::math::Vector home
 
::rl::math::Matrix invGammaPosition
 
::rl::math::Matrix invGammaVelocity
 
::std::vector< Joint * > joints
 
::std::vector< Vertexleaves
 
::std::string manufacturer
 
::std::string name
 
Vertex root
 
::std::vector< Edgetools
 
::std::vector< Transform * > transforms
 
Tree tree
 

Additional Inherited Members

- Protected Types inherited from rl::mdl::Model
typedef ::boost::adjacency_list< ::boost::listS, ::boost::listS, ::boost::bidirectionalS, ::boost::property< ::boost::vertex_color_t, Compound *, ::std::shared_ptr< Frame > >, ::boost::property< ::boost::edge_weight_t, Compound *, ::std::shared_ptr< Transform > >, ::boost::no_property, ::boost::listS > Tree
 
typedef ::boost::graph_traits< Tree >::edge_descriptor Edge
 
typedef ::boost::graph_traits< Tree >::edge_iterator EdgeIterator
 
typedef ::std::pair< EdgeIterator, EdgeIteratorEdgeIteratorPair
 
typedef ::boost::graph_traits< Tree >::in_edge_iterator InEdgeIterator
 
typedef ::std::pair< InEdgeIterator, InEdgeIteratorInEdgeIteratorPair
 
typedef ::boost::graph_traits< Tree >::out_edge_iterator OutEdgeIterator
 
typedef ::std::pair< OutEdgeIterator, OutEdgeIteratorOutEdgeIteratorPair
 
typedef ::boost::graph_traits< Tree >::vertex_descriptor Vertex
 
typedef ::boost::graph_traits< Tree >::vertex_iterator VertexIterator
 
typedef ::std::pair< VertexIterator, VertexIteratorVertexIteratorPair
 
- Protected Member Functions inherited from rl::mdl::Model
void update (const Vertex &u)
 

Constructor & Destructor Documentation

◆ Dynamic()

rl::mdl::Dynamic::Dynamic ( )

◆ ~Dynamic()

rl::mdl::Dynamic::~Dynamic ( )
virtual

Member Function Documentation

◆ calculateCentrifugalCoriolis() [1/2]

void rl::mdl::Dynamic::calculateCentrifugalCoriolis ( )

Calculate centrifugal and Coriolis vector.

Precondition
setPosition()
setVelocity()
Postcondition
getCentrifugalCoriolis()
See also
inverseDynamics()

◆ calculateCentrifugalCoriolis() [2/2]

void rl::mdl::Dynamic::calculateCentrifugalCoriolis ( ::rl::math::Vector V)

Calculate centrifugal and Coriolis vector.

Parameters
[out]VCentrifugal and Coriolis vector \(\vec{V}(\vec{q}, \dot{\vec{q}})\)
Precondition
setPosition()
setVelocity()
See also
inverseDynamics()

◆ calculateGravity() [1/2]

void rl::mdl::Dynamic::calculateGravity ( )

Calculate gravity vector.

Precondition
setPosition()
Postcondition
getGravity()
See also
inverseDynamics()

◆ calculateGravity() [2/2]

void rl::mdl::Dynamic::calculateGravity ( ::rl::math::Vector G)

Calculate gravity vector.

Parameters
[out]GGravity vector \(\vec{G}(\vec{q})\)
Precondition
setPosition()
See also
inverseDynamics()

◆ calculateMassMatrix() [1/2]

void rl::mdl::Dynamic::calculateMassMatrix ( )

Calculate joint space mass matrix.

Precondition
setPosition()
Postcondition
getMassMatrix()
See also
inverseDynamics()

◆ calculateMassMatrix() [2/2]

void rl::mdl::Dynamic::calculateMassMatrix ( ::rl::math::Matrix M)

Calculate joint space mass matrix.

Parameters
[out]MJoint space mass matrix \(\matr{M}^{-1}(\vec{q})\)
Precondition
setPosition()
See also
inverseDynamics()

◆ calculateMassMatrixInverse() [1/2]

void rl::mdl::Dynamic::calculateMassMatrixInverse ( )

Calculate joint space mass matrix inverse.

Precondition
setPosition()
Postcondition
getMassMatrixInverse()
See also
forwardDynamics()

◆ calculateMassMatrixInverse() [2/2]

void rl::mdl::Dynamic::calculateMassMatrixInverse ( ::rl::math::Matrix invM)

Calculate joint space mass matrix inverse.

Parameters
[out]invMJoint space mass matrix inverse \(\matr{M}^{-1}(\vec{q})\)
Precondition
setPosition()
See also
forwardDynamics()

◆ calculateOperationalMassMatrixInverse() [1/2]

void rl::mdl::Dynamic::calculateOperationalMassMatrixInverse ( )

Calculate operational space mass matrix inverse.

Precondition
setPosition()
calculateJacobian()
calculateMassMatrix()
calculateMassMatrixInverse()
Postcondition
getOperationalMassMatrixInverse()

◆ calculateOperationalMassMatrixInverse() [2/2]

void rl::mdl::Dynamic::calculateOperationalMassMatrixInverse ( const ::rl::math::Matrix J,
const ::rl::math::Matrix invM,
::rl::math::Matrix invMx 
) const

Calculate operational space mass matrix inverse.

Parameters
[in]JJacobian matrix \(\matr{J}(\vec{q})\)
[in]invMJoint space mass matrix inverse \(\matr{M}^{-1}(\vec{q})\)
[out]invMxOperational space mass matrix inverse \(\matr{M}_{\mathrm{x}}^{-1}(\vec{q})\)

◆ clone()

Model * rl::mdl::Dynamic::clone ( ) const

◆ eulerCauchy()

void rl::mdl::Dynamic::eulerCauchy ( const ::rl::math::Real dt)

Integration via Euler-Cauchy.

\[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} \]

\[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \Delta t \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \]

\[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \]

\[ t_{i + 1} = t_{i} + \Delta t \]

Parameters
[in]dtIntegration time step \(\Delta t\)
Precondition
setPosition()
setVelocity()
setTorque()
Postcondition
getPosition()
getVelocity()
getAcceleration()
See also
forwardDynamics

◆ forwardDynamics()

void rl::mdl::Dynamic::forwardDynamics ( )

Forward dynamics via articulated-body algorithm.

\[ \ddot{\vec{q}} = \matr{M}^{-1}(\vec{q}) \, \bigl( \vec{\tau} - \vec{C}(\vec{q}, \dot{\vec{q}}) - \vec{V}(\vec{q}) \bigr) \]

Precondition
setPosition()
setVelocity()
setTorque()
Postcondition
getAcceleration()

◆ getCentrifugalCoriolis()

const ::rl::math::Vector & rl::mdl::Dynamic::getCentrifugalCoriolis ( ) const

Access calculated centrifugal and Coriolis vector.

Returns
Centrifugal and Coriolis vector \(\vec{V}(\vec{q}, \dot{\vec{q}})\)
Precondition
setPosition()
setVelocity()

◆ getGravity()

const ::rl::math::Vector & rl::mdl::Dynamic::getGravity ( ) const

Access calculated gravity vector.

Returns
Gravity vector \(\vec{G}(\vec{q})\)
Precondition
setPosition()
setWorldGravity()

◆ getMassMatrix()

const ::rl::math::Matrix & rl::mdl::Dynamic::getMassMatrix ( ) const

Access calculated joint space mass matrix.

Returns
Joint space mass matrix \(\matr{M}(\vec{q})\)
Precondition
setPosition()

◆ getMassMatrixInverse()

const ::rl::math::Matrix & rl::mdl::Dynamic::getMassMatrixInverse ( ) const

Access calculated joint space mass matrix inverse.

Returns
Joint space mass matrix inverse \(\matr{M}^{-1}(\vec{q})\)
Precondition
setPosition()
calculateJacobian()
calculateMassMatrix()
calculateMassMatrixInverse()

◆ getOperationalMassMatrixInverse()

const ::rl::math::Matrix & rl::mdl::Dynamic::getOperationalMassMatrixInverse ( ) const

Access calculated operational space mass matrix inverse.

Returns
Operational space mass matrix inverse \(\matr{M}_{\mathrm{x}}^{-1}(\vec{q})\)
Precondition
setPosition()
calculateJacobian()
calculateMassMatrix()
calculateMassMatrixInverse()
calculateOperationalMassMatrixInverse()

◆ getWorldGravity() [1/2]

void rl::mdl::Dynamic::getWorldGravity ( ::rl::math::Real x,
::rl::math::Real y,
::rl::math::Real z 
) const

◆ getWorldGravity() [2/2]

void rl::mdl::Dynamic::getWorldGravity ( ::rl::math::Vector xyz) const

◆ inverseDynamics()

void rl::mdl::Dynamic::inverseDynamics ( )

Inverse dynamics via recursive Newton-Euler algorithm.

\[ \vec{\tau} = \matr{M}(\vec{q}) \, \ddot{\vec{q}} + \vec{C}(\vec{q}, \dot{\vec{q}}) + \vec{G}(\vec{q}) \]

Precondition
setPosition()
setVelocity()
setAcceleration()
Postcondition
getTorque()

◆ inverseForce()

void rl::mdl::Dynamic::inverseForce ( )

◆ rungeKuttaNystrom()

void rl::mdl::Dynamic::rungeKuttaNystrom ( const ::rl::math::Real dt)

Integration via Runge-Kutta-Nyström.

\[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \frac{\Delta t}{3} (\vec{k}_{1} + \vec{k}_{2} + \vec{k}_{3}) \]

\[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \frac{1}{3} (\vec{k}_{1} + 2 \vec{k}_{2} + 2 \vec{k}_{3} + \vec{k}_{4}) \]

\[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \]

\[ t_{i + 1} = t_{i} + \Delta t \]

\[ \vec{k}_{1} = \frac{\Delta t}{2} \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \]

\[ \vec{k}_{2} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{1}) \]

\[ \vec{k}_{3} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{2}) \]

\[ \vec{k}_{4} = \frac{\Delta t}{2} \, f(t_{i} + \Delta t, \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \Delta t \, \vec{k}_{3}, \dot{\vec{q}}_{i} + 2 \vec{k}_{3}) \]

Parameters
[in]dtIntegration time step \(\Delta t\)
Precondition
setPosition()
setVelocity()
setTorque()
Postcondition
getPosition()
getVelocity()
getAcceleration()
See also
forwardDynamics()

◆ setWorldGravity() [1/2]

void rl::mdl::Dynamic::setWorldGravity ( const ::rl::math::Real x,
const ::rl::math::Real y,
const ::rl::math::Real z 
)

◆ setWorldGravity() [2/2]

void rl::mdl::Dynamic::setWorldGravity ( const ::rl::math::Vector xyz)

◆ update()

void rl::mdl::Dynamic::update ( )
virtual

Reimplemented from rl::mdl::Kinematic.

Member Data Documentation

◆ G

::rl::math::Vector rl::mdl::Dynamic::G
protected

Gravity vector.

\[ \vec{G}(\vec{q}) \]

Precondition
calculateGravity()
See also
getGravity()

◆ invM

::rl::math::Matrix rl::mdl::Dynamic::invM
protected

Joint space mass matrix inverse.

\[ \matr{M}^{-1}(\vec{q}) \]

Precondition
calculateMassMatrixInverse()
See also
getMassMatrixInverse()

◆ invMx

::rl::math::Matrix rl::mdl::Dynamic::invMx
protected

Operational space mass matrix inverse.

\[ \matr{M}_{\mathrm{x}}^{-1}(\vec{q}) \]

Precondition
calculateOperationalMassMatrixInverse()
See also
getOperationalMassMatrixInverse()

◆ M

::rl::math::Matrix rl::mdl::Dynamic::M
protected

Joint space mass matrix.

\[ \matr{M}(\vec{q}) \]

Precondition
calculateMassMatrix()
See also
getMassMatrix()

◆ V

::rl::math::Vector rl::mdl::Dynamic::V
protected

Centrifugal and Coriolis vector.

\[ \vec{V}(\vec{q}, \dot{\vec{q}}) \]

Precondition
calculateCentrifugalCoriolis()
See also
getCentrifugalCoriolis()

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