constraint_app
|
#include <mytreefksolverpos_recursive.hpp>
Public Types | |
typedef std::map< std::string, KDL::Frame > | SegmentToPoseMap |
typedef std::map< std::string, KDL::Frame > | SegmentToPoseMap |
Public Member Functions | |
MyTreeFkSolverPos_recursive (const KDL::Tree &tree) | |
~MyTreeFkSolverPos_recursive () | |
virtual int | JntToCart (const KDL::JntArray &q_in, SegmentToPoseMap &result) |
MyTreeFkSolverPos_recursive (const KDL::Tree &tree) | |
~MyTreeFkSolverPos_recursive () | |
virtual int | JntToCart (const KDL::JntArray &q_in, SegmentToPoseMap &result) |
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 mytreefksolverpos_recursive.hpp.
typedef std::map<std::string, KDL::Frame> MyTreeFkSolverPos_recursive::SegmentToPoseMap |
Definition at line 40 of file mytreefksolverpos_recursive.hpp.
typedef std::map<std::string, KDL::Frame> MyTreeFkSolverPos_recursive::SegmentToPoseMap |
Definition at line 40 of file mytreefksolverpos_recursive.hpp.
MyTreeFkSolverPos_recursive::MyTreeFkSolverPos_recursive | ( | const KDL::Tree & | tree | ) |
Definition at line 86 of file mytreefksolverpos_recursive.cpp.
MyTreeFkSolverPos_recursive::MyTreeFkSolverPos_recursive | ( | const KDL::Tree & | tree | ) |
int MyTreeFkSolverPos_recursive::JntToCart | ( | const KDL::JntArray & | q_in, |
SegmentToPoseMap & | result | ||
) | [virtual] |
Definition at line 34 of file mytreefksolverpos_recursive.cpp.
virtual int MyTreeFkSolverPos_recursive::JntToCart | ( | const KDL::JntArray & | q_in, |
SegmentToPoseMap & | result | ||
) | [virtual] |