$search
00001 #!/usr/bin/python 00002 00003 import roslib 00004 roslib.load_manifest('srs_states') 00005 import rospy 00006 import smach 00007 import smach_ros 00008 00009 import copy 00010 00011 from simple_script_server import * 00012 sss = simple_script_server() 00013 00014 import tf 00015 from tf.transformations import * 00016 from kinematics_msgs.srv import * 00017 00018 #this should be in manipulation_msgs 00019 from cob_mmcontroller.msg import * 00020 00021 from shared_state_information import * 00022 #import grasping_functions 00023 00024 00025 00026 ## Select grasp state 00027 # 00028 # This state select a grasping strategy. A high object will be grasped from the side, a low one from top. 00029 class select_simple_grasp(smach.State): 00030 00031 def __init__(self): 00032 smach.State.__init__( 00033 self, 00034 outcomes=['succeeded', 'failed', 'preempted'], 00035 input_keys=['object'], 00036 output_keys=['grasp_categorisation']) 00037 00038 """ 00039 Very simple grasp selection 00040 This need to be transfered into symbolic grounding service 00041 """ 00042 self.height_switch = 0.5 # Switch to select top or side grasp using the height of the object over the ground in [m]. 00043 00044 #self.listener = tf.TransformListener() 00045 00046 #default grasp categorisation 00047 self.grasp_categorisation = 'side' 00048 00049 def execute(self, userdata): 00050 00051 global listener 00052 00053 rospy.loginfo('userdata is %s', userdata) 00054 try: 00055 # transform object_pose into base_link 00056 object_pose_in = userdata.object.pose 00057 print object_pose_in 00058 object_pose_in.header.stamp = listener.getLatestCommonTime("/base_link",object_pose_in.header.frame_id) 00059 object_pose_bl = listener.transformPose("/base_link", object_pose_in) 00060 except rospy.ROSException, e: 00061 print "Transformation not possible: %s"%e 00062 return 'failed' 00063 00064 if object_pose_bl.pose.position.z >= self.height_switch: #TODO how to select grasps for objects within a cabinet or shelf? 00065 userdata.grasp_categorisation='side' 00066 else: 00067 userdata.grasp_categorisation= 'top' 00068 00069 if self.preempt_requested(): 00070 self.service_preempt() 00071 return 'preempted' 00072 00073 return 'succeeded' 00074 00075 00076 ## Grasp general state 00077 # 00078 # This state will grasp an object with a side grasp 00079 class simple_grasp(smach.State): 00080 00081 def __init__(self, max_retries = 1): 00082 smach.State.__init__( 00083 self, 00084 outcomes=['succeeded', 'retry', 'no_more_retries', 'failed', 'preempted'], 00085 input_keys=['object','grasp_categorisation']) 00086 00087 self.max_retries = max_retries 00088 self.retries = 0 00089 self.iks = rospy.ServiceProxy('/arm_kinematics/get_ik', GetPositionIK) 00090 #self.listener = tf.TransformListener() 00091 self.stiffness = rospy.ServiceProxy('/arm_controller/set_joint_stiffness', SetJointStiffness) 00092 00093 00094 def callIKSolver(self, current_pose, goal_pose): 00095 req = GetPositionIKRequest() 00096 req.ik_request.ik_link_name = "sdh_grasp_link" 00097 req.ik_request.ik_seed_state.joint_state.position = current_pose 00098 req.ik_request.pose_stamped = goal_pose 00099 resp = self.iks(req) 00100 result = [] 00101 for o in resp.solution.joint_state.position: 00102 result.append(o) 00103 return (result, resp.error_code) 00104 00105 def execute(self, userdata): 00106 global current_task_info 00107 00108 if not current_task_info.object_in_hand: #no object in hand 00109 00110 if self.preempt_requested(): 00111 self.service_preempt() 00112 return 'preempted' 00113 00114 global listener 00115 # check if maximum retries reached 00116 print self.retries 00117 print self.max_retries 00118 if self.retries > self.max_retries: 00119 self.retries = 0 00120 return 'no_more_retries' 00121 00122 # transform object_pose into base_link 00123 object_pose_in = userdata.object.pose 00124 object_pose_in.header.stamp = listener.getLatestCommonTime("/base_link",object_pose_in.header.frame_id) 00125 object_pose_bl = listener.transformPose("/base_link", object_pose_in) 00126 00127 00128 if userdata.grasp_categorisation == 'side': 00129 # make arm soft TODO: handle stiffness for schunk arm 00130 try: 00131 self.stiffness([300,300,300,100,100,100,100]) 00132 except rospy.ServiceException, e: 00133 print "Service call failed: %s"%e 00134 self.retries = 0 00135 return 'failed' 00136 00137 [new_x, new_y, new_z, new_w] = tf.transformations.quaternion_from_euler(-1.552, -0.042, 2.481) # rpy 00138 object_pose_bl.pose.orientation.x = new_x 00139 object_pose_bl.pose.orientation.y = new_y 00140 object_pose_bl.pose.orientation.z = new_z 00141 object_pose_bl.pose.orientation.w = new_w 00142 00143 # FIXME: this is calibration between camera and hand and should be removed from scripting level 00144 object_pose_bl.pose.position.x = object_pose_bl.pose.position.x #- 0.06 #- 0.08 00145 object_pose_bl.pose.position.y = object_pose_bl.pose.position.y #- 0.05 00146 object_pose_bl.pose.position.z = object_pose_bl.pose.position.z #- 0.1 00147 00148 # calculate pre and post grasp positions 00149 pre_grasp_bl = PoseStamped() 00150 post_grasp_bl = PoseStamped() 00151 pre_grasp_bl = copy.deepcopy(object_pose_bl) 00152 post_grasp_bl = copy.deepcopy(object_pose_bl) 00153 00154 #pre_grasp_bl.pose.position.x = pre_grasp_bl.pose.position.x + 0.10 # x offset for pre grasp position 00155 #pre_grasp_bl.pose.position.y = pre_grasp_bl.pose.position.y + 0.10 # y offset for pre grasp position 00156 #post_grasp_bl.pose.position.x = post_grasp_bl.pose.position.x + 0.05 # x offset for post grasp position 00157 #post_grasp_bl.pose.position.z = post_grasp_bl.pose.position.z + 0.15 # z offset for post grasp position 00158 00159 pre_grasp_bl.pose.position.x = pre_grasp_bl.pose.position.x + 0.10 # x offset for pre grasp position 00160 pre_grasp_bl.pose.position.y = pre_grasp_bl.pose.position.y + 0.10 # y offset for pre grasp position 00161 pre_grasp_bl.pose.position.z = pre_grasp_bl.pose.position.z + 0.2 # z offset for pre grasp position 00162 post_grasp_bl.pose.position.x = post_grasp_bl.pose.position.x + 0.05 # x offset for post grasp position 00163 post_grasp_bl.pose.position.z = post_grasp_bl.pose.position.z + 0.17 # z offset for post grasp position 00164 00165 elif userdata.grasp_categorisation == 'top': 00166 try: 00167 self.stiffness([100,100,100,100,100,100,100]) 00168 except rospy.ServiceException, e: 00169 print "Service call failed: %s"%e 00170 self.retries = 0 00171 return 'failed' 00172 00173 # use a predefined (fixed) orientation for object_pose_bl 00174 [new_x, new_y, new_z, new_w] = tf.transformations.quaternion_from_euler(3.121, 0.077, -2.662) # rpy 00175 object_pose_bl.pose.orientation.x = new_x 00176 object_pose_bl.pose.orientation.y = new_y 00177 object_pose_bl.pose.orientation.z = new_z 00178 object_pose_bl.pose.orientation.w = new_w 00179 00180 # FIXME: this is calibration between camera and hand and should be removed from scripting level 00181 object_pose_bl.pose.position.x = object_pose_bl.pose.position.x #-0.04 #- 0.08 00182 object_pose_bl.pose.position.y = object_pose_bl.pose.position.y# + 0.02 00183 object_pose_bl.pose.position.z = object_pose_bl.pose.position.z #+ 0.07 00184 00185 # calculate pre and post grasp positions 00186 pre_grasp_bl = PoseStamped() 00187 post_grasp_bl = PoseStamped() 00188 pre_grasp_bl = copy.deepcopy(object_pose_bl) 00189 post_grasp_bl = copy.deepcopy(object_pose_bl) 00190 00191 pre_grasp_bl.pose.position.z = pre_grasp_bl.pose.position.z + 0.18 # z offset for pre grasp position 00192 post_grasp_bl.pose.position.x = post_grasp_bl.pose.position.x + 0.05 # x offset for post grasp position 00193 post_grasp_bl.pose.position.z = post_grasp_bl.pose.position.z + 0.15 # z offset for post grasp position 00194 else: 00195 return 'failed' 00196 #unknown categorisation 00197 00198 00199 00200 # calculate ik solutions for pre grasp configuration 00201 if userdata.grasp_categorisation == 'top': 00202 arm_pre_grasp = rospy.get_param("/script_server/arm/pregrasp_top") 00203 else: 00204 # userdata.grasp_categorisation == 'side': 00205 arm_pre_grasp = rospy.get_param("/script_server/arm/pregrasp") 00206 00207 (pre_grasp_conf, error_code) = self.callIKSolver(arm_pre_grasp[0], pre_grasp_bl) 00208 00209 if(error_code.val != error_code.SUCCESS): 00210 rospy.logerr("Ik pre_grasp Failed") 00211 self.retries += 1 00212 return 'retry' 00213 00214 # calculate ik solutions for grasp configuration 00215 (grasp_conf, error_code) = self.callIKSolver(pre_grasp_conf, object_pose_bl) 00216 if(error_code.val != error_code.SUCCESS): 00217 rospy.logerr("Ik grasp Failed") 00218 self.retries += 1 00219 return 'retry' 00220 00221 # calculate ik solutions for pre grasp configuration 00222 (post_grasp_conf, error_code) = self.callIKSolver(grasp_conf, post_grasp_bl) 00223 if(error_code.val != error_code.SUCCESS): 00224 rospy.logerr("Ik post_grasp Failed") 00225 self.retries += 1 00226 return 'retry' 00227 00228 # execute grasp 00229 if self.preempt_requested(): 00230 self.service_preempt() 00231 return 'preempted' 00232 00233 sss.say([current_task_info.speaking_language['Grasp'] + userdata.object.label ],False) 00234 sss.move("torso","home") 00235 handle_arm = sss.move("arm", [pre_grasp_conf , grasp_conf],False) 00236 00237 if userdata.grasp_categorisation == 'side': 00238 sss.move("sdh", "cylopen") 00239 elif userdata.grasp_categorisation == 'top': 00240 sss.move("sdh", "spheropen") 00241 else: 00242 return 'failed' 00243 00244 if self.preempt_requested(): 00245 self.service_preempt() 00246 handle_arm.client.cancel_goal() 00247 return 'preempted' 00248 else: 00249 handle_arm.wait() 00250 00251 00252 if self.preempt_requested(): 00253 self.service_preempt() 00254 return 'preempted' 00255 else: 00256 if userdata.grasp_categorisation == 'side': 00257 sss.move("sdh", "cylclosed") 00258 elif userdata.grasp_categorisation == 'top': 00259 sss.move("sdh", "spherclosed") 00260 else: 00261 return 'failed' 00262 #unknown categorisation 00263 00264 #object is already in hand 00265 current_task_info.object_in_hand = True 00266 #object graspped, any previous detection is not valid anymore 00267 current_task_info.set_object_identification_state(False) 00268 #New object grasp, post grasp adjustment might be required 00269 current_task_info.set_post_grasp_adjustment_state(False) 00270 00271 sss.move("arm", [post_grasp_conf, "hold"]) 00272 self.retries = 0 00273 return 'succeeded' 00274