KDL::ChainIkSolverPos_NR_JL Class Reference

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. More...

#include <chainiksolverpos_nr_jl.hpp>

Inheritance diagram for KDL::ChainIkSolverPos_NR_JL:
KDL::ChainIkSolverPos

List of all members.

Public Member Functions

virtual int CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out)
 Calculate inverse position kinematics, from cartesian coordinates to joint coordinates.
 ChainIkSolverPos_NR_JL (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
 Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
 ~ChainIkSolverPos_NR_JL ()

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.

Takes joint limits into account.

Definition at line 40 of file chainiksolverpos_nr_jl.hpp.


Constructor & Destructor Documentation

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

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

Parameters:
chain the chain to calculate the inverse position for
q_max the maximum joint positions
q_min the minimum joint positions
fksolver a forward position kinematics solver
iksolver an inverse velocity kinematics solver
maxiter the maximum Newton-Raphson iterations, default: 100
eps the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp)
Returns:

Definition at line 37 of file chainiksolverpos_nr_jl.cpp.

KDL::ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL (  ) 

Definition at line 81 of file chainiksolverpos_nr_jl.cpp.


Member Function Documentation

int KDL::ChainIkSolverPos_NR_JL::CartToJnt ( const JntArray q_init,
const Frame p_in,
JntArray q_out 
) [virtual]

Calculate inverse position kinematics, from cartesian coordinates to joint coordinates.

Parameters:
q_init initial guess of the joint coordinates
p_in input cartesian coordinates
q_out output joint coordinates
Returns:
if < 0 something went wrong

Implements KDL::ChainIkSolverPos.

Definition at line 46 of file chainiksolverpos_nr_jl.cpp.

References KDL::Add(), KDL::ChainIkSolverVel::CartToJnt(), KDL::diff(), KDL::Equal(), KDL::ChainFkSolverPos::JntToCart(), M_PI, KDL::JntArray::rows(), and KDL::Twist::Zero().

Referenced by Robot::Robot6Axis::setTo().


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

Generated on Wed Nov 23 19:02:16 2011 for FreeCAD by  doxygen 1.6.1