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

#include <Kinematic.h>

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

Public Member Functions

 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...
 
virtual void update ()
 
- 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::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

◆ Kinematic()

rl::mdl::Kinematic::Kinematic ( )

◆ ~Kinematic()

rl::mdl::Kinematic::~Kinematic ( )
virtual

Member Function Documentation

◆ calculateInversePosition()

bool rl::mdl::Kinematic::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.

Precondition
setPosition()
Postcondition
getPosition()
See also
calculateJacobian()
calculateJacobianInverse()

◆ calculateJacobian() [1/2]

void rl::mdl::Kinematic::calculateJacobian ( ::rl::math::Matrix J,
const bool &  inWorldFrame = true 
)

Calculate Jacobian matrix.

Parameters
[out]JJacobian matrix \(\matr{J}(\vec{q})\)
[in]inWorldFrameCalculate in world or tool frame
Precondition
setPosition()
See also
forwardVelocity()

◆ calculateJacobian() [2/2]

void rl::mdl::Kinematic::calculateJacobian ( const bool &  inWorldFrame = true)

Calculate Jacobian matrix.

Parameters
[in]inWorldFrameCalculate in world or tool frame
Precondition
setPosition()
Postcondition
getJacobian()
See also
forwardVelocity()

◆ calculateJacobianDerivative() [1/2]

void rl::mdl::Kinematic::calculateJacobianDerivative ( ::rl::math::Vector Jdqd,
const bool &  inWorldFrame = true 
)

Calculate Jacobian derivative vector.

Parameters
[out]JdqdJacobian derivative vector \(\dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}}\)
[in]inWorldFrameCalculate in world or tool frame
Precondition
setPosition()
setVelocity()
See also
forwardVelocity()
forwardAcceleration()

◆ calculateJacobianDerivative() [2/2]

void rl::mdl::Kinematic::calculateJacobianDerivative ( const bool &  inWorldFrame = true)

Calculate Jacobian derivative vector.

Parameters
[in]inWorldFrameCalculate in world or tool frame
Precondition
setPosition()
setVelocity()
Postcondition
getJacobianDerivative()
See also
forwardVelocity
forwardAcceleration

◆ calculateJacobianInverse() [1/2]

void rl::mdl::Kinematic::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.

\[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \]

\[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \]

Parameters
[in]JJacobian matrix \(\matr{J}\)
[in]invJJacobian matrix inverse \(\matr{J}^{\dagger}\)
[in]lambdaDamping factor \(\lambda\)
[in]doSvdUse singular value decomposition or damped least squares
Precondition
setPosition()
calculateJacobian()

◆ calculateJacobianInverse() [2/2]

void rl::mdl::Kinematic::calculateJacobianInverse ( const ::rl::math::Real lambda = 0.0f,
const bool &  doSvd = true 
)

Calculate Jacobian matrix inverse.

\[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \]

\[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \]

Parameters
[in]lambdaDamping factor \(\lambda\)
[in]doSvdUse singular value decomposition or damped least squares
Precondition
setPosition()
calculateJacobian()
Postcondition
getJacobianInverse()

◆ calculateManipulabilityMeasure() [1/2]

rl::math::Real rl::mdl::Kinematic::calculateManipulabilityMeasure ( ) const

Calculate manipulability measure.

\[ \mu(\vec{q}) = \sqrt{\det \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) \bigr)} \]

Returns
Manipulability measure \(\mu(\vec{q})\)
Precondition
setPosition()
calculateJacobian()

◆ calculateManipulabilityMeasure() [2/2]

rl::math::Real rl::mdl::Kinematic::calculateManipulabilityMeasure ( const ::rl::math::Matrix J) const

Calculate manipulability measure.

\[ \mu(\vec{q}) = \sqrt{\det \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) \bigr)} \]

Parameters
[in]JJacobian matrix \(\matr{J}(\vec{q})\)
Returns
Manipulability measure \(\mu(\vec{q})\)

◆ clone()

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

◆ forwardAcceleration()

void rl::mdl::Kinematic::forwardAcceleration ( )

◆ forwardPosition()

void rl::mdl::Kinematic::forwardPosition ( )
Precondition
setPosition()
Postcondition
getOperationalPosition()

◆ forwardVelocity()

void rl::mdl::Kinematic::forwardVelocity ( )

◆ getJacobian()

const ::rl::math::Matrix & rl::mdl::Kinematic::getJacobian ( ) const

Access calculated Jacobian matrix.

Returns
Jacobian matrix \(\matr{J}(\vec{q})\)
Precondition
setPosition()
calculateJacobian()

◆ getJacobianDerivative()

const ::rl::math::Vector & rl::mdl::Kinematic::getJacobianDerivative ( ) const

Access calculated Jacobian derivative vector.

Returns
Jacobian derivative vector \(\dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}}\)
Precondition
setPosition()
setVelocity()
calculateJacobianDerivative()

◆ getJacobianInverse()

const ::rl::math::Matrix & rl::mdl::Kinematic::getJacobianInverse ( ) const

Access calculated Jacobian matrix inverse.

Returns
Jacobian matrix inverse \(\matr{J}^{\dagger}(\vec{q})\)
Precondition
setPosition()
calculateJacobian()
calculateJacobianInverse()

◆ isSingular() [1/2]

bool rl::mdl::Kinematic::isSingular ( ) const

Check if current configuration is singular.

Precondition
calculateJacobian()

◆ isSingular() [2/2]

bool rl::mdl::Kinematic::isSingular ( const ::rl::math::Matrix J) const

Check if current configuration is singular.

Parameters
[in]JJacobian matrix \(\matr{J}(\vec{q})\)

◆ update()

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

Reimplemented from rl::mdl::Model.

Reimplemented in rl::mdl::Dynamic.

Member Data Documentation

◆ invJ

::rl::math::Matrix rl::mdl::Kinematic::invJ
protected

Jacobian matrix inverse.

\[ \matr{J}^{\dagger}(\vec{q}) \]

Precondition
calculateJacobianInverse()
See also
getJacobianInverse()

◆ J

::rl::math::Matrix rl::mdl::Kinematic::J
protected

Jacobian matrix.

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

Precondition
calculateJacobian()
See also
getJacobian()

◆ Jdqd

::rl::math::Vector rl::mdl::Kinematic::Jdqd
protected

Jacobian derivative vector.

\[ \dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}} \]

Precondition
calculateJacobianDerivative()
See also
getJacobianDerivative()

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