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

#include <chainiksolvervel_pinv.hpp>

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

Public Member Functions

virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
 
virtual int CartToJnt (const JntArray &, const FrameVel &, JntArrayVel &)
 
 ChainIkSolverVel_pinv (const Chain &chain, double eps=0.00001, int maxiter=150)
 
unsigned int getNrZeroSigmas () const
 
int getSVDResult () const
 
virtual const char * strError (const int error) const
 
virtual void updateInternalDataStructures ()
 
 ~ChainIkSolverVel_pinv ()
 
- Public Member Functions inherited from KDL::ChainIkSolverVel
virtual ~ChainIkSolverVel ()
 
- 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 ~SolverI ()
 

Static Public Attributes

static const int E_CONVERGE_PINV_SINGULAR = +100
 solution converged but (pseudo)inverse is singular More...
 

Private Attributes

const Chainchain
 
double eps
 
Jacobian jac
 
ChainJntToJacSolver jnt2jac
 
int maxiter
 
unsigned int nj
 
unsigned int nrZeroSigmas
 
JntArray S
 
SVD_HH svd
 
int svdResult
 
JntArray tmp
 
std::vector< JntArrayU
 
std::vector< JntArrayV
 

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 inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain. It uses a svd-calculation based on householders rotations.

Definition at line 40 of file chainiksolvervel_pinv.hpp.

Constructor & Destructor Documentation

KDL::ChainIkSolverVel_pinv::ChainIkSolverVel_pinv ( const Chain chain,
double  eps = 0.00001,
int  maxiter = 150 
)
explicit

Constructor of the solver

Parameters
chainthe chain to calculate the inverse velocity kinematics for
epsif a singular value is below this value, its inverse is set to zero, default: 0.00001
maxitermaximum iterations for the svd calculation, default: 150

Definition at line 26 of file chainiksolvervel_pinv.cpp.

KDL::ChainIkSolverVel_pinv::~ChainIkSolverVel_pinv ( )

Definition at line 57 of file chainiksolvervel_pinv.cpp.

Member Function Documentation

int KDL::ChainIkSolverVel_pinv::CartToJnt ( const JntArray q_in,
const Twist v_in,
JntArray qdot_out 
)
virtual

Find an output joint velocity qdot_out, given a starting joint pose q_init and a desired cartesian velocity v_in

Returns
E_NOERROR=solution converged to <eps in maxiter E_SVD_FAILED=SVD computation failed E_CONVERGE_PINV_SINGULAR=solution converged but (pseudo)inverse is singular
Note
if E_CONVERGE_PINV_SINGULAR returned then converged and can continue motion, but have degraded solution
If E_SVD_FAILED returned, then getSvdResult() returns the error code from the SVD algorithm.

Implements KDL::ChainIkSolverVel.

Definition at line 62 of file chainiksolvervel_pinv.cpp.

virtual int KDL::ChainIkSolverVel_pinv::CartToJnt ( const JntArray ,
const FrameVel ,
JntArrayVel  
)
inlinevirtual

not (yet) implemented.

Implements KDL::ChainIkSolverVel.

Definition at line 80 of file chainiksolvervel_pinv.hpp.

unsigned int KDL::ChainIkSolverVel_pinv::getNrZeroSigmas ( ) const
inline

Retrieve the number of singular values of the jacobian that are < eps; if the number of near zero singular values is > jac.col()-jac.row(), then the jacobian pseudoinverse is singular

Definition at line 87 of file chainiksolvervel_pinv.hpp.

int KDL::ChainIkSolverVel_pinv::getSVDResult ( ) const
inline

Retrieve the latest return code from the SVD algorithm

Returns
0 if CartToJnt() not yet called, otherwise latest SVD result code.

Definition at line 93 of file chainiksolvervel_pinv.hpp.

const char * KDL::ChainIkSolverVel_pinv::strError ( const int  error) const
virtual

Return a description of the latest error

Returns
if error is known then a description of error, otherwise "UNKNOWN ERROR"

Reimplemented from KDL::SolverI.

Definition at line 132 of file chainiksolvervel_pinv.cpp.

void KDL::ChainIkSolverVel_pinv::updateInternalDataStructures ( )
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::ChainIkSolverVel.

Definition at line 43 of file chainiksolvervel_pinv.cpp.

Member Data Documentation

const Chain& KDL::ChainIkSolverVel_pinv::chain
private

Definition at line 101 of file chainiksolvervel_pinv.hpp.

const int KDL::ChainIkSolverVel_pinv::E_CONVERGE_PINV_SINGULAR = +100
static

solution converged but (pseudo)inverse is singular

Definition at line 44 of file chainiksolvervel_pinv.hpp.

double KDL::ChainIkSolverVel_pinv::eps
private

Definition at line 110 of file chainiksolvervel_pinv.hpp.

Jacobian KDL::ChainIkSolverVel_pinv::jac
private

Definition at line 104 of file chainiksolvervel_pinv.hpp.

ChainJntToJacSolver KDL::ChainIkSolverVel_pinv::jnt2jac
private

Definition at line 102 of file chainiksolvervel_pinv.hpp.

int KDL::ChainIkSolverVel_pinv::maxiter
private

Definition at line 111 of file chainiksolvervel_pinv.hpp.

unsigned int KDL::ChainIkSolverVel_pinv::nj
private

Definition at line 103 of file chainiksolvervel_pinv.hpp.

unsigned int KDL::ChainIkSolverVel_pinv::nrZeroSigmas
private

Definition at line 112 of file chainiksolvervel_pinv.hpp.

JntArray KDL::ChainIkSolverVel_pinv::S
private

Definition at line 107 of file chainiksolvervel_pinv.hpp.

SVD_HH KDL::ChainIkSolverVel_pinv::svd
private

Definition at line 105 of file chainiksolvervel_pinv.hpp.

int KDL::ChainIkSolverVel_pinv::svdResult
private

Definition at line 113 of file chainiksolvervel_pinv.hpp.

JntArray KDL::ChainIkSolverVel_pinv::tmp
private

Definition at line 109 of file chainiksolvervel_pinv.hpp.

std::vector<JntArray> KDL::ChainIkSolverVel_pinv::U
private

Definition at line 106 of file chainiksolvervel_pinv.hpp.

std::vector<JntArray> KDL::ChainIkSolverVel_pinv::V
private

Definition at line 108 of file chainiksolvervel_pinv.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