Implementation of a recursive forward position kinematics algorithm to calculate the position transformation from joint space to Cartesian space of a general kinematic tree (KDL::Tree). More...
#include <treefksolverpos_recursive.hpp>
Public Member Functions | |
virtual int | JntToCart (const JntArray &q_in, Frame &p_out, std::string segmentName) |
Calculate forward position kinematics for a KDL::Tree, from joint coordinates to cartesian pose. | |
TreeFkSolverPos_recursive (const Tree &tree) | |
~TreeFkSolverPos_recursive () |
Implementation of a recursive forward position kinematics algorithm to calculate the position transformation from joint space to Cartesian space of a general kinematic tree (KDL::Tree).
Definition at line 37 of file treefksolverpos_recursive.hpp.
KDL::TreeFkSolverPos_recursive::TreeFkSolverPos_recursive | ( | const Tree & | tree | ) |
Definition at line 28 of file treefksolverpos_recursive.cpp.
KDL::TreeFkSolverPos_recursive::~TreeFkSolverPos_recursive | ( | ) |
Definition at line 65 of file treefksolverpos_recursive.cpp.
int KDL::TreeFkSolverPos_recursive::JntToCart | ( | const JntArray & | q_in, | |
Frame & | p_out, | |||
std::string | segmentName | |||
) | [virtual] |
Calculate forward position kinematics for a KDL::Tree, from joint coordinates to cartesian pose.
q_in | input joint coordinates | |
p_out | reference to output cartesian pose | |
segmentName |
Implements KDL::TreeFkSolverPos.
Definition at line 33 of file treefksolverpos_recursive.cpp.
References KDL::Tree::getNrOfJoints(), KDL::Tree::getSegment(), KDL::Tree::getSegments(), and KDL::JntArray::rows().