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

Inheritance diagram for KDL::ChainIkSolverPos_NR:
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 (const Chain &chain, 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 ()

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 
)

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
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 26 of file chainiksolverpos_nr.cpp.

KDL::ChainIkSolverPos_NR::~ChainIkSolverPos_NR (  ) 

Definition at line 52 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]

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 33 of file chainiksolverpos_nr.cpp.

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

Referenced by Robot::RobotAlgos::Test().


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