This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain. More...
#include <chainfksolver.hpp>
Public Member Functions | |
virtual int | JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1)=0 |
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates. | |
virtual | ~ChainFkSolverVel () |
This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain.
Definition at line 64 of file chainfksolver.hpp.
virtual KDL::ChainFkSolverVel::~ChainFkSolverVel | ( | ) | [inline, virtual] |
Definition at line 78 of file chainfksolver.hpp.
virtual int KDL::ChainFkSolverVel::JntToCart | ( | const JntArrayVel & | q_in, | |
FrameVel & | out, | |||
int | segmentNr = -1 | |||
) | [pure virtual] |
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates.
q_in | input joint coordinates (position and velocity) | |
out | output cartesian coordinates (position and velocity) | |
segmentNr | default to -1 |
Implemented in KDL::ChainFkSolverVel_recursive.