$search
00001 #!/usr/bin/env python 00002 # 00003 # Copyright 2011 Shadow Robot Company Ltd. 00004 # 00005 # This program is free software: you can redistribute it and/or modify it 00006 # under the terms of the GNU General Public License as published by the Free 00007 # Software Foundation, either version 2 of the License, or (at your option) 00008 # any later version. 00009 # 00010 # This program is distributed in the hope that it will be useful, but WITHOUT 00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or 00012 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for 00013 # more details. 00014 # 00015 # You should have received a copy of the GNU General Public License along 00016 # with this program. If not, see <http://www.gnu.org/licenses/>. 00017 # 00018 00019 import roslib; roslib.load_manifest('sr_hand') 00020 import rospy 00021 00022 import time, mutex, subprocess, math 00023 00024 from sr_robot_msgs.msg import sendupdate, joint, Biotac, BiotacAll, ShadowPST 00025 from sensor_msgs.msg import * 00026 from std_msgs.msg import Float64 00027 00028 #the threshold for pdc above which the tactile is considered "pressed" 00029 PDC_THRESHOLD = 2000 00030 #the threshold for the PSTs above which the tactile is considered "pressed" 00031 PST_THRESHOLD = 400 00032 00033 class FancyDemo(object): 00034 # starting position for the hand (DON't use until reviewed. Should be executed in two movement sequences) 00035 start_pos_hand = [ joint(joint_name = "THJ1", joint_target = 21), 00036 joint(joint_name = "THJ2", joint_target = 25), 00037 joint(joint_name = "THJ3", joint_target = 0), 00038 joint(joint_name = "THJ4", joint_target = 50), 00039 joint(joint_name = "THJ5", joint_target = 9), 00040 joint(joint_name = "FFJ0", joint_target = 180), 00041 joint(joint_name = "FFJ3", joint_target = 90), 00042 joint(joint_name = "FFJ4", joint_target = 0), 00043 joint(joint_name = "MFJ0", joint_target = 180), 00044 joint(joint_name = "MFJ3", joint_target = 90), 00045 joint(joint_name = "MFJ4", joint_target = 0), 00046 joint(joint_name = "RFJ0", joint_target = 180), 00047 joint(joint_name = "RFJ3", joint_target = 90), 00048 joint(joint_name = "RFJ4", joint_target = 0), 00049 joint(joint_name = "LFJ0", joint_target = 180), 00050 joint(joint_name = "LFJ3", joint_target = 90), 00051 joint(joint_name = "LFJ4", joint_target = 0), 00052 joint(joint_name = "LFJ5", joint_target = 0), 00053 joint(joint_name = "WRJ1", joint_target = 0), 00054 joint(joint_name = "WRJ2", joint_target = 0) ] 00055 # starting position for the hand 00056 extended_pos_hand = [ joint(joint_name = "THJ1", joint_target = 21), 00057 joint(joint_name = "THJ2", joint_target = 25), 00058 joint(joint_name = "THJ3", joint_target = 0), 00059 joint(joint_name = "THJ4", joint_target = 50), 00060 joint(joint_name = "THJ5", joint_target = 9), 00061 joint(joint_name = "FFJ0", joint_target = 0), 00062 joint(joint_name = "FFJ3", joint_target = 0), 00063 joint(joint_name = "FFJ4", joint_target = 0), 00064 joint(joint_name = "MFJ0", joint_target = 0), 00065 joint(joint_name = "MFJ3", joint_target = 0), 00066 joint(joint_name = "MFJ4", joint_target = 0), 00067 joint(joint_name = "RFJ0", joint_target = 0), 00068 joint(joint_name = "RFJ3", joint_target = 0), 00069 joint(joint_name = "RFJ4", joint_target = 0), 00070 joint(joint_name = "LFJ0", joint_target = 0), 00071 joint(joint_name = "LFJ3", joint_target = 0), 00072 joint(joint_name = "LFJ4", joint_target = 0), 00073 joint(joint_name = "LFJ5", joint_target = 0), 00074 joint(joint_name = "WRJ1", joint_target = 0), 00075 joint(joint_name = "WRJ2", joint_target = 0) ] 00076 #starting position for the arm 00077 start_pos_arm = [ joint(joint_name = "ElbowJRotate", joint_target = 0), 00078 joint(joint_name = "ElbowJSwing", joint_target = 59), 00079 joint(joint_name = "ShoulderJRotate", joint_target = 0), 00080 joint(joint_name = "ShoulderJSwing", joint_target = 33) 00081 ] 00082 #thumb up position for the hand 00083 thumb_up_pos_hand = [ joint(joint_name = "THJ1", joint_target = 0), 00084 joint(joint_name = "THJ2", joint_target = 0), 00085 joint(joint_name = "THJ3", joint_target = 0), 00086 joint(joint_name = "THJ4", joint_target = 0), 00087 joint(joint_name = "THJ5", joint_target = 0), 00088 joint(joint_name = "FFJ0", joint_target = 180), 00089 joint(joint_name = "FFJ3", joint_target = 90), 00090 joint(joint_name = "FFJ4", joint_target = 0), 00091 joint(joint_name = "MFJ0", joint_target = 180), 00092 joint(joint_name = "MFJ3", joint_target = 90), 00093 joint(joint_name = "MFJ4", joint_target = 0), 00094 joint(joint_name = "RFJ0", joint_target = 180), 00095 joint(joint_name = "RFJ3", joint_target = 90), 00096 joint(joint_name = "RFJ4", joint_target = 0), 00097 joint(joint_name = "LFJ0", joint_target = 180), 00098 joint(joint_name = "LFJ3", joint_target = 90), 00099 joint(joint_name = "LFJ4", joint_target = 0), 00100 joint(joint_name = "LFJ5", joint_target = 0), 00101 joint(joint_name = "WRJ1", joint_target = 0), 00102 joint(joint_name = "WRJ2", joint_target = 10) ] 00103 00104 00105 00106 #The arm publisher: 00107 # publish the message to the /sr_arm/sendupdate topic. 00108 arm_publisher = rospy.Publisher('/sr_arm/sendupdate', sendupdate) 00109 00110 #A boolean used in this demo: set to true while an action is running 00111 # just so we don't do 2 actions at once 00112 action_running = mutex.mutex() 00113 00114 def __init__(self): 00115 #A vector containing the different callbacks, in the same order 00116 # as the tactiles. 00117 self.fingers_pressed_functions = [self.ff_pressed, self.mf_pressed, self.rf_pressed, 00118 self.lf_pressed, self.th_pressed] 00119 00120 #The hand publishers: 00121 # we use a dictionnary of publishers, because on the etherCAT hand 00122 # you have one publisher per controller. 00123 self.hand_publishers = self.create_hand_publishers() 00124 00125 #send the start position to the hand 00126 self.hand_publish(self.start_pos_hand) 00127 #send the start position to the arm 00128 self.arm_publisher.publish( sendupdate(len(self.start_pos_arm), self.start_pos_arm) ) 00129 00130 #wait for the node to be initialized and then go to the starting position 00131 time.sleep(1) 00132 rospy.loginfo("OK, ready for the demo") 00133 00134 # We subscribe to the data being published by the biotac sensors. 00135 self.sub_biotacs = rospy.Subscriber("/tactiles", BiotacAll, self.callback_biotacs, queue_size=1) 00136 self.sub_psts = rospy.Subscriber("/tactile", ShadowPST, self.callback_psts, queue_size=1) 00137 00138 def create_hand_publishers(self): 00139 """ 00140 Creates a dictionnary of publishers to send the targets to the controllers 00141 on /sh_??j?_mixed_position_velocity_controller/command 00142 """ 00143 hand_pub = {} 00144 00145 for joint in ["FFJ0", "FFJ3", "FFJ4", 00146 "MFJ0", "MFJ3", "MFJ4", 00147 "RFJ0", "RFJ3", "RFJ4", 00148 "LFJ0", "LFJ3", "LFJ4", "LFJ5", 00149 "THJ1", "THJ2", "THJ3", "THJ4", "THJ5", 00150 "WRJ1", "WRJ2" ]: 00151 hand_pub[joint] = rospy.Publisher('/sh_'+joint.lower()+'_position_controller/command', Float64) 00152 00153 return hand_pub 00154 00155 def hand_publish(self, pose): 00156 """ 00157 Publishes the given pose to the correct controllers for the hand. 00158 The targets are converted in radians. 00159 """ 00160 for joint in pose: 00161 self.hand_publishers[joint.joint_name].publish( math.radians(joint.joint_target) ) 00162 00163 def callback_biotacs(self, msg): 00164 """ 00165 The callback function for the biotacs. Checks if one of the fingers 00166 was pressed (filter the noise). If it is the case, call the 00167 corresponding function. 00168 00169 @msg is the message containing the biotac data 00170 """ 00171 #loop through the five tactiles 00172 for index,tactile in enumerate(msg.tactiles): 00173 #here we're just checking pdc (the pressure) 00174 # to see if a finger has been pressed, but you have 00175 # access to the whole data from the sensor 00176 # (look at sr_robot_msgs/msg/Biotac.msg) 00177 if tactile.pdc >= PDC_THRESHOLD: 00178 # the tactile has been pressed, call the 00179 # corresponding function 00180 self.fingers_pressed_functions[index](tactile.pdc) 00181 00182 def callback_psts(self, msg): 00183 """ 00184 The callback function for the PSTs. Checks if one of the fingers 00185 was pressed (filter the noise). If it is the case, call the 00186 corresponding function. 00187 00188 @msg is the message containing the biotac data 00189 """ 00190 #loop through the five tactiles 00191 for index,tactile in enumerate(msg.pressure): 00192 #here we're just checking the pressure 00193 # to see if a finger has been pressed 00194 # 18456 is the value the PST takes when the sensor is not plugged in 00195 if tactile >= PST_THRESHOLD and tactile != 18456: 00196 # the tactile has been pressed, call the 00197 # corresponding function 00198 self.fingers_pressed_functions[index](tactile) 00199 00200 def ff_pressed(self,data): 00201 """ 00202 The first finger was pressed. 00203 00204 If no action is currently running, we set the ShoulderJRotate 00205 to a negative value proportional to the pressure received. 00206 00207 @param data: the pressure value (pdc) 00208 """ 00209 #if we're already performing an action, don't do anything 00210 if not self.action_running.testandset(): 00211 return 00212 00213 #ok the finger sensor was pressed 00214 p = subprocess.Popen('beep') 00215 00216 #rotate the trunk to (data_received * min_pos) 00217 # convert data to be in [0., 1.] 00218 data /= 4000. 00219 if data > 1.: 00220 data = 1. 00221 target_sh_rot = 0. + data * (-45.0) 00222 target_sh_swing = 20. + data * (-10.0) 00223 target_elb_swing = 90. + data * (-10.0) 00224 target_elb_rot = 0. + data * (-45.0) 00225 00226 rospy.loginfo("FF touched, going to new target ") 00227 00228 #wait 1s for the user to release the sensor 00229 time.sleep(.2) 00230 message = [joint(joint_name = "ShoulderJRotate", joint_target = target_sh_rot), 00231 joint(joint_name = "ShoulderJSwing", joint_target = target_sh_swing), 00232 joint(joint_name = "ElbowJRotate", joint_target = target_elb_rot), 00233 joint(joint_name = "ElbowJSwing", joint_target = target_elb_swing) 00234 ] 00235 00236 self.arm_publisher.publish(sendupdate(len(message), message)) 00237 00238 #send the start position to the hand 00239 self.hand_publish( self.extended_pos_hand ) 00240 00241 #wait before next possible action 00242 time.sleep(.2) 00243 self.action_running.unlock() 00244 00245 def mf_pressed(self, data): 00246 """ 00247 The middle finger was pressed. 00248 00249 If no action is currently running, we move the arm angles 00250 to a positive value proportional to the pressure received. 00251 00252 @param data: the pressure value (pdc) 00253 """ 00254 #if we're already performing an action, don't do anything 00255 if not self.action_running.testandset(): 00256 return 00257 00258 #ok finger was pressed 00259 p = subprocess.Popen('beep') 00260 00261 #rotate the trunk to (data_received * min_pos) 00262 # convert data to be in [0., 1.] 00263 data /= 4000. 00264 if data > 1.: 00265 data = 1. 00266 target_sh_rot = 0. + data * (45.0) 00267 target_sh_swing = 20. + data * (20.0) 00268 target_elb_swing = 90. + data * (20.0) 00269 target_elb_rot = 0. + data * (45.0) 00270 00271 rospy.loginfo("MF touched, going to new target ") 00272 00273 #wait 1s for the user to release the sensor 00274 time.sleep(.2) 00275 message = [joint(joint_name = "ShoulderJRotate", joint_target = target_sh_rot), 00276 joint(joint_name = "ShoulderJSwing", joint_target = target_sh_swing), 00277 joint(joint_name = "ElbowJRotate", joint_target = target_elb_rot), 00278 joint(joint_name = "ElbowJSwing", joint_target = target_elb_swing) 00279 ] 00280 00281 self.arm_publisher.publish(sendupdate(len(message), message)) 00282 00283 #wait before next possible action 00284 time.sleep(.2) 00285 self.action_running.unlock() 00286 00287 00288 def rf_pressed(self, data): 00289 """ 00290 The ring finger was pressed. 00291 00292 If no action is currently running, we make a beep 00293 but don't do anything else. 00294 00295 @param data: the pressure value (pdc) 00296 """ 00297 #if we're already performing an action, don't do anything 00298 if not self.action_running.testandset(): 00299 return 00300 00301 #ok finger was pressed 00302 p = subprocess.Popen('beep') 00303 00304 rospy.loginfo("RF touched, not doing anything.") 00305 00306 #wait before next possible action 00307 time.sleep(.2) 00308 self.action_running.unlock() 00309 00310 def lf_pressed(self, data): 00311 """ 00312 The little finger was pressed. 00313 00314 If no action is currently running, we reset the arm and 00315 hand to their starting position 00316 00317 @param data: the pressure value (pdc) 00318 """ 00319 #if we're already performing an action, don't do anything 00320 if not self.action_running.testandset(): 00321 return 00322 00323 #ok finger pressed 00324 p = subprocess.Popen('beep') 00325 00326 rospy.loginfo("LF touched, going to start position.") 00327 00328 #wait 1s for the user to release the sensor 00329 time.sleep(.2) 00330 00331 #send the start position to the hand 00332 self.hand_publish( self.start_pos_hand ) 00333 #send the start position to the arm 00334 self.arm_publisher.publish(sendupdate(len(self.start_pos_arm), self.start_pos_arm)) 00335 00336 #wait before next possible action 00337 time.sleep(.2) 00338 self.action_running.unlock() 00339 00340 def th_pressed(self, data): 00341 """ 00342 The thumb was pressed. 00343 00344 If no action is currently running, we send the thumb_up 00345 targets to the hand. 00346 00347 @param data: the pressure value (pdc) 00348 """ 00349 #if we're already performing an action, don't do anything 00350 if not self.action_running.testandset(): 00351 return 00352 00353 #ok the finger was pressed 00354 p = subprocess.Popen('beep') 00355 00356 rospy.loginfo("TH touched, going to thumb up position.") 00357 00358 #wait 1s for the user to release the sensor 00359 time.sleep(.2) 00360 00361 #send the thumb_up_position to the hand 00362 self.hand_publish( self.thumb_up_pos_hand ) 00363 00364 #wait before next possible action 00365 time.sleep(.2) 00366 self.action_running.unlock() 00367 00368 def main(): 00369 """ 00370 The main function 00371 """ 00372 # init the ros node 00373 rospy.init_node('fancy_touch_demo', anonymous=True) 00374 00375 fancy_demo = FancyDemo() 00376 00377 # subscribe until interrupted 00378 rospy.spin() 00379 00380 00381 if __name__ == '__main__': 00382 main() 00383