24 #ifndef KDLCHAINIKSOLVERPOS_NR_JL_HPP 25 #define KDLCHAINIKSOLVERPOS_NR_JL_HPP unsigned int nj
Definition: chainiksolverpos_nr_jl.hpp:113
This abstract class encapsulates the inverse position solver for a KDL::Chain.
Definition: chainiksolver.hpp:42
int setJointLimits(const JntArray &q_min, const JntArray &q_max)
Function to set the joint limits.
Definition: chainiksolverpos_nr_jl.cpp:103
Twist delta_twist
Definition: chainiksolverpos_nr_jl.hpp:123
This class encapsulates a serial kinematic interconnection structure.
Definition: chain.hpp:35
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.
Definition: chainiksolverpos_nr_jl.cpp:30
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
Frame f
Definition: chainiksolverpos_nr_jl.hpp:122
represents both translational and rotational velocities.
Definition: frames.hpp:720
const Chain & chain
Definition: chainiksolverpos_nr_jl.hpp:112
JntArray q_min
Definition: chainiksolverpos_nr_jl.hpp:114
Definition: articulatedbodyinertia.cpp:28
JntArray delta_q
Definition: chainiksolverpos_nr_jl.hpp:118
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations ...
Definition: chainiksolverpos_nr_jl.hpp:40
const char * strError(const int error) const
Return a description of the latest error.
Definition: chainiksolverpos_nr_jl.cpp:115
static const int E_FKSOLVERPOS_FAILED
Child IK solver vel failed.
Definition: chainiksolverpos_nr_jl.hpp:45
ChainIkSolverVel & iksolver
Definition: chainiksolverpos_nr_jl.hpp:116
unsigned int maxiter
Definition: chainiksolverpos_nr_jl.hpp:119
double eps
Definition: chainiksolverpos_nr_jl.hpp:120
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
~ChainIkSolverPos_NR_JL()
Definition: chainiksolverpos_nr_jl.cpp:111
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
virtual void updateInternalDataStructures()
Update the internal data structures.
Definition: chainiksolverpos_nr_jl.cpp:53
ChainFkSolverPos & fksolver
Definition: chainiksolverpos_nr_jl.hpp:117
JntArray q_max
Definition: chainiksolverpos_nr_jl.hpp:115
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
Calculates the joint values that correspond to the input pose given an initial guess.
Definition: chainiksolverpos_nr_jl.cpp:62
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition: chainiksolver.hpp:66
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain...
Definition: chainfksolver.hpp:41
static const int E_IKSOLVERVEL_FAILED
Definition: chainiksolverpos_nr_jl.hpp:44