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 import rospy
00019 import rospkg
00020 
00021 
00022 class HandControllerTuning(object):
00023     def __init__(self, mapping):
00024         """
00025 
00026         """
00027         ros_pack = rospkg.RosPack()
00028         ethercat_path = ros_pack.get_path('sr_ethercat_hand_config')
00029         self.friction_compensation = {}
00030         self.host_control = {}
00031         self.motor_control = {}
00032         for hand in mapping:
00033             self.friction_compensation[mapping[hand]] = \
00034                 ethercat_path + '/controls/' + 'friction_compensation.yaml'
00035             host_path = ethercat_path + '/controls/host/' + mapping[hand] + '/'
00036             self.host_control[mapping[hand]] = \
00037                 [host_path + 'sr_edc_calibration_controllers.yaml',
00038                  host_path + 'sr_edc_joint_velocity_controllers_PWM.yaml',
00039                  host_path + 'sr_edc_effort_controllers_PWM.yaml',
00040                  host_path + 'sr_edc_joint_velocity_controllers.yaml',
00041                  host_path + 'sr_edc_effort_controllers.yaml',
00042                  host_path + 'sr_edc_mixed_position_velocity_'
00043                              'joint_controllers_PWM.yaml',
00044                  host_path + 'sr_edc_joint_position_controllers_PWM.yaml',
00045                  host_path + 'sr_edc_mixed_position_velocity_'
00046                              'joint_controllers.yaml',
00047                  host_path + 'sr_edc_joint_position_controllers.yaml']
00048 
00049             self.motor_control[mapping[hand]] = \
00050                 ethercat_path + '/controls/motors/' +\
00051                 mapping[hand] + '/motor_board_effort_controllers.yaml'
00052 
00053 
00054 class HandCalibration(object):
00055     def __init__(self, mapping):
00056         """
00057 
00058         """
00059         ros_pack = rospkg.RosPack()
00060         ethercat_path = ros_pack.get_path('sr_ethercat_hand_config')
00061         self.calibration_path = {}
00062         for hand in mapping:
00063             self.calibration_path[mapping[hand]] = \
00064                 ethercat_path + '/calibrations/' + mapping[hand] + '/' \
00065                 + "calibration.yaml"
00066 
00067 
00068 class HandConfig(object):
00069 
00070     def __init__(self, mapping, joint_prefix):
00071         """
00072 
00073         """
00074         self.mapping = mapping
00075         self.joint_prefix = joint_prefix
00076 
00077 
00078 class HandJoints(object):
00079     def __init__(self, mapping):
00080         """
00081 
00082         """
00083         joints = ['FFJ1', 'FFJ2', 'FFJ3', 'FFJ4', 'MFJ1', 'MFJ2', 'MFJ3',
00084                   'MFJ4', 'RFJ1', 'RFJ2', 'RFJ3', 'RFJ4', 'LFJ1', 'LFJ2',
00085                   'LFJ3', 'LFJ4', 'LFJ5', 'THJ1', 'THJ2', 'THJ3', 'THJ4',
00086                   'THJ5', 'WRJ1', 'WRJ2']
00087         self.joints = {}
00088         hand_joints = []
00089         for hand in mapping:
00090             for joint in joints:
00091                 hand_joints.append(mapping[hand] + '_' + joint)
00092             self.joints[mapping[hand]] = hand_joints
00093 
00094 
00095 class HandFinder(object):
00096     """
00097     The HandFinder is a utility library for detecting Shadow Hands running on
00098     the system. The idea is to make it easier to write generic code,
00099      using this library to handle prefixes, joint prefixes etc...
00100     """
00101 
00102     def __init__(self):
00103         """
00104         Parses the parameter server to extract the necessary information.
00105         """
00106         if not rospy.has_param("hand"):
00107             rospy.logerr("No hand is detected")
00108             hand_parameters = {'joint_prefix': {}, 'mapping': {}}
00109         else:
00110             hand_parameters = rospy.get_param("hand")
00111         self.hand_config = HandConfig(hand_parameters["mapping"],
00112                                       hand_parameters["joint_prefix"])
00113         self.hand_joints = HandJoints(self.hand_config.mapping).joints
00114         self.calibration_path = \
00115             HandCalibration(self.hand_config.mapping).calibration_path
00116         self.hand_control_tuning = \
00117             HandControllerTuning(self.hand_config.mapping)
00118 
00119     def get_calibration_path(self):
00120         return self.calibration_path
00121 
00122     def get_hand_joints(self):
00123         return self.hand_joints
00124 
00125     def get_hand_parameters(self):
00126         return self.hand_config
00127 
00128     def get_hand_control_tuning(self):
00129         return self.hand_control_tuning