24 #ifndef KDLCHAINIKSOLVERPOS_NR_JL_HPP 25 #define KDLCHAINIKSOLVERPOS_NR_JL_HPP
This abstract class encapsulates the inverse position solver for a KDL::Chain.
int setJointLimits(const JntArray &q_min, const JntArray &q_max)
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
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.
This class represents an fixed size array containing joint values of a KDL::Chain.
represents both translational and rotational velocities.
static const int E_FKSOLVERPOS_FAILED
Child IK solver vel failed.
ChainIkSolverVel & iksolver
const char * strError(const int error) const
represents a frame transformation in 3D space (rotation + translation)
~ChainIkSolverPos_NR_JL()
int error
Latest error, initialized to E_NOERROR in constructor.
virtual void updateInternalDataStructures()
ChainFkSolverPos & fksolver
virtual int CartToJnt(const JntArray &q_init, const Frame &p_in, JntArray &q_out)
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain...
static const int E_IKSOLVERVEL_FAILED