#include <hand_description.h>
Public Member Functions | |
geometry_msgs::Vector3 | approachDirection (std::string arm_name) |
std::string | armGroup (std::string arm_name) |
std::string | attachedName (std::string arm_name) |
std::string | attachLinkName (std::string arm_name) |
std::vector< std::string > | fingertipLinks (std::string arm_name) |
std::string | gripperCollisionName (std::string arm_name) |
std::string | gripperFrame (std::string arm_name) |
std::vector< std::string > | gripperTouchLinkNames (std::string arm_name) |
std::string | handDatabaseName (std::string arm_name) |
HandDescription () | |
std::vector< std::string > | handJointNames (std::string arm_name) |
std::string | robotFrame (std::string arm_name) |
Private Member Functions | |
std::string | getStringParam (std::string name) |
std::vector< double > | getVectorDoubleParam (std::string name) |
std::vector< std::string > | getVectorParam (std::string name) |
Private Attributes | |
ros::NodeHandle | root_nh_ |
Node handle in the root namespace. |
Definition at line 46 of file hand_description.h.
object_manipulator::HandDescription::HandDescription | ( | ) | [inline] |
Definition at line 91 of file hand_description.h.
geometry_msgs::Vector3 object_manipulator::HandDescription::approachDirection | ( | std::string | arm_name | ) | [inline] |
Definition at line 143 of file hand_description.h.
std::string object_manipulator::HandDescription::armGroup | ( | std::string | arm_name | ) | [inline] |
Definition at line 118 of file hand_description.h.
std::string object_manipulator::HandDescription::attachedName | ( | std::string | arm_name | ) | [inline] |
Definition at line 103 of file hand_description.h.
std::string object_manipulator::HandDescription::attachLinkName | ( | std::string | arm_name | ) | [inline] |
Definition at line 108 of file hand_description.h.
std::vector<std::string> object_manipulator::HandDescription::fingertipLinks | ( | std::string | arm_name | ) | [inline] |
Definition at line 138 of file hand_description.h.
std::string object_manipulator::HandDescription::getStringParam | ( | std::string | name | ) | [inline, private] |
Definition at line 52 of file hand_description.h.
std::vector<double> object_manipulator::HandDescription::getVectorDoubleParam | ( | std::string | name | ) | [inline, private] |
Definition at line 76 of file hand_description.h.
std::vector<std::string> object_manipulator::HandDescription::getVectorParam | ( | std::string | name | ) | [inline, private] |
Definition at line 60 of file hand_description.h.
std::string object_manipulator::HandDescription::gripperCollisionName | ( | std::string | arm_name | ) | [inline] |
Definition at line 113 of file hand_description.h.
std::string object_manipulator::HandDescription::gripperFrame | ( | std::string | arm_name | ) | [inline] |
Definition at line 93 of file hand_description.h.
std::vector<std::string> object_manipulator::HandDescription::gripperTouchLinkNames | ( | std::string | arm_name | ) | [inline] |
Definition at line 133 of file hand_description.h.
std::string object_manipulator::HandDescription::handDatabaseName | ( | std::string | arm_name | ) | [inline] |
Definition at line 123 of file hand_description.h.
std::vector<std::string> object_manipulator::HandDescription::handJointNames | ( | std::string | arm_name | ) | [inline] |
Definition at line 128 of file hand_description.h.
std::string object_manipulator::HandDescription::robotFrame | ( | std::string | arm_name | ) | [inline] |
Definition at line 98 of file hand_description.h.
ros::NodeHandle object_manipulator::HandDescription::root_nh_ [private] |
Node handle in the root namespace.
Definition at line 50 of file hand_description.h.