Public Member Functions | 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 <chainfksolver.hpp>

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

Public Member Functions

virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)=0
 
virtual int JntToCart (const JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1)=0
 
virtual void updateInternalDataStructures ()=0
 
virtual ~ChainFkSolverPos ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 Return the latest error. More...
 
 SolverI ()
 Initialize latest error to E_NOERROR. More...
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Additional Inherited Members

- Public Types inherited from KDL::SolverI
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
}
 
- Protected Attributes inherited from KDL::SolverI
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.

Definition at line 41 of file chainfksolver.hpp.

Constructor & Destructor Documentation

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

Definition at line 65 of file chainfksolver.hpp.

Member Function Documentation

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.

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


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


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44