00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import roslib; roslib.load_manifest('sr_hand')
00019 import time
00020 import os
00021 import math
00022 import rospy
00023 import subprocess
00024 import threading
00025 import rosgraph.masterapi
00026 import pr2_controllers_msgs.msg
00027 from sr_robot_msgs.msg import sendupdate, joint, joints_data, JointControllerState
00028 from sensor_msgs.msg import *
00029 from std_msgs.msg import Float64
00030 from grasps_parser import GraspParser
00031 from grasps_interpoler import GraspInterpoler
00032
00033 class Joint():
00034 def __init__(self, name="", motor="", min=0, max=90):
00035 self.name = name
00036 self.motor = motor
00037 self.min = min
00038 self.max = max
00039
00040 class ShadowHand_ROS():
00041 """
00042 This is a python library used to easily access the shadow hand ROS interface.
00043 """
00044 def __init__(self):
00045 """
00046 Builds the library, creates the communication node in ROS and
00047 initializes the hand publisher and subscriber to the default
00048 values of shadowhand_data and sendupdate
00049 """
00050 self.allJoints = [Joint("THJ1", "smart_motor_th1", 0, 90),
00051 Joint("THJ2", "smart_motor_th2", -40, 40),
00052 Joint("THJ3", "smart_motor_th3",-15, 15),
00053 Joint("THJ4", "smart_motor_th4",0, 75),
00054 Joint("THJ5", "smart_motor_th5",-60, 60),
00055 Joint("FFJ0", "smart_motor_ff2", 0, 180),
00056 Joint("FFJ3", "smart_motor_ff3"),
00057 Joint("FFJ4", "smart_motor_ff4", -20, 20),
00058 Joint("MFJ0", "smart_motor_mf2", 0, 180),
00059 Joint("MFJ3", "smart_motor_mf3"),
00060 Joint("MFJ4", "smart_motor_mf4", -20, 20),
00061 Joint("RFJ0", "smart_motor_rf2", 0, 180),
00062 Joint("RFJ3", "smart_motor_rf3"),
00063 Joint("RFJ4", "smart_motor_rf4", -20,20),
00064 Joint("LFJ0", "smart_motor_lf2", 0, 180),
00065 Joint("LFJ3", "smart_motor_lf3"),
00066 Joint("LFJ4", "smart_motor_lf4", -20, 20),
00067 Joint("LFJ5", "smart_motor_lf5", 0, 45),
00068 Joint("WRJ1", "smart_motor_wr1", -45, 30),
00069 Joint("WRJ2", "smart_motor_wr2", -30, 10),
00070 ]
00071 self.handJoints = []
00072 self.armJoints = [Joint("ShoulderJRotate", "", -45, 60),
00073 Joint("ShoulderJSwing", "", 0, 80),
00074 Joint("ElbowJSwing", "", 0,120),
00075 Joint("ElbowJRotate", "", -80,80)
00076 ]
00077 self.lastMsg = joints_data()
00078 self.lastArmMsg = joints_data()
00079 self.cyberglove_pub = 0
00080 self.cyberglove_sub = 0
00081 self.cybergrasp_pub = 0
00082 self.cyberglove_sub = 0
00083 self.isFirstMessage = True
00084 self.isFirstMessageArm = True
00085 self.isReady = False
00086 self.liste = 0
00087 self.hasarm = 0
00088 self.dict_pos = {}
00089 self.dict_tar = {}
00090 self.dict_arm_pos = {}
00091 self.dict_arm_tar = {}
00092 self.dict_ethercat_joints = {}
00093 self.eth_publishers = {}
00094 self.eth_subscribers = {}
00095
00096 self.sendupdate_lock = threading.Lock()
00097
00098
00099 self.topic_ending = ""
00100
00101
00102
00103 self.activate_etherCAT_hand()
00104
00105
00106
00107 self.grasp_parser = GraspParser()
00108 process = subprocess.Popen("rospack find sr_hand".split(), stdout=subprocess.PIPE)
00109 self.rootPath = process.communicate()[0]
00110 self.rootPath = self.rootPath.split('\n')
00111 self.rootPath = self.rootPath[0]
00112
00113 self.grasp_parser.parse_tree(self.rootPath+"/python_lib/grasp/grasps.xml")
00114
00115 self.grasp_interpoler = 0
00116 self.pub = rospy.Publisher('srh/sendupdate',sendupdate, latch=True)
00117 self.pub_arm = rospy.Publisher('sr_arm/sendupdate',sendupdate, latch=True)
00118
00119 self.sub_arm = rospy.Subscriber('sr_arm/shadowhand_data', joints_data,self.callback_arm)
00120 self.sub = rospy.Subscriber('srh/shadowhand_data', joints_data ,self.callback)
00121
00122 self.hand_type = self.check_hand_type()
00123
00124 threading.Thread(None, rospy.spin)
00125
00126 def create_grasp_interpoler(self, current_step, next_step):
00127 self.grasp_interpoler = GraspInterpoler(current_step, next_step)
00128
00129 def callback_ethercat_states(self, data, jointName):
00130 """
00131 @param data: The ROS message received which called the callback
00132 If the message is the first received, initializes the dictionnaries
00133 Else, it updates the lastMsg
00134 @param joint: a Joint object that contains the name of the joint that we receive data from
00135 """
00136 joint_data = joint(joint_name=jointName, joint_target=math.degrees(float(data.set_point)), joint_position=math.degrees(float(data.process_value)))
00137
00138
00139 self.dict_ethercat_joints[joint_data.joint_name]=joint_data
00140
00141
00142 self.lastMsg = joints_data()
00143
00144 for joint_name in self.dict_ethercat_joints.keys() :
00145 self.lastMsg.joints_list.append(self.dict_ethercat_joints[joint_name])
00146
00147
00148
00149 self.isReady = True
00150
00151 '''
00152 if self.isFirstMessage :
00153 self.init_actual_joints()
00154 for joint in self.lastMsg.joints_list :
00155 self.dict_pos[joint.joint_name]=joint.joint_position
00156 self.dict_tar[joint.joint_name]=joint.joint_target
00157 self.isFirstMessage = False
00158 self.isReady = True
00159 '''
00160
00161 def callback(self, data):
00162 """
00163 @param data: The ROS message received which called the callback
00164 If the message is the first received, initializes the dictionnaries
00165 Else, it updates the lastMsg
00166 """
00167 self.lastMsg = data;
00168 if self.isFirstMessage :
00169 self.init_actual_joints()
00170 for joint in self.lastMsg.joints_list :
00171 self.dict_pos[joint.joint_name]=joint.joint_position
00172 self.dict_tar[joint.joint_name]=joint.joint_target
00173 self.isFirstMessage = False
00174 self.isReady = True
00175
00176 def callback_arm(self, data):
00177 """
00178 @param data: The ROS message received which called the callback
00179 If the message is the first received, initializes the dictionnaries
00180 Else, it updates the lastMsg
00181 """
00182 self.lastArmMsg = data
00183 if self.isFirstMessageArm :
00184 for joint in self.lastArmMsg.joints_list :
00185 self.dict_arm_pos[joint.joint_name]=joint.joint_position
00186 self.dict_arm_tar[joint.joint_name]=joint.joint_target
00187
00188 def init_actual_joints(self):
00189 """
00190 Initializes the library with just the fingers actually connected
00191 """
00192 for joint_all in self.allJoints :
00193 for joint_msg in self.lastMsg.joints_list :
00194 if joint_msg.joint_name == joint_all.name:
00195 self.handJoints.append(joint_all)
00196
00197 def check_hand_type(self):
00198 """
00199 @return : true if some hand is detected
00200 """
00201 if self.check_etherCAT_hand_presence():
00202 return "etherCAT"
00203 elif self.check_gazebo_hand_presence():
00204 return "gazebo"
00205 elif self.check_CAN_hand_presence():
00206 return "CANhand"
00207 return None
00208
00209 def check_CAN_hand_presence(self):
00210 """
00211 @return : true if the CAN hand is detected
00212 """
00213 t = 0.0
00214 while not self.isReady:
00215 time.sleep(1.0)
00216 t = t+1.0
00217 rospy.loginfo("Waiting for service since "+str(t)+" seconds...")
00218 if t >= 5.0:
00219 rospy.logerr("No hand found. Are you sure the ROS hand is running ?")
00220 return False
00221 return True
00222
00223 def set_shadowhand_data_topic(self, topic):
00224 """
00225 @param topic: The new topic to be set as the hand publishing topic
00226 Set the library to listen to a new topic
00227 """
00228 print 'Changing subscriber to ' + topic
00229 self.sub = rospy.Subscriber(topic, joints_data ,self.callback)
00230
00231 def set_sendupdate_topic(self, topic):
00232 """
00233 @param topic: The new topic to be set as the hand subscribing topic
00234 Set the library to publish to a new topic
00235 """
00236 print 'Changing publisher to ' + topic
00237 self.pub = rospy.Publisher(topic,sendupdate, latch=True)
00238
00239 def sendupdate_from_dict(self, dicti):
00240 """
00241 @param dicti: Dictionnary containing all the targets to send, mapping the name of the joint to the value of its target
00242 Sends new targets to the hand from a dictionnary
00243 """
00244
00245 if (self.hand_type == "etherCAT") or (self.hand_type == "gazebo"):
00246 for join in dicti.keys():
00247
00248 if not self.eth_publishers.has_key(join):
00249 topic = "sh_"+ join.lower() + self.topic_ending+"/command"
00250 self.eth_publishers[join] = rospy.Publisher(topic, Float64, latch=True)
00251
00252 msg_to_send = Float64()
00253 msg_to_send.data = math.radians( float( dicti[join] ) )
00254 self.eth_publishers[join].publish(msg_to_send)
00255 elif self.hand_type == "CANhand":
00256 message = []
00257 for join in dicti.keys():
00258 message.append(joint(joint_name=join, joint_target=dicti[join]))
00259 self.pub.publish(sendupdate(len(message), message))
00260
00261 def sendupdate(self, jointName, angle=0):
00262 """
00263 @param jointName: Name of the joint to update
00264 @param angle: Target of the joint, 0 if not set
00265 Sends a new target for the specified joint
00266 """
00267 self.sendupdate_lock.acquire()
00268
00269 if (self.hand_type == "etherCAT") or (self.hand_type == "gazebo"):
00270 if not self.eth_publishers.has_key(jointName):
00271 topic = "sh_"+ jointName.lower() + self.topic_ending + "/command"
00272 self.eth_publishers[jointName] = rospy.Publisher(topic, Float64, latch=True)
00273
00274 msg_to_send = Float64()
00275 msg_to_send.data = math.radians( float( angle ) )
00276 self.eth_publishers[jointName].publish(msg_to_send)
00277 elif self.hand_type == "CANhand":
00278 message = [joint(joint_name=jointName, joint_target=angle)]
00279 self.pub.publish(sendupdate(len(message), message))
00280
00281 self.sendupdate_lock.release()
00282
00283 def sendupdate_arm_from_dict(self, dicti):
00284 """
00285 @param dicti: Dictionnary containing all the targets to send, mapping the name of the joint to the value of its target
00286 Sends new targets to the hand from a dictionnary
00287 """
00288 message = []
00289 for join in dicti.keys():
00290 message.append(joint(joint_name=join, joint_target=dicti[join]))
00291 self.pub_arm.publish(sendupdate(len(message), message))
00292
00293 def sendupdate_arm(self, jointName, angle=0):
00294 """
00295 @param jointName: Name of the joint to update
00296 @param angle: Target of the joint, 0 if not set
00297 Sends a new target for the specified joint
00298 """
00299 message = [joint(joint_name=jointName, joint_target=angle)]
00300 self.pub_arm.publish(sendupdate_arm(len(message), message))
00301
00302 def valueof(self, jointName):
00303 """
00304 @param jointName: Name of the joint to read the value
00305 @return: 'NaN' if the value is not correct, the actual position of the joint else
00306 """
00307 for joint in self.lastMsg.joints_list:
00308 if joint.joint_name == jointName:
00309 return float(joint.joint_position)
00310 for joint in self.lastArmMsg.joints_list:
00311 if joint.joint_name == jointName:
00312 return float(joint.joint_position)
00313 return 'NaN'
00314
00315 def has_arm(self):
00316 """
00317 @return : True if an arm is detected on the roscore
00318 """
00319 if not self.hasarm == 0:
00320 return self.hasarm
00321 self.hasarm = False
00322 if self.liste == 0:
00323 master = rosgraph.masterapi.Master('/rostopic')
00324 self.liste = master.getPublishedTopics('/')
00325 for topic_typ in self.liste :
00326 for topic in topic_typ:
00327 if 'sr_arm/shadowhand_data' in topic :
00328 self.hasarm = True
00329 return self.hasarm
00330
00331 def record_step_to_file(self, filename, grasp_as_xml):
00332 """
00333 @param filename: name (or path) of the file to save to
00334 @param grasp_as_xml: xml-formatted grasp
00335 Write the grasp at the end of the file, creates the file if does not exist
00336 """
00337 if os.path.exists(filename) :
00338 obj = open(filename, 'r')
00339 text = obj.readlines()
00340 obj.close()
00341 objWrite = open(filename,'w')
00342 for index in range(0,len(text)-1):
00343 objWrite.write(text[index])
00344 objWrite.write(grasp_as_xml)
00345 objWrite.write('</root>')
00346 objWrite.close()
00347 else :
00348 objWrite = open(filename,'w')
00349 objWrite.write('<root>\n')
00350 objWrite.write(grasp_as_xml)
00351 objWrite.write('</root>')
00352 objWrite.close()
00353
00354 def save_hand_position_to_file(self, filename):
00355 objFile=open(filename,'w')
00356 for key, value in self.dict_pos:
00357 objFile.write(key + ' ' + value + '\n')
00358 objFile.close()
00359
00360 def read_all_current_positions(self):
00361 """
00362 @return: dictionnary mapping joint names to actual positions
00363 Read all the positions in the lastMsg
00364 """
00365 if not self.isReady:
00366 return
00367 for joint in self.lastMsg.joints_list:
00368 self.dict_pos[joint.joint_name] = joint.joint_position
00369 return self.dict_pos
00370
00371 def read_all_current_targets(self):
00372 """
00373 @return: dictionnary mapping joint names to current targets
00374 Read all the targets in the lastMsg
00375 """
00376 for joint in self.lastMsg.joints_list:
00377 self.dict_tar[joint.joint_name] = joint.joint_target
00378 return self.dict_tar
00379
00380 def read_all_current_arm_positions(self):
00381 """
00382 @return: dictionnary mapping joint names to actual positions
00383 Read all the positions in the lastMsg
00384 """
00385 for joint in self.lastArmMsg.joints_list:
00386 self.dict_arm_pos[joint.joint_name] = joint.joint_position
00387 return self.dict_arm_pos
00388
00389 def read_all_current_arm_targets(self):
00390 """
00391 @return: dictionnary mapping joint names to actual targets
00392 Read all the targets in the lastMsg
00393 """
00394 for joint in self.lastArmMsg.joints_list:
00395 self.dict_arm_tar[joint.joint_name] = joint.joint_target
00396 return self.dict_arm_tar
00397
00398 def resend_targets(self):
00399 """
00400 Resend the targets read in the lastMsg to the hand
00401 """
00402 for key, value in self.dict_tar.items():
00403 self.sendupdate(jointName=key, angle=value)
00404
00405 def callVisualisationService(self, callList=0, reset = 0):
00406 """
00407 @param callList: dictionnary mapping joint names to information that should be displayed
00408 @param reset: flag used to tell if the parameters should be replaced by the new ones or just added to the previous ones
00409 Calls a ROS service to display various information in Rviz
00410 """
00411 if reset == 0:
00412 print 'no reset'
00413
00414 if reset == 1:
00415 print 'reset'
00416
00417 def check_etherCAT_hand_presence(self):
00418 """
00419 Only used to check if a real etherCAT hand is detected in the system
00420 check if something is being published to this topic, otherwise
00421 return false
00422 """
00423
00424 try:
00425 rospy.wait_for_message("joint_states", JointState, timeout = 0.2)
00426 except:
00427 rospy.logwarn("no message received from joint_states")
00428 return False
00429
00430 return True
00431
00432 def check_gazebo_hand_presence(self):
00433 """
00434 Only used to check if a Gazebo simulated (etherCAT protocol) hand is detected in the system
00435 check if something is being published to this topic, otherwise
00436 return false
00437 """
00438
00439 try:
00440 rospy.wait_for_message("gazebo/joint_states", JointState, timeout = 0.2)
00441 except:
00442 return False
00443
00444 return True
00445
00446 def activate_etherCAT_hand(self):
00447 """
00448 At the moment we just try to use the mixed position velocity controllers
00449 """
00450 success = True
00451 for joint_all in self.allJoints :
00452 self.topic_ending = "_mixed_position_velocity_controller"
00453 topic = "sh_"+ joint_all.name.lower() + self.topic_ending + "/state"
00454 success = True
00455 try:
00456 rospy.wait_for_message(topic, JointControllerState, timeout = 0.2)
00457 except:
00458 try:
00459 self.topic_ending = "_position_controller"
00460 topic = "sh_"+ joint_all.name.lower() + self.topic_ending + "/state"
00461 rospy.wait_for_message(topic, pr2_controllers_msgs.msg.JointControllerState, timeout = 0.2)
00462 except:
00463 success = False
00464
00465 if success:
00466 if self.topic_ending == "_mixed_position_velocity_controller":
00467 self.eth_subscribers[joint_all.name] = rospy.Subscriber(topic, JointControllerState, self.callback_ethercat_states, joint_all.name)
00468 else:
00469 self.eth_subscribers[joint_all.name] = rospy.Subscriber(topic, pr2_controllers_msgs.msg.JointControllerState, self.callback_ethercat_states, joint_all.name)
00470
00471 if len(self.eth_subscribers) > 0:
00472 return True
00473
00474 return False