Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef _HAND_DESCRIPTION_H_
00034 #define _HAND_DESCRIPTION_H_
00035
00036 #include <ros/ros.h>
00037
00038 #include <cmath>
00039
00040 #include <geometry_msgs/Vector3.h>
00041
00042 #include "object_manipulator/tools/exceptions.h"
00043
00044 #include "configuration_loader.h"
00045
00046 namespace object_manipulator {
00047
00048
00049
00050
00051 class HandDescription : public ConfigurationLoader
00052 {
00053 private:
00054
00055 public:
00056 HandDescription() {}
00057
00058 inline std::string gripperFrame(std::string arm_name)
00059 {
00060 return getStringParam("/hand_description/" + arm_name + "/hand_frame");
00061 }
00062
00063 inline std::string robotFrame(std::string arm_name)
00064 {
00065 return getStringParam("/hand_description/" + arm_name + "/robot_frame");
00066 }
00067
00068 inline std::string attachedName(std::string arm_name)
00069 {
00070 return getStringParam("/hand_description/" + arm_name + "/attached_objects_name");
00071 }
00072
00073 inline std::string attachLinkName(std::string arm_name)
00074 {
00075 return getStringParam("/hand_description/" + arm_name + "/attach_link");
00076 }
00077
00078 inline std::string gripperCollisionName(std::string arm_name)
00079 {
00080 return getStringParam("/hand_description/" + arm_name + "/hand_group_name");
00081 }
00082
00083 inline std::string armGroup(std::string arm_name)
00084 {
00085 return getStringParam("/hand_description/" + arm_name + "/arm_group_name");
00086 }
00087
00088 inline std::string handDatabaseName(std::string arm_name)
00089 {
00090 return getStringParam("/hand_description/" + arm_name + "/hand_database_name");
00091 }
00092
00093 inline std::vector<std::string> handJointNames(std::string arm_name)
00094 {
00095 return getVectorParam("/hand_description/" + arm_name + "/hand_joints");
00096 }
00097
00098 inline std::vector<std::string> gripperTouchLinkNames(std::string arm_name)
00099 {
00100 return getVectorParam("/hand_description/" + arm_name + "/hand_touch_links");
00101 }
00102
00103 inline std::vector<std::string> fingertipLinks(std::string arm_name)
00104 {
00105 return getVectorParam("/hand_description/" + arm_name + "/hand_fingertip_links");
00106 }
00107
00108 inline geometry_msgs::Vector3 approachDirection(std::string arm_name)
00109 {
00110 std::string name = "/hand_description/" + arm_name + "/hand_approach_direction";
00111 std::vector<double> values = getVectorDoubleParam(name);
00112 if ( values.size() != 3 ) throw BadParamException(name);
00113 double length = sqrt( values[0]*values[0] + values[1]*values[1] + values[2]*values[2] );
00114 if ( fabs(length) < 1.0e-5 ) throw BadParamException(name);
00115 geometry_msgs::Vector3 app;
00116 app.x = values[0] / length;
00117 app.y = values[1] / length;
00118 app.z = values[2] / length;
00119 return app;
00120 }
00121
00122 inline std::vector<std::string> armJointNames(std::string arm_name)
00123 {
00124 return getVectorParam("/hand_description/" + arm_name + "/arm_joints");
00125 }
00126
00127 };
00128
00130 inline HandDescription& handDescription()
00131 {
00132 static HandDescription hand_description;
00133 return hand_description;
00134 }
00135
00136 }
00137
00138 #endif