KDL  1.3.0
Public Types | Public Member Functions | Protected Attributes | Private Attributes | List of all members
KDL::ChainFkSolverVel_recursive Class Reference

Implementation of a recursive forward position and velocity kinematics algorithm to calculate the position and velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain). More...

#include <src/chainfksolvervel_recursive.hpp>

Inheritance diagram for KDL::ChainFkSolverVel_recursive:
Inheritance graph
[legend]
Collaboration diagram for KDL::ChainFkSolverVel_recursive:
Collaboration graph
[legend]

Public Types

enum  { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2 }
 

Public Member Functions

 ChainFkSolverVel_recursive (const Chain &chain)
 
 ~ChainFkSolverVel_recursive ()
 
virtual int JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1)
 Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates. More...
 
virtual int getError () const
 Return the latest error. More...
 
virtual const char * strError (const int error) const
 Return a description of the latest error. More...
 

Protected Attributes

int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

Private Attributes

const Chain chain
 

Detailed Description

Implementation of a recursive forward position and velocity kinematics algorithm to calculate the position and velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).

Member Enumeration Documentation

anonymous enum
inherited
Enumerator
E_DEGRADED 

Converged but degraded solution (e.g. WDLS with psuedo-inverse singular)

E_NOERROR 

No error.

E_NO_CONVERGE 

Failed to converge.

E_UNDEFINED 

Undefined value (e.g. computed a NAN, or tan(90 degrees) )

Constructor & Destructor Documentation

KDL::ChainFkSolverVel_recursive::ChainFkSolverVel_recursive ( const Chain chain)
KDL::ChainFkSolverVel_recursive::~ChainFkSolverVel_recursive ( )

Member Function Documentation

virtual int KDL::SolverI::getError ( ) const
inlinevirtualinherited

Return the latest error.

References KDL::SolverI::error.

int KDL::ChainFkSolverVel_recursive::JntToCart ( const JntArrayVel q_in,
FrameVel out,
int  segmentNr = -1 
)
virtual

Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates.

Parameters
q_ininput joint coordinates (position and velocity)
outoutput cartesian coordinates (position and velocity)
Returns
if < 0 something went wrong

Implements KDL::ChainFkSolverVel.

References chain, KDL::Segment::getJoint(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), KDL::Joint::getType(), KDL::FrameVel::Identity(), KDL::Joint::None, KDL::Segment::pose(), KDL::JntArrayVel::q, KDL::JntArrayVel::qdot, and KDL::Segment::twist().

virtual const char* KDL::SolverI::strError ( const int  error) const
inlinevirtualinherited

Member Data Documentation

const Chain KDL::ChainFkSolverVel_recursive::chain
private

Referenced by JntToCart().

int KDL::SolverI::error
protectedinherited

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