#include <MobileTreeIk.h>

Public Member Functions | |
| virtual std::string | getBaseName () const |
| get base of tree. Virtual so derived classes can publish a different base if desired. | |
| virtual void | getFrames (const KDL::JntArray &joints_in, std::map< std::string, KDL::Frame > &frameMap) |
| getJoints | |
| virtual unsigned int | getJointCount () const |
| get joint count of tree. Virtual so derived classes can publish a different number if desired. | |
| virtual void | getJointNames (std::vector< std::string > &jointNames) const |
| get joint names in tree. Virtual so derived classes can manipulate the published names if desired. | |
| virtual void | getJointPositions (const KDL::JntArray &joints_in, const std::vector< std::string > &nodeNames, const std::vector< KDL::Frame > &nodeFrames, KDL::JntArray &joints_out, const std::vector< NodePriority > &nodePriorities) |
| getJoints | |
| MobileTreeIk () | |
| void | resetMobileJoints () |
| void | setBases (const std::vector< std::string > &bases_in) |
| void | setPriorityTol (const std::map< int, std::pair< double, double > > &priority_tol) |
| ~MobileTreeIk () | |
Static Public Attributes | |
| static const int | BASE = -1 |
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 | |
Private Attributes | |
| std::vector< std::string > | bases |
| KDL::JntArray | mobileJoints |
| std::string | robotModelBase |
Definition at line 11 of file MobileTreeIk.h.
Definition at line 5 of file MobileTreeIk.cpp.
Definition at line 10 of file MobileTreeIk.cpp.
| virtual std::string MobileTreeIk::getBaseName | ( | ) | const [inline, virtual] |
get base of tree. Virtual so derived classes can publish a different base if desired.
Reimplemented from KdlTreeUtilities.
Definition at line 35 of file MobileTreeIk.h.
| void MobileTreeIk::getFrames | ( | const KDL::JntArray & | joints_in, |
| std::map< std::string, KDL::Frame > & | frameMap | ||
| ) | [virtual] |
getJoints
| joints_in | input joints |
| nodeNames | input frame names |
| nodeFrames | input frames |
| joints_out | output joints |
| nodePriorities | input node priorities (6 * nodeNames.size()) |
Reimplemented from KdlTreeIk.
Definition at line 144 of file MobileTreeIk.cpp.
| virtual unsigned int MobileTreeIk::getJointCount | ( | ) | const [inline, virtual] |
get joint count of tree. Virtual so derived classes can publish a different number if desired.
Reimplemented from KdlTreeUtilities.
Definition at line 37 of file MobileTreeIk.h.
| void MobileTreeIk::getJointNames | ( | std::vector< std::string > & | jointNames | ) | const [virtual] |
get joint names in tree. Virtual so derived classes can manipulate the published names if desired.
Reimplemented from KdlTreeUtilities.
Definition at line 125 of file MobileTreeIk.cpp.
| void MobileTreeIk::getJointPositions | ( | const KDL::JntArray & | joints_in, |
| const std::vector< std::string > & | nodeNames, | ||
| const std::vector< KDL::Frame > & | nodeFrames, | ||
| KDL::JntArray & | joints_out, | ||
| const std::vector< NodePriority > & | nodePriorities | ||
| ) | [virtual] |
getJoints
| joints_in | input joints |
| nodeNames | input frame names |
| nodeFrames | input frames |
| joints_out | output joints |
| nodePriorities | input node priorities (6 * nodeNames.size()) |
Reimplemented from KdlTreeTr.
Definition at line 45 of file MobileTreeIk.cpp.
| void MobileTreeIk::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 KdlTreeTr.
Definition at line 100 of file MobileTreeIk.cpp.
| void MobileTreeIk::resetMobileJoints | ( | ) |
Definition at line 40 of file MobileTreeIk.cpp.
| void MobileTreeIk::setBases | ( | const std::vector< std::string > & | bases_in | ) |
Definition at line 14 of file MobileTreeIk.cpp.
| void MobileTreeIk::setPriorityTol | ( | const std::map< int, std::pair< double, double > > & | priority_tol | ) | [inline] |
Reimplemented from KdlTreeIk.
Definition at line 40 of file MobileTreeIk.h.
const int MobileTreeIk::BASE = -1 [static] |
Definition at line 14 of file MobileTreeIk.h.
std::vector<std::string> MobileTreeIk::bases [private] |
Definition at line 51 of file MobileTreeIk.h.
KDL::JntArray MobileTreeIk::mobileJoints [private] |
Definition at line 50 of file MobileTreeIk.h.
std::string MobileTreeIk::robotModelBase [private] |
Definition at line 52 of file MobileTreeIk.h.