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

#include <chainfksolvervel_recursive.hpp>

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

Public Member Functions

 ChainFkSolverVel_recursive (const Chain &chain)
 
virtual int JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1)
 
virtual int JntToCart (const JntArrayVel &q_in, std::vector< FrameVel > &out, int segmentNr=-1)
 
virtual void updateInternalDataStructures ()
 
 ~ChainFkSolverVel_recursive ()
 
- Public Member Functions inherited from KDL::ChainFkSolverVel
virtual int JntToCart (const JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1)=0
 
virtual ~ChainFkSolverVel ()
 
- 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 and velocity kinematics algorithm to calculate the position and velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).

Definition at line 37 of file chainfksolvervel_recursive.hpp.

Constructor & Destructor Documentation

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

Definition at line 28 of file chainfksolvervel_recursive.cpp.

KDL::ChainFkSolverVel_recursive::~ChainFkSolverVel_recursive ( )

Definition at line 33 of file chainfksolvervel_recursive.cpp.

Member Function Documentation

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.

Definition at line 37 of file chainfksolvervel_recursive.cpp.

int KDL::ChainFkSolverVel_recursive::JntToCart ( const JntArrayVel q_in,
std::vector< FrameVel > &  out,
int  segmentNr = -1 
)
virtual

Definition at line 68 of file chainfksolvervel_recursive.cpp.

virtual void KDL::ChainFkSolverVel_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::ChainFkSolverVel.

Definition at line 45 of file chainfksolvervel_recursive.hpp.

Member Data Documentation

const Chain& KDL::ChainFkSolverVel_recursive::chain
private

Definition at line 45 of file chainfksolvervel_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