KDL  1.4.0
Public Types | Public Member Functions | Protected Attributes | List of all members
KDL::ChainFkSolverPos Class Referenceabstract

This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain. More...

#include <src/chainfksolver.hpp>

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

Public Types

enum  {
  E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2,
  E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6,
  E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8
}
 

Public Member Functions

virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)=0
 Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose. More...
 
virtual int JntToCart (const JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1)=0
 Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose. More...
 
virtual void updateInternalDataStructures ()=0
 Update the internal data structures. More...
 
virtual ~ChainFkSolverPos ()
 
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...
 

Detailed Description

This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain.

Member Enumeration Documentation

§ anonymous enum

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) )

E_NOT_UP_TO_DATE 

Chain size changed.

E_SIZE_MISMATCH 

Input size does not match internal state.

E_MAX_ITERATIONS_EXCEEDED 

Maximum number of iterations exceeded.

E_OUT_OF_RANGE 

Requested index out of range.

E_NOT_IMPLEMENTED 

Not yet implemented.

E_SVD_FAILED 

Internal svd calculation failed.

Constructor & Destructor Documentation

§ ~ChainFkSolverPos()

virtual KDL::ChainFkSolverPos::~ChainFkSolverPos ( )
inlinevirtual

Member Function Documentation

§ getError()

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

Return the latest error.

References KDL::SolverI::error.

§ JntToCart() [1/2]

virtual int KDL::ChainFkSolverPos::JntToCart ( const JntArray q_in,
Frame p_out,
int  segmentNr = -1 
)
pure virtual

Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose.

Parameters
q_ininput joint coordinates
p_outreference to output cartesian pose
Returns
if < 0 something went wrong

Implemented in KDL::ChainFkSolverPos_recursive.

Referenced by KDL::ChainIkSolverPos_NR::CartToJnt(), and KDL::ChainIkSolverPos_NR_JL::CartToJnt().

§ JntToCart() [2/2]

virtual int KDL::ChainFkSolverPos::JntToCart ( const JntArray q_in,
std::vector< KDL::Frame > &  p_out,
int  segmentNr = -1 
)
pure virtual

Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose.

Parameters
q_ininput joint coordinates
p_outreference to a vector of output cartesian poses for all segments
Returns
if < 0 something went wrong

Implemented in KDL::ChainFkSolverPos_recursive.

§ strError()

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

§ updateInternalDataStructures()

virtual void KDL::ChainFkSolverPos::updateInternalDataStructures ( )
pure virtual

Update the internal data structures.

This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::SolverI.

Implemented in KDL::ChainFkSolverPos_recursive.

Referenced by KDL::ChainIkSolverPos_NR::updateInternalDataStructures(), and KDL::ChainIkSolverPos_NR_JL::updateInternalDataStructures().

Member Data Documentation

§ error

int KDL::SolverI::error
protectedinherited

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