Public Member Functions | Static Public Attributes | Private Attributes | List of all members
KDL::ChainIkSolverPos_NR_JL Class Reference

#include <chainiksolverpos_nr_jl.hpp>

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

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. More...
 
 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
 
virtual void updateInternalDataStructures ()
 
 ~ChainIkSolverPos_NR_JL ()
 
- Public Member Functions inherited from KDL::ChainIkSolverPos
virtual ~ChainIkSolverPos ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 Return the latest error. More...
 
 SolverI ()
 Initialize latest error to E_NOERROR. More...
 
virtual ~SolverI ()
 

Static Public Attributes

static const int E_FKSOLVERPOS_FAILED = -101
 Child IK solver vel failed. More...
 
static const int E_IKSOLVERVEL_FAILED = -100
 

Private Attributes

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

Additional Inherited Members

- Public Types inherited from KDL::SolverI
enum  {
  E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2,
  E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6,
  E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8
}
 
- Protected Attributes inherited from KDL::SolverI
int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

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.

KDL::ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL ( )

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

void KDL::ChainIkSolverPos_NR_JL::updateInternalDataStructures ( )
virtual

Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::ChainIkSolverPos.

Definition at line 53 of file chainiksolverpos_nr_jl.cpp.

Member Data Documentation

const Chain& KDL::ChainIkSolverPos_NR_JL::chain
private

Definition at line 112 of file chainiksolverpos_nr_jl.hpp.

JntArray KDL::ChainIkSolverPos_NR_JL::delta_q
private

Definition at line 118 of file chainiksolverpos_nr_jl.hpp.

Twist KDL::ChainIkSolverPos_NR_JL::delta_twist
private

Definition at line 123 of file chainiksolverpos_nr_jl.hpp.

const int KDL::ChainIkSolverPos_NR_JL::E_FKSOLVERPOS_FAILED = -101
static

Child IK solver vel failed.

Definition at line 45 of file chainiksolverpos_nr_jl.hpp.

const int KDL::ChainIkSolverPos_NR_JL::E_IKSOLVERVEL_FAILED = -100
static

Definition at line 44 of file chainiksolverpos_nr_jl.hpp.

double KDL::ChainIkSolverPos_NR_JL::eps
private

Definition at line 120 of file chainiksolverpos_nr_jl.hpp.

Frame KDL::ChainIkSolverPos_NR_JL::f
private

Definition at line 122 of file chainiksolverpos_nr_jl.hpp.

ChainFkSolverPos& KDL::ChainIkSolverPos_NR_JL::fksolver
private

Definition at line 117 of file chainiksolverpos_nr_jl.hpp.

ChainIkSolverVel& KDL::ChainIkSolverPos_NR_JL::iksolver
private

Definition at line 116 of file chainiksolverpos_nr_jl.hpp.

unsigned int KDL::ChainIkSolverPos_NR_JL::maxiter
private

Definition at line 119 of file chainiksolverpos_nr_jl.hpp.

unsigned int KDL::ChainIkSolverPos_NR_JL::nj
private

Definition at line 113 of file chainiksolverpos_nr_jl.hpp.

JntArray KDL::ChainIkSolverPos_NR_JL::q_max
private

Definition at line 115 of file chainiksolverpos_nr_jl.hpp.

JntArray KDL::ChainIkSolverPos_NR_JL::q_min
private

Definition at line 114 of file chainiksolverpos_nr_jl.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44