$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 00023 00024 from sr_robot_msgs.msg import sendupdate, joint, joints_data 00025 from sensor_msgs.msg import * 00026 from std_msgs.msg import Float64 00027 00028 00029 class FancyDemo(object): 00030 # starting position for the hand 00031 start_pos_hand = [ joint(joint_name = "THJ1", joint_target = 21), 00032 joint(joint_name = "THJ2", joint_target = 30), 00033 joint(joint_name = "THJ3", joint_target = 0), 00034 joint(joint_name = "THJ4", joint_target = 30), 00035 joint(joint_name = "THJ5", joint_target = 9), 00036 joint(joint_name = "FFJ0", joint_target = 180), 00037 joint(joint_name = "FFJ3", joint_target = 90), 00038 joint(joint_name = "FFJ4", joint_target = 0), 00039 joint(joint_name = "MFJ0", joint_target = 180), 00040 joint(joint_name = "MFJ3", joint_target = 90), 00041 joint(joint_name = "MFJ4", joint_target = 0), 00042 joint(joint_name = "RFJ0", joint_target = 180), 00043 joint(joint_name = "RFJ3", joint_target = 90), 00044 joint(joint_name = "RFJ4", joint_target = 0), 00045 joint(joint_name = "LFJ0", joint_target = 180), 00046 joint(joint_name = "LFJ3", joint_target = 90), 00047 joint(joint_name = "LFJ4", joint_target = 0), 00048 joint(joint_name = "LFJ5", joint_target = 0), 00049 joint(joint_name = "WRJ1", joint_target = 0), 00050 joint(joint_name = "WRJ2", joint_target = 0) ] 00051 #starting position for the arm 00052 start_pos_arm = [ joint(joint_name = "ElbowJRotate", joint_target = 0), 00053 joint(joint_name = "ElbowJSwing", joint_target = 59), 00054 joint(joint_name = "ShoulderJRotate", joint_target = 0), 00055 joint(joint_name = "ShoulderJSwing", joint_target = 33) 00056 ] 00057 #thumb up position for the hand 00058 thumb_up_pos_hand = [ joint(joint_name = "THJ1", joint_target = 0), 00059 joint(joint_name = "THJ2", joint_target = 0), 00060 joint(joint_name = "THJ3", joint_target = 0), 00061 joint(joint_name = "THJ4", joint_target = 0), 00062 joint(joint_name = "THJ5", joint_target = 0), 00063 joint(joint_name = "FFJ0", joint_target = 180), 00064 joint(joint_name = "FFJ3", joint_target = 90), 00065 joint(joint_name = "FFJ4", joint_target = 0), 00066 joint(joint_name = "MFJ0", joint_target = 180), 00067 joint(joint_name = "MFJ3", joint_target = 90), 00068 joint(joint_name = "MFJ4", joint_target = 0), 00069 joint(joint_name = "RFJ0", joint_target = 180), 00070 joint(joint_name = "RFJ3", joint_target = 90), 00071 joint(joint_name = "RFJ4", joint_target = 0), 00072 joint(joint_name = "LFJ0", joint_target = 180), 00073 joint(joint_name = "LFJ3", joint_target = 90), 00074 joint(joint_name = "LFJ4", joint_target = 0), 00075 joint(joint_name = "LFJ5", joint_target = 0), 00076 joint(joint_name = "WRJ1", joint_target = 0), 00077 joint(joint_name = "WRJ2", joint_target = 10) ] 00078 00079 #The hand publisher: 00080 # publish the message to the /srh/sendupdate topic. 00081 hand_publisher = rospy.Publisher('/srh/sendupdate', sendupdate) 00082 00083 #The arm publisher: 00084 # publish the message to the /sr_arm/sendupdate topic. 00085 arm_publisher = rospy.Publisher('/sr_arm/sendupdate', sendupdate) 00086 00087 #A boolean used in this demo: set to true while an action is running 00088 # just so we don't do 2 actions at once 00089 action_running = mutex.mutex() 00090 00091 def __init__(self): 00092 #send the start position to the hand 00093 self.hand_publisher.publish(sendupdate(len(self.start_pos_hand), self.start_pos_hand)) 00094 #send the start position to the arm 00095 self.arm_publisher.publish(sendupdate(len(self.start_pos_arm), self.start_pos_arm)) 00096 00097 #wait for the node to be initialized and then go to the starting position 00098 time.sleep(1) 00099 rospy.loginfo("OK, ready for the demo") 00100 00101 # We have one subscriber per tactile sensor 00102 # This way we can easily have a different action mapped to 00103 # each tactile sensor 00104 # NB: The tactile sensor on the ring finger is not mapped in this example 00105 self.sub_ff = rospy.Subscriber("/sr_tactile/touch/ff", Float64, self.callback_ff, queue_size=1) 00106 self.sub_mf = rospy.Subscriber("/sr_tactile/touch/mf", Float64, self.callback_mf, queue_size=1) 00107 self.sub_lf = rospy.Subscriber("/sr_tactile/touch/lf", Float64, self.callback_lf, queue_size=1) 00108 self.sub_th = rospy.Subscriber("/sr_tactile/touch/th", Float64, self.callback_th, queue_size=1) 00109 00110 00111 def callback_ff(self,data): 00112 """ 00113 The callback function for the first finger: 00114 called each time the tactile sensor publishes a message. 00115 00116 If no action is currently running, we set the ShoulderJRotate 00117 to a negative value proportional to the pressure received. 00118 00119 @param data: the pressure value 00120 """ 00121 #if we're already performing an action, don't do anything 00122 if not self.action_running.testandset(): 00123 return 00124 00125 #filters the noise: check when the finger is being pressed 00126 if data.data < .1: 00127 self.action_running.unlock() 00128 return 00129 00130 #ok the finger sensor was pressed 00131 p = subprocess.Popen('beep') 00132 00133 #rotate the trunk to (data_received * min_pos) 00134 data.data /= 2. 00135 if data.data > 1.: 00136 data.data = 1. 00137 target_sh_rot = 0. + data.data * (-45.0) 00138 target_sh_swing = 20. + data.data * (-10.0) 00139 target_elb_swing = 90. + data.data * (-10.0) 00140 target_elb_rot = 0. + data.data * (-45.0) 00141 00142 rospy.loginfo("FF touched, going to new target ") 00143 00144 #wait 1s for the user to release the sensor 00145 time.sleep(.2) 00146 message = [joint(joint_name = "ShoulderJRotate", joint_target = target_sh_rot), 00147 joint(joint_name = "ShoulderJSwing", joint_target = target_sh_swing), 00148 joint(joint_name = "ElbowJRotate", joint_target = target_elb_rot), 00149 joint(joint_name = "ElbowJSwing", joint_target = target_elb_swing) 00150 ] 00151 00152 self.arm_publisher.publish(sendupdate(len(message), message)) 00153 00154 #wait before next possible action 00155 time.sleep(.2) 00156 self.action_running.unlock() 00157 00158 def callback_mf(self, data): 00159 """ 00160 The callback function for the middle finger: 00161 called each time the tactile sensor publishes a message. 00162 00163 If no action is currently running, we set the ShoulderJRotate 00164 to a positive value proportional to the pressure received. 00165 00166 @param data: the pressure value 00167 """ 00168 #if we're already performing an action, don't do anything 00169 if not self.action_running.testandset(): 00170 return 00171 00172 #filters the noise: check when the finger is being pressed 00173 if data.data < .1: 00174 self.action_running.unlock() 00175 return 00176 00177 #ok finger was pressed 00178 p = subprocess.Popen('beep') 00179 00180 #rotate the trunk to (data_received * min_pos) 00181 data.data /= 2. 00182 if data.data > 1.: 00183 data.data = 1. 00184 target_sh_rot = 0. + data.data * (45.0) 00185 target_sh_swing = 20. + data.data * (20.0) 00186 target_elb_swing = 90. + data.data * (20.0) 00187 target_elb_rot = 0. + data.data * (45.0) 00188 00189 rospy.loginfo("MF touched, going to new target ") 00190 00191 #wait 1s for the user to release the sensor 00192 time.sleep(.2) 00193 message = [joint(joint_name = "ShoulderJRotate", joint_target = target_sh_rot), 00194 joint(joint_name = "ShoulderJSwing", joint_target = target_sh_swing), 00195 joint(joint_name = "ElbowJRotate", joint_target = target_elb_rot), 00196 joint(joint_name = "ElbowJSwing", joint_target = target_elb_swing) 00197 ] 00198 00199 self.arm_publisher.publish(sendupdate(len(message), message)) 00200 00201 #wait before next possible action 00202 time.sleep(.2) 00203 self.action_running.unlock() 00204 00205 def callback_th(self, data): 00206 """ 00207 The callback function for the thumb: 00208 called each time the tactile sensor publishes a message. 00209 00210 If no action is currently running, we send the thumb_up 00211 targets to the hand. 00212 00213 @param data: the pressure value 00214 """ 00215 #if we're already performing an action, don't do anything 00216 if not self.action_running.testandset(): 00217 return 00218 00219 #filters the noise: check when the finger is being pressed 00220 if data.data < .1: 00221 self.action_running.unlock() 00222 return 00223 00224 #ok the finger was pressed 00225 p = subprocess.Popen('beep') 00226 00227 rospy.loginfo("TH touched, going to thumb up position.") 00228 00229 #wait 1s for the user to release the sensor 00230 time.sleep(.2) 00231 00232 #send the thumb_up_position to the hand 00233 self.hand_publisher.publish(sendupdate(len(self.thumb_up_pos_hand), self.thumb_up_pos_hand)) 00234 00235 #wait before next possible action 00236 time.sleep(.2) 00237 self.action_running.unlock() 00238 00239 def callback_lf(self, data): 00240 """ 00241 The callback function for the little finger: 00242 called each time the tactile sensor publishes a message. 00243 00244 If no action is currently running, we reset the arm and 00245 hand to their starting position 00246 00247 @param data: the pressure value 00248 """ 00249 #if we're already performing an action, don't do anything 00250 if not self.action_running.testandset(): 00251 return 00252 00253 #filters the noise: check when the finger is being pressed 00254 if data.data < .1: 00255 self.action_running.unlock() 00256 return 00257 #ok finger pressed 00258 p = subprocess.Popen('beep') 00259 00260 rospy.loginfo("LF touched, going to start position.") 00261 00262 #wait 1s for the user to release the sensor 00263 time.sleep(.2) 00264 00265 #send the start position to the hand 00266 self.hand_publisher.publish(sendupdate(len(self.start_pos_hand), self.start_pos_hand)) 00267 #send the start position to the arm 00268 self.arm_publisher.publish(sendupdate(len(self.start_pos_arm), self.start_pos_arm)) 00269 00270 #wait before next possible action 00271 time.sleep(.2) 00272 self.action_running.unlock() 00273 00274 def main(): 00275 """ 00276 The main function 00277 """ 00278 # init the ros node 00279 rospy.init_node('fancy_touch_demo', anonymous=True) 00280 00281 fancy_demo = FancyDemo() 00282 00283 # subscribe until interrupted 00284 rospy.spin() 00285 00286 00287 if __name__ == '__main__': 00288 main() 00289