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 |
virtual int | JntToCart (const JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1)=0 |
virtual void | updateInternalDataStructures ()=0 |
virtual | ~ChainFkSolverVel () |
This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain.
Definition at line 74 of file chainfksolver.hpp.
virtual KDL::ChainFkSolverVel::~ChainFkSolverVel | ( | ) | [inline, virtual] |
Definition at line 98 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) |
Implemented in KDL::ChainFkSolverVel_recursive.
virtual int KDL::ChainFkSolverVel::JntToCart | ( | const JntArrayVel & | q_in, |
std::vector< KDL::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 for all segments (position and velocity) |
virtual void KDL::ChainFkSolverVel::updateInternalDataStructures | ( | ) | [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::ChainFkSolverVel_recursive.