Retrieves hand description info from the parameter server. More...
Public Member Functions | |
geometry_msgs::Vector3 | approachDirection (std::string arm_name) |
std::string | armAttachmentFrame (std::string arm_name) |
tf::Transform | armToHandTransform (std::string arm_name) |
std::string | gripperFrame (std::string arm_name) |
std::string | handDatabaseName (std::string arm_name) |
HandDescription () | |
std::vector< std::string > | handJointNames (std::string arm_name) |
Private Member Functions | |
std::string | getStringParam (std::string name) |
tf::Transform | getTransformParam (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. |
Retrieves hand description info from the parameter server.
Duplicated from object_manipulator to avoid an additional dependency. Would be nice to find a permanent home for this.
Definition at line 89 of file objects_database_node.cpp.
HandDescription::HandDescription | ( | ) | [inline] |
Definition at line 167 of file objects_database_node.cpp.
geometry_msgs::Vector3 HandDescription::approachDirection | ( | std::string | arm_name | ) | [inline] |
Definition at line 179 of file objects_database_node.cpp.
std::string HandDescription::armAttachmentFrame | ( | std::string | arm_name | ) | [inline] |
Definition at line 209 of file objects_database_node.cpp.
tf::Transform HandDescription::armToHandTransform | ( | std::string | arm_name | ) | [inline] |
Definition at line 204 of file objects_database_node.cpp.
std::string HandDescription::getStringParam | ( | std::string | name | ) | [inline, private] |
Definition at line 95 of file objects_database_node.cpp.
tf::Transform HandDescription::getTransformParam | ( | std::string | name | ) | [inline, private] |
Definition at line 154 of file objects_database_node.cpp.
std::vector<double> HandDescription::getVectorDoubleParam | ( | std::string | name | ) | [inline, private] |
Definition at line 131 of file objects_database_node.cpp.
std::vector<std::string> HandDescription::getVectorParam | ( | std::string | name | ) | [inline, private] |
Definition at line 106 of file objects_database_node.cpp.
std::string HandDescription::gripperFrame | ( | std::string | arm_name | ) | [inline] |
Definition at line 199 of file objects_database_node.cpp.
std::string HandDescription::handDatabaseName | ( | std::string | arm_name | ) | [inline] |
Definition at line 169 of file objects_database_node.cpp.
std::vector<std::string> HandDescription::handJointNames | ( | std::string | arm_name | ) | [inline] |
Definition at line 174 of file objects_database_node.cpp.
ros::NodeHandle HandDescription::root_nh_ [private] |
Node handle in the root namespace.
Definition at line 93 of file objects_database_node.cpp.