This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain. More...
#include <chainfksolver.hpp>
Public Member Functions | |
virtual int | JntToCart (const JntArray &q_in, Frame &p_out, int segmentNr=-1)=0 |
Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose. | |
virtual | ~ChainFkSolverPos () |
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain.
Definition at line 42 of file chainfksolver.hpp.
virtual KDL::ChainFkSolverPos::~ChainFkSolverPos | ( | ) | [inline, virtual] |
Definition at line 55 of file chainfksolver.hpp.
virtual int KDL::ChainFkSolverPos::JntToCart | ( | const JntArray & | q_in, | |
Frame & | p_out, | |||
int | segmentNr = -1 | |||
) | [pure virtual] |
Calculate forward position kinematics for a KDL::Chain, from joint coordinates to cartesian pose.
q_in | input joint coordinates | |
p_out | reference to output cartesian pose | |
segmentNr | default to -1 |
Implemented in KDL::ChainFkSolverPos_recursive.
Referenced by KDL::ChainIkSolverPos_NR_JL::CartToJnt(), and KDL::ChainIkSolverPos_NR::CartToJnt().