#include <hand_description.h>
Public Member Functions | |
const geometry_msgs::Vector3 & | getApproachDirection () const |
const std::string & | getArmName () const |
const std::string & | getAttachLink () const |
double | getEndEffectorLength () const |
const std::vector< std::string > & | getFingerLinks () const |
const std::vector< std::string > & | getFingerTipLinks () const |
const std::string & | getGripperJoint () const |
const std::string & | getHandFrame () const |
const std::string & | getHandGroup () const |
const std::vector< std::string > & | getHandLinks () const |
const std::vector< std::string > & | getTouchLinks () const |
virtual | ~HandDescription () |
Static Public Member Functions | |
static const HandDescription & | get (const std::string &arm_name) |
Private Member Functions | |
HandDescription (const std::string &arm) | |
Private Attributes | |
geometry_msgs::Vector3 | approachDirection |
std::string | armName |
std::string | attachLink |
double | endEffectorLength |
std::vector< std::string > | fingerLinks |
std::vector< std::string > | fingerTipLinks |
std::string | gripperJoint |
std::string | handFrame |
std::string | handGroup |
std::vector< std::string > | handLinks |
std::vector< std::string > | touchLinks |
Static Private Attributes | |
static std::map< std::string, HandDescription > | descriptions |
Definition at line 15 of file hand_description.h.
HandDescription::~HandDescription | ( | ) | [virtual] |
Definition at line 152 of file hand_description.cpp.
HandDescription::HandDescription | ( | const std::string & | arm | ) | [private] |
Definition at line 26 of file hand_description.cpp.
const HandDescription & HandDescription::get | ( | const std::string & | arm_name | ) | [static] |
Definition at line 14 of file hand_description.cpp.
const geometry_msgs::Vector3& HandDescription::getApproachDirection | ( | ) | const [inline] |
Definition at line 22 of file hand_description.h.
const std::string& HandDescription::getArmName | ( | ) | const [inline] |
Definition at line 27 of file hand_description.h.
const std::string& HandDescription::getAttachLink | ( | ) | const [inline] |
Definition at line 32 of file hand_description.h.
double HandDescription::getEndEffectorLength | ( | ) | const [inline] |
Definition at line 37 of file hand_description.h.
const std::vector<std::string>& HandDescription::getFingerLinks | ( | ) | const [inline] |
Definition at line 42 of file hand_description.h.
const std::vector<std::string>& HandDescription::getFingerTipLinks | ( | ) | const [inline] |
Definition at line 47 of file hand_description.h.
const std::string& HandDescription::getGripperJoint | ( | ) | const [inline] |
Definition at line 52 of file hand_description.h.
const std::string& HandDescription::getHandFrame | ( | ) | const [inline] |
Definition at line 57 of file hand_description.h.
const std::string& HandDescription::getHandGroup | ( | ) | const [inline] |
Definition at line 62 of file hand_description.h.
const std::vector<std::string>& HandDescription::getHandLinks | ( | ) | const [inline] |
Definition at line 67 of file hand_description.h.
const std::vector<std::string>& HandDescription::getTouchLinks | ( | ) | const [inline] |
Definition at line 72 of file hand_description.h.
geometry_msgs::Vector3 HandDescription::approachDirection [private] |
Definition at line 92 of file hand_description.h.
std::string HandDescription::armName [private] |
Definition at line 80 of file hand_description.h.
std::string HandDescription::attachLink [private] |
Definition at line 82 of file hand_description.h.
map< string, HandDescription > HandDescription::descriptions [static, private] |
Definition at line 94 of file hand_description.h.
double HandDescription::endEffectorLength [private] |
Definition at line 91 of file hand_description.h.
std::vector<std::string> HandDescription::fingerLinks [private] |
Definition at line 89 of file hand_description.h.
std::vector<std::string> HandDescription::fingerTipLinks [private] |
Definition at line 88 of file hand_description.h.
std::string HandDescription::gripperJoint [private] |
Definition at line 84 of file hand_description.h.
std::string HandDescription::handFrame [private] |
Definition at line 83 of file hand_description.h.
std::string HandDescription::handGroup [private] |
Definition at line 81 of file hand_description.h.
std::vector<std::string> HandDescription::handLinks [private] |
Definition at line 86 of file hand_description.h.
std::vector<std::string> HandDescription::touchLinks [private] |
Definition at line 87 of file hand_description.h.