Public Member Functions | Static Public Attributes | 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)
 Child FK solver failed.
 ChainIkSolverPos_NR_JL (const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
int setJointLimits (const JntArray &q_min, const JntArray &q_max)
const char * strError (const int error) const
 ~ChainIkSolverPos_NR_JL ()

Static Public Attributes

static const int E_FKSOLVERPOS_FAILED = -101
 Child IK solver vel failed.
static const int E_IKSOLVERVEL_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
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 
)

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
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 30 of file chainiksolverpos_nr_jl.cpp.

KDL::ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL ( 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:
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 41 of file chainiksolverpos_nr_jl.cpp.

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

Calculates the joint values that correspond to the input pose given an initial guess.

Parameters:
q_initInitial guess for the joint values.
p_inThe input pose of the chain tip.
q_outThe resulting output joint values
Returns:
E_MAX_ITERATIONS_EXCEEDED if the maximum number of iterations was exceeded before a result was found E_NOT_UP_TO_DATE if the internal data is not up to date with the chain E_SIZE_MISMATCH if the size of the input/output data does not match the chain.

Implements KDL::ChainIkSolverPos.

Definition at line 53 of file chainiksolverpos_nr_jl.cpp.

int KDL::ChainIkSolverPos_NR_JL::setJointLimits ( const JntArray q_min,
const JntArray q_max 
)

Function to set the joint limits.

Parameters:
q_minminimum values for the joints
q_maxmaximum values for the joints
Returns:
E_SIZE_MISMATCH if input sizes do not match the chain

Definition at line 91 of file chainiksolverpos_nr_jl.cpp.

const char * KDL::ChainIkSolverPos_NR_JL::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 103 of file chainiksolverpos_nr_jl.cpp.


Member Data Documentation

Definition at line 109 of file chainiksolverpos_nr_jl.hpp.

Definition at line 115 of file chainiksolverpos_nr_jl.hpp.

Definition at line 120 of file chainiksolverpos_nr_jl.hpp.

Child IK solver vel failed.

Definition at line 45 of file chainiksolverpos_nr_jl.hpp.

Definition at line 44 of file chainiksolverpos_nr_jl.hpp.

Definition at line 117 of file chainiksolverpos_nr_jl.hpp.

Definition at line 119 of file chainiksolverpos_nr_jl.hpp.

Definition at line 114 of file chainiksolverpos_nr_jl.hpp.

Definition at line 113 of file chainiksolverpos_nr_jl.hpp.

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

Definition at line 116 of file chainiksolverpos_nr_jl.hpp.

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

Definition at line 110 of file chainiksolverpos_nr_jl.hpp.

Definition at line 112 of file chainiksolverpos_nr_jl.hpp.

Definition at line 111 of file chainiksolverpos_nr_jl.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