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

#include <chainiksolverpos_nr.hpp>

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

Public Member Functions

virtual int CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out)
 
 ChainIkSolverPos_NR (const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
 Child FK solver failed. More...
 
virtual const char * strError (const int error) const
 
virtual void updateInternalDataStructures ()
 
 ~ChainIkSolverPos_NR ()
 
- Public Member Functions inherited from KDL::ChainIkSolverPos
virtual ~ChainIkSolverPos ()
 
- 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_FKSOLVERPOS_FAILED = -101
 Child IK solver vel failed. More...
 
static const int E_IKSOLVER_FAILED = -100
 

Private Attributes

const Chainchain
 
JntArray delta_q
 
Twist delta_twist
 
double eps
 
Frame f
 
ChainFkSolverPosfksolver
 
ChainIkSolverVeliksolver
 
unsigned int maxiter
 
unsigned int nj
 

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 general inverse position kinematics algorithm based on Newton-Raphson iterations to calculate the position transformation from Cartesian to joint space of a general KDL::Chain.

Definition at line 38 of file chainiksolverpos_nr.hpp.

Constructor & Destructor Documentation

KDL::ChainIkSolverPos_NR::ChainIkSolverPos_NR ( const Chain chain,
ChainFkSolverPos fksolver,
ChainIkSolverVel iksolver,
unsigned int  maxiter = 100,
double  eps = 1e-6 
)

Child FK solver failed.

Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.

Parameters
chainthe chain to calculate the inverse position for
fksolvera forward position kinematics solver
iksolveran inverse velocity kinematics solver
maxiterthe maximum Newton-Raphson iterations, default: 100
epsthe precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp)
Returns

Definition at line 26 of file chainiksolverpos_nr.cpp.

KDL::ChainIkSolverPos_NR::~ChainIkSolverPos_NR ( )

Definition at line 70 of file chainiksolverpos_nr.cpp.

Member Function Documentation

int KDL::ChainIkSolverPos_NR::CartToJnt ( const JntArray q_init,
const Frame p_in,
JntArray q_out 
)
virtual

Find an output joint pose q_out, given a starting joint pose q_init and a desired cartesian pose p_in

Returns
: E_NOERROR=solution converged to <eps in maxiter E_DEGRADED=solution converged to <eps in maxiter, but solution is degraded in quality (e.g. pseudo-inverse in iksolver is singular) E_IKSOLVER_FAILED=velocity solver failed E_NO_CONVERGE=solution did not converge (e.g. large displacement, low iterations)

Implements KDL::ChainIkSolverPos.

Definition at line 42 of file chainiksolverpos_nr.cpp.

const char * KDL::ChainIkSolverPos_NR::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 74 of file chainiksolverpos_nr.cpp.

void KDL::ChainIkSolverPos_NR::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::ChainIkSolverPos.

Definition at line 35 of file chainiksolverpos_nr.cpp.

Member Data Documentation

const Chain& KDL::ChainIkSolverPos_NR::chain
private

Definition at line 82 of file chainiksolverpos_nr.hpp.

JntArray KDL::ChainIkSolverPos_NR::delta_q
private

Definition at line 87 of file chainiksolverpos_nr.hpp.

Twist KDL::ChainIkSolverPos_NR::delta_twist
private

Definition at line 89 of file chainiksolverpos_nr.hpp.

const int KDL::ChainIkSolverPos_NR::E_FKSOLVERPOS_FAILED = -101
static

Child IK solver vel failed.

Definition at line 42 of file chainiksolverpos_nr.hpp.

const int KDL::ChainIkSolverPos_NR::E_IKSOLVER_FAILED = -100
static

Definition at line 41 of file chainiksolverpos_nr.hpp.

double KDL::ChainIkSolverPos_NR::eps
private

Definition at line 92 of file chainiksolverpos_nr.hpp.

Frame KDL::ChainIkSolverPos_NR::f
private

Definition at line 88 of file chainiksolverpos_nr.hpp.

ChainFkSolverPos& KDL::ChainIkSolverPos_NR::fksolver
private

Definition at line 86 of file chainiksolverpos_nr.hpp.

ChainIkSolverVel& KDL::ChainIkSolverPos_NR::iksolver
private

Definition at line 85 of file chainiksolverpos_nr.hpp.

unsigned int KDL::ChainIkSolverPos_NR::maxiter
private

Definition at line 91 of file chainiksolverpos_nr.hpp.

unsigned int KDL::ChainIkSolverPos_NR::nj
private

Definition at line 84 of file chainiksolverpos_nr.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