Robotics Library  0.6.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
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]
Collaboration diagram for rl::mdl::Kinematic:
Collaboration graph
[legend]

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Kinematic ()
 
virtual ~Kinematic ()
 
Modelclone () const
 
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
 
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 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
 
Modelclone () 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::Matrix invJ
 
::rl::math::Matrix J
 
::rl::math::Vector Jdqd
 

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 *,::boost::shared_ptr
< Frame > >,::boost::property
< ::boost::edge_weight_t,
Compound *,::boost::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, EdgeIterator
EdgeIteratorPair
 
typedef ::boost::graph_traits
< Tree >::in_edge_iterator 
InEdgeIterator
 
typedef ::std::pair
< InEdgeIterator,
InEdgeIterator
InEdgeIteratorPair
 
typedef ::boost::graph_traits
< Tree >::out_edge_iterator 
OutEdgeIterator
 
typedef ::std::pair
< OutEdgeIterator,
OutEdgeIterator
OutEdgeIteratorPair
 
typedef ::boost::graph_traits
< Tree >::vertex_descriptor 
Vertex
 
typedef ::boost::graph_traits
< Tree >::vertex_iterator 
VertexIterator
 
typedef ::std::pair
< VertexIterator,
VertexIterator
VertexIteratorPair
 
- Protected Member Functions inherited from rl::mdl::Model
void update (const Vertex &u)
 

Constructor & Destructor Documentation

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

Member Function Documentation

bool rl::mdl::Kinematic::calculateInversePosition ( const ::rl::math::Transform x,
const ::std::size_t &  iterations = 1000 
)

Resolved motion rate control.

Precondition
setPosition()
Postcondition
getPosition()
Side Effects:
calculateJacobian()

calculateJacobianInverse()
void rl::mdl::Kinematic::calculateJacobian ( )
void rl::mdl::Kinematic::calculateJacobian ( ::rl::math::Matrix J)

Calculate Jacobian matrix.

Precondition
setPosition()
Side Effects:
setVelocity()

forwardVelocity()
void rl::mdl::Kinematic::calculateJacobianDerivative ( )
void rl::mdl::Kinematic::calculateJacobianDerivative ( ::rl::math::Vector Jdqd)

Calculate Jacobian derivative matrix.

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

forwardVelocity()

forwardAcceleration()
void rl::mdl::Kinematic::calculateJacobianInverse ( const ::rl::math::Real lambda = 0.0f,
const bool &  doSvd = true 
)
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.

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

Calculate manipulability measure.

Precondition
calculateJacobian()
rl::math::Real rl::mdl::Kinematic::calculateManipulabilityMeasure ( const ::rl::math::Matrix J) const
Model * rl::mdl::Kinematic::clone ( ) const
void rl::mdl::Kinematic::forwardAcceleration ( )
void rl::mdl::Kinematic::forwardPosition ( )
Precondition
setPosition()
Postcondition
getOperationalPosition()
void rl::mdl::Kinematic::forwardVelocity ( )
const ::rl::math::Matrix & rl::mdl::Kinematic::getJacobian ( ) const
const ::rl::math::Vector & rl::mdl::Kinematic::getJacobianDerivative ( ) const
const ::rl::math::Matrix & rl::mdl::Kinematic::getJacobianInverse ( ) const
void rl::mdl::Kinematic::inverseVelocity ( const ::rl::math::Real lambda = 1)
bool rl::mdl::Kinematic::isSingular ( ) const

Check if current configuration is singular.

Precondition
calculateJacobian()
bool rl::mdl::Kinematic::isSingular ( const ::rl::math::Matrix J) const
void rl::mdl::Kinematic::update ( )
virtual

Reimplemented from rl::mdl::Model.

Reimplemented in rl::mdl::Dynamic.

Member Data Documentation

::rl::math::Matrix rl::mdl::Kinematic::invJ
protected
::rl::math::Matrix rl::mdl::Kinematic::J
protected
::rl::math::Vector rl::mdl::Kinematic::Jdqd
protected

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