KDL
1.3.0
|
This abstract class encapsulates the inverse velocity solver for a KDL::Chain. More...
#include <src/chainiksolver.hpp>
Public Types | |
enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2 } |
Public Member Functions | |
virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)=0 |
Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities. More... | |
virtual int | CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)=0 |
Calculate inverse position and velocity kinematics, from cartesian position and velocity to joint positions and velocities. More... | |
virtual | ~ChainIkSolverVel () |
virtual int | getError () const |
Return the latest error. More... | |
virtual const char * | strError (const int error) const |
Return a description of the latest error. More... | |
Protected Attributes | |
int | error |
Latest error, initialized to E_NOERROR in constructor. More... | |
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
|
inherited |
|
inlinevirtual |
|
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.
Referenced by KDL::ChainIkSolverPos_NR_JL::CartToJnt(), and KDL::ChainIkSolverPos_NR::CartToJnt().
|
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.
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
inlinevirtualinherited |
Return a description of the latest error.
Reimplemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverPos_NR, and KDL::ChainJntToJacSolver.
References KDL::SolverI::E_NO_CONVERGE, and KDL::SolverI::E_NOERROR.
Referenced by KDL::ChainJntToJacSolver::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverVel_pinv::strError(), and KDL::ChainIkSolverVel_wdls::strError().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::SolverI::getError(), KDL::ChainIkSolverVel_pinv::getSVDResult(), KDL::ChainIkSolverVel_wdls::getSVDResult(), and KDL::ChainJntToJacSolver::JntToJac().