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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:08:51