22 #ifndef KDLCHAINIKSOLVERPOS_NR_HPP
23 #define KDLCHAINIKSOLVERPOS_NR_HPP
Definition: chainfksolver.hpp:41
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations ...
Definition: chainiksolverpos_nr.hpp:39
unsigned int maxiter
Definition: chainiksolverpos_nr.hpp:91
ChainIkSolverVel & iksolver
Definition: chainiksolverpos_nr.hpp:85
static const int E_FKSOLVERPOS_FAILED
Child IK solver vel failed.
Definition: chainiksolverpos_nr.hpp:42
unsigned int nj
Definition: chainiksolverpos_nr.hpp:84
double eps
Definition: chainiksolverpos_nr.hpp:92
JntArray delta_q
Definition: chainiksolverpos_nr.hpp:87
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
Find an output joint pose q_out, given a starting joint pose q_init and a desired cartesian pose p_in...
Definition: chainiksolverpos_nr.cpp:42
~ChainIkSolverPos_NR()
Definition: chainiksolverpos_nr.cpp:70
ChainIkSolverPos_NR(const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6)
Child FK solver failed.
Definition: chainiksolverpos_nr.cpp:26
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chainiksolverpos_nr.cpp:35
Twist delta_twist
Definition: chainiksolverpos_nr.hpp:89
Frame f
Definition: chainiksolverpos_nr.hpp:88
virtual const char * strError(const int error) const
Return a description of the latest error.
Definition: chainiksolverpos_nr.cpp:74
static const int E_IKSOLVER_FAILED
Definition: chainiksolverpos_nr.hpp:41
const Chain & chain
Definition: chainiksolverpos_nr.hpp:82
ChainFkSolverPos & fksolver
Definition: chainiksolverpos_nr.hpp:86
Definition: chainiksolver.hpp:42
Definition: chainiksolver.hpp:66
Definition: frames.hpp:570
Definition: jntarray.hpp:70
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
represents both translational and rotational velocities.
Definition: frames.hpp:720
Definition: articulatedbodyinertia.cpp:28