Public Member Functions | Static Public Attributes | Private Attributes
KDL::ChainIkSolverPos_NR Class Reference

#include <chainiksolverpos_nr.hpp>

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

List of all members.

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.
virtual const char * strError (const int error) const
 ~ChainIkSolverPos_NR ()

Static Public Attributes

static const int E_FKSOLVERPOS_FAILED = -101
 Child IK solver vel failed.
static const int E_IKSOLVER_FAILED = -100

Private Attributes

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

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.

Definition at line 60 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 35 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 64 of file chainiksolverpos_nr.cpp.


Member Data Documentation

Definition at line 80 of file chainiksolverpos_nr.hpp.

Definition at line 84 of file chainiksolverpos_nr.hpp.

Definition at line 86 of file chainiksolverpos_nr.hpp.

Child IK solver vel failed.

Definition at line 42 of file chainiksolverpos_nr.hpp.

Definition at line 41 of file chainiksolverpos_nr.hpp.

Definition at line 89 of file chainiksolverpos_nr.hpp.

Definition at line 85 of file chainiksolverpos_nr.hpp.

Definition at line 83 of file chainiksolverpos_nr.hpp.

Definition at line 82 of file chainiksolverpos_nr.hpp.

unsigned int KDL::ChainIkSolverPos_NR::maxiter [private]

Definition at line 88 of file chainiksolverpos_nr.hpp.

unsigned int KDL::ChainIkSolverPos_NR::nj [private]

Definition at line 81 of file chainiksolverpos_nr.hpp.


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


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:29