This abstract class encapsulates the inverse velocity solver for a KDL::Chain. More...
#include <chainiksolver.hpp>
Public Member Functions | |
virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0 |
virtual int | CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)=0 |
virtual void | updateInternalDataStructures ()=0 |
virtual | ~ChainIkSolverVel () |
Public Member Functions inherited from KDL::SolverI | |
virtual int | getError () const |
Return the latest error. More... | |
SolverI () | |
Initialize latest error to E_NOERROR. More... | |
virtual const char * | strError (const int error) const |
virtual | ~SolverI () |
Additional Inherited Members | |
Public Types inherited from KDL::SolverI | |
enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2, E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6, E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8 } |
Protected Attributes inherited from KDL::SolverI | |
int | error |
Latest error, initialized to E_NOERROR in constructor. More... | |
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition at line 66 of file chainiksolver.hpp.
|
inlinevirtual |
Definition at line 91 of file chainiksolver.hpp.
|
pure virtual |
Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities.
q_in | input joint positions |
v_in | input cartesian velocity |
qdot_out | output joint velocities |
Implemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverVel_pinv_nso, and KDL::ChainIkSolverVel_pinv_givens.
|
pure virtual |
Calculate inverse position and velocity kinematics, from cartesian position and velocity to joint positions and velocities.
q_init | initial joint positions |
v_in | input cartesian position and velocity |
q_out | output joint position and velocity |
Implemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverVel_pinv_nso, and KDL::ChainIkSolverVel_pinv_givens.
|
pure 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::SolverI.
Implemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv_nso, KDL::ChainIkSolverVel_pinv, and KDL::ChainIkSolverVel_pinv_givens.