Robotics Library  0.6.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
Public Member Functions | Protected Attributes
rl::mdl::Dynamic Class Reference

#include <Dynamic.h>

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

List of all members.

Public Member Functions

 Dynamic ()
virtual ~Dynamic ()
void calculateCentrifugalCoriolis ()
void calculateCentrifugalCoriolis (::rl::math::Vector &V)
void calculateGravity ()
void calculateGravity (::rl::math::Vector &G)
void calculateMassMatrix ()
void calculateMassMatrix (::rl::math::Matrix &M)
void calculateMassMatrixInverse ()
void calculateMassMatrixInverse (::rl::math::Matrix &invM)
void calculateOperationalMassMatrixInverse ()
void calculateOperationalMassMatrixInverse (const ::rl::math::Matrix &J, const ::rl::math::Matrix &invM,::rl::math::Matrix &invMx) const
Modelclone () const
void eulerCauchy (const ::rl::math::Real &dt)
void forwardDynamics ()
const ::rl::math::VectorgetCentrifugalCoriolis () const
const ::rl::math::VectorgetGravity () const
const ::rl::math::MatrixgetMassMatrixInverse () const
const ::rl::math::MatrixgetMassMatrix () const
const ::rl::math::MatrixgetOperationalMassMatrixInverse () const
void getWorldGravity (::rl::math::Real &x,::rl::math::Real &y,::rl::math::Real &z) const
void getWorldGravity (::rl::math::Vector &xyz) const
void inverseDynamics ()
void inverseForce ()
void rungeKuttaNystrom (const ::rl::math::Real &dt)
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
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Kinematic ()
virtual ~Kinematic ()
bool calculateInversePosition (const ::rl::math::Transform &x, const ::std::size_t &iterations=1000)
void calculateJacobian ()
void calculateJacobian (::rl::math::Matrix &J)
void calculateJacobianDerivative ()
void calculateJacobianDerivative (::rl::math::Vector &Jdqd)
void calculateJacobianInverse (const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true)
void calculateJacobianInverse (const ::rl::math::Matrix &J,::rl::math::Matrix &invJ, const ::rl::math::Real &lambda=0.0f, const bool &doSvd=true) const
::rl::math::Real calculateManipulabilityMeasure () const
::rl::math::Real calculateManipulabilityMeasure (const ::rl::math::Matrix &J) const
void forwardAcceleration ()
void forwardPosition ()
void forwardVelocity ()
const ::rl::math::MatrixgetJacobian () const
const ::rl::math::VectorgetJacobianDerivative () const
const ::rl::math::MatrixgetJacobianInverse () const
void inverseVelocity (const ::rl::math::Real &lambda=1)
bool isSingular () const
bool isSingular (const ::rl::math::Matrix &J) const
- Public Member Functions inherited from rl::mdl::Metric
 Metric ()
virtual ~Metric ()
void clip (::rl::math::Vector &q) 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 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
- 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
void getAcceleration (::rl::math::Vector &qdd) const
::std::size_t getBodies () const
const BodygetBody (const ::std::size_t &i) const
::std::size_t getDof () const
const ::rl::math::TransformgetFrame (const ::std::size_t &i) const
const JointgetJoint (const ::std::size_t &i) 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
void getMaximum (::rl::math::Vector &max) const
void getMinimum (::rl::math::Vector &min) const
const ::std::string & getName () const
void getPosition (::rl::math::Vector &q) const
void getTorque (::rl::math::Vector &tau) const
void getSpeed (::rl::math::Vector &speed) const
void getVelocity (::rl::math::Vector &qd) 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 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
::rl::math::Matrix invM
::rl::math::Matrix invMx
::rl::math::Matrix M
::rl::math::Vector V
- Protected Attributes inherited from rl::mdl::Kinematic
::rl::math::Matrix invJ
::rl::math::Matrix J
::rl::math::Vector Jdqd

Constructor & Destructor Documentation

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

Member Function Documentation

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

Calculate centrifugal and Coriolis vector.

Precondition:
setPosition()
setVelocity()
Side Effects:
setAcceleration()

setGravity()

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

Calculate gravity vector.

Precondition:
setPosition()
setGravity()
Side Effects:
setVelocity()

setAcceleration()

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

Calculate mass matrix.

Precondition:
setPosition()
Side Effects:
setVelocity()

setGravity()

setAcceleration()

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

Calculate mass matrix inverse.

Precondition:
setPosition()
Side Effects:
setVelocity()

setGravity()

setTorque()

forwardDynamics()
void rl::mdl::Dynamic::calculateOperationalMassMatrixInverse ( )
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.

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

Reimplemented from rl::mdl::Kinematic.

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

Integrate with Euler-Cauchy.

Precondition:
setPosition()
setVelocity()
Postcondition:
getPosition()
getVelocity()
getAcceleration()
void rl::mdl::Dynamic::forwardDynamics ( )
const ::rl::math::Vector & rl::mdl::Dynamic::getCentrifugalCoriolis ( ) const
const ::rl::math::Vector & rl::mdl::Dynamic::getGravity ( ) const
const ::rl::math::Matrix & rl::mdl::Dynamic::getMassMatrix ( ) const
const ::rl::math::Matrix & rl::mdl::Dynamic::getMassMatrixInverse ( ) const
const ::rl::math::Matrix & rl::mdl::Dynamic::getOperationalMassMatrixInverse ( ) const
void rl::mdl::Dynamic::getWorldGravity ( ::rl::math::Real x,
::rl::math::Real y,
::rl::math::Real z 
) const
void rl::mdl::Dynamic::getWorldGravity ( ::rl::math::Vector xyz) const
void rl::mdl::Dynamic::inverseDynamics ( )
void rl::mdl::Dynamic::inverseForce ( )
void rl::mdl::Dynamic::rungeKuttaNystrom ( const ::rl::math::Real dt)

Integrate with Runge-Kutta-Nystrom.

Precondition:
setPosition()
setVelocity()
Postcondition:
getPosition()
getVelocity()
getAcceleration()
void rl::mdl::Dynamic::setWorldGravity ( const ::rl::math::Real x,
const ::rl::math::Real y,
const ::rl::math::Real z 
)
void rl::mdl::Dynamic::setWorldGravity ( const ::rl::math::Vector xyz)
void rl::mdl::Dynamic::update ( )
virtual

Reimplemented from rl::mdl::Kinematic.


Member Data Documentation

::rl::math::Vector rl::mdl::Dynamic::G
protected
::rl::math::Matrix rl::mdl::Dynamic::invM
protected
::rl::math::Matrix rl::mdl::Dynamic::invMx
protected
::rl::math::Matrix rl::mdl::Dynamic::M
protected
::rl::math::Vector rl::mdl::Dynamic::V
protected

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