#include <KdlTreeFk.h>
Public Member Functions | |
void | getPose (const KDL::JntArray &joints, const std::string &name, KDL::Frame &frame) |
void | getPoses (const KDL::JntArray &joints, std::map< std::string, KDL::Frame > &frames) |
getPoses | |
void | getVelocities (const KDL::JntArrayVel &joints, std::map< std::string, KDL::FrameVel > &frames) |
getVelocities | |
KdlTreeFk () | |
~KdlTreeFk () | |
Protected Member Functions | |
virtual void | initialize () |
initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded | |
void | recursiveGetPoses (bool getAll, const KDL::Frame &baseFrame, const KDL::SegmentMap::const_iterator &it, const KDL::JntArray &joints, std::map< std::string, KDL::Frame > &frames) |
void | recursiveGetVels (bool getAll, const KDL::FrameVel &baseFrame, const KDL::SegmentMap::const_iterator &it, const KDL::JntArrayVel &joints, std::map< std::string, KDL::FrameVel > &frames) |
Private Attributes | |
std::auto_ptr < KDL::TreeFkSolverPos > | fkSolver |
Definition at line 18 of file KdlTreeFk.h.
Definition at line 3 of file KdlTreeFk.cpp.
Definition at line 7 of file KdlTreeFk.cpp.
void KdlTreeFk::getPose | ( | const KDL::JntArray & | joints, |
const std::string & | name, | ||
KDL::Frame & | frame | ||
) |
Definition at line 11 of file KdlTreeFk.cpp.
void KdlTreeFk::getPoses | ( | const KDL::JntArray & | joints, |
std::map< std::string, KDL::Frame > & | frames | ||
) |
getPoses
joints | input joints |
frames | output frames |
std::runtime_error | - requested an unavailable pose |
if frames is empty, all segments are returned, otherwise the segments named are returned
make sure all of the listed frames are available
Definition at line 23 of file KdlTreeFk.cpp.
void KdlTreeFk::getVelocities | ( | const KDL::JntArrayVel & | joints, |
std::map< std::string, KDL::FrameVel > & | frames | ||
) |
getVelocities
joints | input joints |
frames | output frames |
std::runtime_error | - requested an unavailable pose |
if frames is empty, all segments are returned, otherwise the segments named are returned
make sure all of the listed frames are available
Definition at line 60 of file KdlTreeFk.cpp.
void KdlTreeFk::initialize | ( | ) | [protected, virtual] |
initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded
Reimplemented from KdlTreeParser.
Reimplemented in RosMsgTreeFk.
Definition at line 97 of file KdlTreeFk.cpp.
void KdlTreeFk::recursiveGetPoses | ( | bool | getAll, |
const KDL::Frame & | baseFrame, | ||
const KDL::SegmentMap::const_iterator & | it, | ||
const KDL::JntArray & | joints, | ||
std::map< std::string, KDL::Frame > & | frames | ||
) | [protected] |
get frame for this segment and store as needed
recurse
Definition at line 102 of file KdlTreeFk.cpp.
void KdlTreeFk::recursiveGetVels | ( | bool | getAll, |
const KDL::FrameVel & | baseFrame, | ||
const KDL::SegmentMap::const_iterator & | it, | ||
const KDL::JntArrayVel & | joints, | ||
std::map< std::string, KDL::FrameVel > & | frames | ||
) | [protected] |
get FrameVel for this segment and store as needed
recurse
Definition at line 135 of file KdlTreeFk.cpp.
std::auto_ptr<KDL::TreeFkSolverPos> KdlTreeFk::fkSolver [private] |
Definition at line 52 of file KdlTreeFk.h.