#include <chainiksolverpos_nr_jl.hpp>
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.
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.
chain | the chain to calculate the inverse position for |
q_min | the minimum joint positions |
q_max | the maximum 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) |
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.
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) |
Definition at line 41 of file chainiksolverpos_nr_jl.cpp.
Definition at line 111 of file chainiksolverpos_nr_jl.cpp.
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.
q_init | Initial guess for the joint values. |
p_in | The input pose of the chain tip. |
q_out | The resulting output joint values |
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.
q_min | minimum values for the joints |
q_max | maximum values for the joints |
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
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.
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.
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.
Definition at line 117 of file chainiksolverpos_nr_jl.hpp.
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.