Public Member Functions | Private Attributes | List of all members
KDL::ChainFkSolverPos_recursive Class Reference

#include <chainfksolverpos_recursive.hpp>

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

Public Member Functions

 ChainFkSolverPos_recursive (const Chain &chain)
 
virtual int JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)
 
virtual int JntToCart (const JntArray &q_in, std::vector< Frame > &p_out, int segmentNr=-1)
 
virtual void updateInternalDataStructures ()
 
 ~ChainFkSolverPos_recursive ()
 
- Public Member Functions inherited from KDL::ChainFkSolverPos
virtual int JntToCart (const JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1)=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 ()
 

Private Attributes

const Chainchain
 

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

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

Definition at line 36 of file chainfksolverpos_recursive.hpp.

Constructor & Destructor Documentation

KDL::ChainFkSolverPos_recursive::ChainFkSolverPos_recursive ( const Chain chain)

Definition at line 29 of file chainfksolverpos_recursive.cpp.

KDL::ChainFkSolverPos_recursive::~ChainFkSolverPos_recursive ( )

Definition at line 96 of file chainfksolverpos_recursive.cpp.

Member Function Documentation

int KDL::ChainFkSolverPos_recursive::JntToCart ( const JntArray q_in,
Frame p_out,
int  segmentNr = -1 
)
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

Implements KDL::ChainFkSolverPos.

Definition at line 34 of file chainfksolverpos_recursive.cpp.

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

Definition at line 60 of file chainfksolverpos_recursive.cpp.

virtual void KDL::ChainFkSolverPos_recursive::updateInternalDataStructures ( )
inlinevirtual

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

Definition at line 45 of file chainfksolverpos_recursive.hpp.

Member Data Documentation

const Chain& KDL::ChainFkSolverPos_recursive::chain
private

Definition at line 45 of file chainfksolverpos_recursive.hpp.


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


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