|
KDL
1.5.1
|
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 <src/treefksolverpos_recursive.hpp>


Public Member Functions | |
| TreeFkSolverPos_recursive (const Tree &tree) | |
| ~TreeFkSolverPos_recursive () | |
| 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. More... | |
Private Member Functions | |
| Frame | recursiveFk (const JntArray &q_in, const SegmentMap::const_iterator &it) |
Private Attributes | |
| const Tree | tree |
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).
| KDL::TreeFkSolverPos_recursive::TreeFkSolverPos_recursive | ( | const Tree & | tree | ) |
| KDL::TreeFkSolverPos_recursive::~TreeFkSolverPos_recursive | ( | ) |
|
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 |
Implements KDL::TreeFkSolverPos.
References KDL::Tree::getNrOfJoints(), KDL::Tree::getSegment(), KDL::Tree::getSegments(), recursiveFk(), KDL::JntArray::rows(), and tree.
|
private |
References KDL::Tree::getRootSegment(), GetTreeElementParent, GetTreeElementQNr, GetTreeElementSegment, and tree.
Referenced by JntToCart().
|
private |
Referenced by JntToCart(), and recursiveFk().
1.8.14