#include <chainiksolverpos_nr.hpp>

Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out) |
| ChainIkSolverPos_NR (const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6) | |
| Child IK solver failed. | |
| virtual const char * | strError (const int error) const |
| ~ChainIkSolverPos_NR () | |
Static Public Attributes | |
| static const int | E_IKSOLVER_FAILED = -100 |
Private Attributes | |
| const Chain | chain |
| JntArray | delta_q |
| Twist | delta_twist |
| double | eps |
| Frame | f |
| ChainFkSolverPos & | fksolver |
| ChainIkSolverVel & | iksolver |
| unsigned int | maxiter |
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.
Definition at line 38 of file chainiksolverpos_nr.hpp.
| KDL::ChainIkSolverPos_NR::ChainIkSolverPos_NR | ( | const Chain & | chain, |
| ChainFkSolverPos & | fksolver, | ||
| ChainIkSolverVel & | iksolver, | ||
| unsigned int | maxiter = 100, |
||
| double | eps = 1e-6 |
||
| ) |
Child IK 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 |
| 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 26 of file chainiksolverpos_nr.cpp.
Definition at line 54 of file chainiksolverpos_nr.cpp.
| int KDL::ChainIkSolverPos_NR::CartToJnt | ( | const JntArray & | q_init, |
| const Frame & | p_in, | ||
| JntArray & | q_out | ||
| ) | [virtual] |
Find an output joint pose q_out, given a starting joint pose q_init and a desired cartesian pose p_in
Implements KDL::ChainIkSolverPos.
Definition at line 33 of file chainiksolverpos_nr.cpp.
| const char * KDL::ChainIkSolverPos_NR::strError | ( | const int | error | ) | const [virtual] |
Return a description of the latest error
Reimplemented from KDL::SolverI.
Definition at line 58 of file chainiksolverpos_nr.cpp.
const Chain KDL::ChainIkSolverPos_NR::chain [private] |
Definition at line 79 of file chainiksolverpos_nr.hpp.
JntArray KDL::ChainIkSolverPos_NR::delta_q [private] |
Definition at line 82 of file chainiksolverpos_nr.hpp.
Twist KDL::ChainIkSolverPos_NR::delta_twist [private] |
Definition at line 84 of file chainiksolverpos_nr.hpp.
const int KDL::ChainIkSolverPos_NR::E_IKSOLVER_FAILED = -100 [static] |
Definition at line 41 of file chainiksolverpos_nr.hpp.
double KDL::ChainIkSolverPos_NR::eps [private] |
Definition at line 87 of file chainiksolverpos_nr.hpp.
Frame KDL::ChainIkSolverPos_NR::f [private] |
Definition at line 83 of file chainiksolverpos_nr.hpp.
Definition at line 81 of file chainiksolverpos_nr.hpp.
Definition at line 80 of file chainiksolverpos_nr.hpp.
unsigned int KDL::ChainIkSolverPos_NR::maxiter [private] |
Definition at line 86 of file chainiksolverpos_nr.hpp.