Public Member Functions | Private Attributes
KDL::ChainIkSolverPos_NR_JL Class Reference

#include <chainiksolverpos_nr_jl.hpp>

Inheritance diagram for KDL::ChainIkSolverPos_NR_JL:
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_JL (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
 ~ChainIkSolverPos_NR_JL ()

Private Attributes

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

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:
chainthe chain to calculate the inverse position for
q_minthe minimum joint positions
q_maxthe maximum joint positions
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 28 of file chainiksolverpos_nr_jl.cpp.

Definition at line 69 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_initinitial guess of the joint coordinates
p_ininput cartesian coordinates
q_outoutput joint coordinates
Returns:
if < 0 something went wrong

Implements KDL::ChainIkSolverPos.

Definition at line 36 of file chainiksolverpos_nr_jl.cpp.


Member Data Documentation

Definition at line 66 of file chainiksolverpos_nr_jl.hpp.

Definition at line 71 of file chainiksolverpos_nr_jl.hpp.

Definition at line 76 of file chainiksolverpos_nr_jl.hpp.

Definition at line 73 of file chainiksolverpos_nr_jl.hpp.

Definition at line 75 of file chainiksolverpos_nr_jl.hpp.

Definition at line 70 of file chainiksolverpos_nr_jl.hpp.

Definition at line 69 of file chainiksolverpos_nr_jl.hpp.

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

Definition at line 72 of file chainiksolverpos_nr_jl.hpp.

Definition at line 68 of file chainiksolverpos_nr_jl.hpp.

Definition at line 67 of file chainiksolverpos_nr_jl.hpp.


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


orocos_kdl
Author(s):
autogenerated on Wed Aug 26 2015 15:14:15