$search

KDL::TreeIkSolverPos_NR_JL Class Reference
[Kinematic Families]

#include <treeiksolverpos_nr_jl.hpp>

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

List of all members.

Public Member Functions

virtual double CartToJnt (const JntArray &q_init, const Frames &p_in, JntArray &q_out)
 TreeIkSolverPos_NR_JL (const Tree &tree, const std::vector< std::string > &endpoints, const JntArray &q_min, const JntArray &q_max, TreeFkSolverPos &fksolver, TreeIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
 ~TreeIkSolverPos_NR_JL ()

Private Attributes

JntArray delta_q
Twists delta_twists
std::vector< std::string > endpoints
double eps
TreeFkSolverPosfksolver
Frames frames
TreeIkSolverVeliksolver
unsigned int maxiter
JntArray q_max
JntArray q_min
const Tree tree

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::Tree. Takes joint limits into account.

Definition at line 42 of file treeiksolverpos_nr_jl.hpp.


Constructor & Destructor Documentation

KDL::TreeIkSolverPos_NR_JL::TreeIkSolverPos_NR_JL ( const Tree tree,
const std::vector< std::string > &  endpoints,
const JntArray &  q_min,
const JntArray &  q_max,
TreeFkSolverPos fksolver,
TreeIkSolverVel iksolver,
unsigned int  maxiter = 100,
double  eps = 1e-6 
)

Constructor of the solver, it needs the tree, a forward position kinematics solver and an inverse velocity kinematics solver for that tree, and a list of the segments you are interested in.

Parameters:
tree the tree to calculate the inverse position for
endpoints the list of endpoints you are interested in.
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 26 of file treeiksolverpos_nr_jl.cpp.

KDL::TreeIkSolverPos_NR_JL::~TreeIkSolverPos_NR_JL (  ) 

Definition at line 81 of file treeiksolverpos_nr_jl.cpp.


Member Function Documentation

double KDL::TreeIkSolverPos_NR_JL::CartToJnt ( const JntArray &  q_init,
const Frames 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 otherwise (>=0) remaining (weighted) distance to target

Implements KDL::TreeIkSolverPos.

Definition at line 44 of file treeiksolverpos_nr_jl.cpp.


Member Data Documentation

Definition at line 73 of file treeiksolverpos_nr_jl.hpp.

Definition at line 75 of file treeiksolverpos_nr_jl.hpp.

std::vector<std::string> KDL::TreeIkSolverPos_NR_JL::endpoints [private]

Definition at line 76 of file treeiksolverpos_nr_jl.hpp.

Definition at line 79 of file treeiksolverpos_nr_jl.hpp.

Definition at line 72 of file treeiksolverpos_nr_jl.hpp.

Definition at line 74 of file treeiksolverpos_nr_jl.hpp.

Definition at line 71 of file treeiksolverpos_nr_jl.hpp.

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

Definition at line 78 of file treeiksolverpos_nr_jl.hpp.

Definition at line 70 of file treeiksolverpos_nr_jl.hpp.

Definition at line 69 of file treeiksolverpos_nr_jl.hpp.

Definition at line 68 of file treeiksolverpos_nr_jl.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


orocos_kdl
Author(s): Ruben Smits, Erwin Aertbelien, Orocos Developers
autogenerated on Fri Mar 1 16:20:17 2013