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 | ~ChainIkSolverVel () |
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
Definition at line 64 of file chainiksolver.hpp.
virtual KDL::ChainIkSolverVel::~ChainIkSolverVel | ( | ) | [inline, virtual] |
Definition at line 89 of file chainiksolver.hpp.
virtual int KDL::ChainIkSolverVel::CartToJnt | ( | const JntArray & | q_in, |
const Twist & | v_in, | ||
JntArray & | qdot_out | ||
) | [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_nso, KDL::ChainIkSolverVel_pinv, and KDL::ChainIkSolverVel_pinv_givens.
virtual int KDL::ChainIkSolverVel::CartToJnt | ( | const JntArray & | q_init, |
const FrameVel & | v_in, | ||
JntArrayVel & | q_out | ||
) | [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_nso, KDL::ChainIkSolverVel_pinv, and KDL::ChainIkSolverVel_pinv_givens.