$search
00001 #!/usr/bin/python 00002 ################################################################# 00003 ##\file 00004 # 00005 # \note 00006 # Copyright (c) 2012 \n 00007 # Robotnik Automation SLL \n\n 00008 # 00009 ################################################################# 00010 # 00011 # \note 00012 # Project name: srs 00013 # \note 00014 # ROS stack name: srs 00015 # \note 00016 # ROS package name: srs_grasping 00017 # 00018 # \author 00019 # Author: Manuel Rodriguez, email:mrodriguez@robotnik.es 00020 # \author 00021 # Supervised by: Manuel Rodriguez, email:mrodriguez@robotnik.es 00022 # 00023 # \date Date of creation: March 2012 00024 # 00025 # \brief 00026 # Implements a service that returns all the feasible grasping configurations for a given object_id and target pose. 00027 # 00028 ################################################################# 00029 # 00030 # Redistribution and use in source and binary forms, with or without 00031 # modification, are permitted provided that the following conditions are met: 00032 # 00033 # - Redistributions of source code must retain the above copyright 00034 # notice, this list of conditions and the following disclaimer. \n 00035 # - Redistributions in binary form must reproduce the above copyright 00036 # notice, this list of conditions and the following disclaimer in the 00037 # documentation and/or other materials provided with the distribution. \n 00038 # - Neither the name of the Robotnik Automation SLL nor the names of its 00039 # contributors may be used to endorse or promote products derived from 00040 # this software without specific prior written permission. \n 00041 # 00042 # This program is free software: you can redistribute it and/or modify 00043 # it under the terms of the GNU Lesser General Public License LGPL as 00044 # published by the Free Software Foundation, either version 3 of the 00045 # License, or (at your option) any later version. 00046 # 00047 # This program is distributed in the hope that it will be useful, 00048 # but WITHOUT ANY WARRANTY; without even the implied warranty of 00049 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00050 # GNU Lesser General Public License LGPL for more details. 00051 # 00052 # You should have received a copy of the GNU Lesser General Public 00053 # License LGPL along with this program. 00054 # If not, see <http://www.gnu.org/licenses/>. 00055 # 00056 ################################################################# 00057 00058 import roslib 00059 roslib.load_manifest('srs_grasping') 00060 import tf 00061 import rospy 00062 import time 00063 import grasping_functions 00064 00065 from srs_grasping.srv import * 00066 from srs_msgs.msg import * 00067 from pr2_controllers_msgs.msg import * 00068 from geometry_msgs.msg import * 00069 from kinematics_msgs.srv import * 00070 from srs_msgs.msg import GraspingErrorCodes 00071 00072 class get_feasible_grasps(): 00073 00074 def __init__(self): 00075 00076 self.ik_loop_reply = 1; 00077 self.finger_correction = -1; 00078 self.cjc = [] 00079 self.cylopen_position = [[[0.09121056454806604, 0.03300469295835018, 0.1386980387655565],[0.01977019790965633, 6.428768666637955e-07, 0.9998045500082638, -3.251111695101345e-05]], [[0.01905, 0.033, 0.091],[0.47359137769338583, 1.5399994595997778e-05, 0.880744688270724, -2.863959117221133e-05]], [[-0.11021758805551472, 0.0, 0.13877808854293133],[0.0, -0.019200739055054376, 0.0, 0.9998156488171905]]] 00080 self.spheropen_position = [[[0.04967501468386526, 0.08596897096059274, 0.15214447310255375],[-0.11284765597435997, -0.06510645561927879, 0.8587963331213594, -0.49547493800907255]], [[0.01905, 0.033, 0.091],[0.3316048124188912, 0.19131645949114948, 0.8001899672091825, -0.4616625142744111]], [[-0.0992496375660626, 0.0, 0.1521898252840332],[0.0, 0.13060867295881992, 0.0, 0.9914339990881572]]] 00081 00082 self.listener = tf.TransformListener(True, rospy.Duration(10.0)) 00083 self.arm_state = rospy.Subscriber("/arm_controller/state", JointTrajectoryControllerState, self.get_joint_state); 00084 00085 rospy.loginfo("Waiting /arm_kinematics/get_constraint_aware_ik service..."); 00086 rospy.wait_for_service('/arm_kinematics/get_constraint_aware_ik') 00087 rospy.loginfo("/arm_kinematics/get_constraint_aware_ik is ready."); 00088 00089 rospy.loginfo("Waiting /get_db_grasps service..."); 00090 rospy.wait_for_service('/get_db_grasps') 00091 self.client = rospy.ServiceProxy('/get_db_grasps', GetDBGrasps) 00092 rospy.loginfo("/get_feasible_grasps service is ready."); 00093 00094 00095 def get_feasible_grasps(self, request): 00096 x = time.time(); 00097 rospy.loginfo("/get_feasible_grasps service has been called..."); 00098 00099 if len(request.pregrasp_offsets) != 2: 00100 print "pregrasps_offsets value must be an array with length 2: [X,Z]" 00101 print "Using default values: [0.2, 0.0]" 00102 00103 client_response = self.client(request.object_id) 00104 grasp_configuration = client_response.grasp_configuration; 00105 error_code = client_response.error_code.val 00106 00107 #current_joint_configuration 00108 while self.arm_state.get_num_connections() == 0: 00109 time.sleep(0.3); 00110 continue; 00111 00112 rotacion = grasping_functions.graspingutils.rotation_matrix(request.object_pose); 00113 resp = GetFeasibleGraspsResponse(); 00114 resp.error_code.val = 0; 00115 resp.feasible_grasp_available = False; 00116 resp.grasp_configuration = [] 00117 00118 if error_code == GraspingErrorCodes.SUCCESS: 00119 00120 for grasp_configuration in grasp_configuration: 00121 pre_trans = rotacion * grasping_functions.graspingutils.matrix_from_pose(grasp_configuration.pre_grasp.pose); 00122 grasp_trans = rotacion * grasping_functions.graspingutils.matrix_from_pose(grasp_configuration.grasp.pose); 00123 00124 pre = grasping_functions.graspingutils.pose_from_matrix(pre_trans); 00125 g = grasping_functions.graspingutils.pose_from_matrix(grasp_trans); 00126 00127 category = grasping_functions.graspingutils.get_grasp_category(pre.pose.position, g.pose.position); 00128 fpos = self.get_finger_positions(category) 00129 nvg = FeasibleGrasp(grasp_configuration.sdh_joint_values, "/sdh_palm_link", g, pre, category); 00130 pre.pose = grasping_functions.graspingutils.set_pregrasp_offsets(category, pre.pose, request.pregrasp_offsets); 00131 00132 if (grasping_functions.graspingutils.valid_grasp(category)) and (not self.checkCollisions(fpos, nvg, request.object_pose)): 00133 class FeasibleGraspFound(Exception): pass 00134 try: 00135 for w in range(0, self.ik_loop_reply): 00136 (pgc, error) = grasping_functions.graspingutils.callIKSolver(self.cjc, pre); 00137 if(error.val == error.SUCCESS): 00138 for k in range(0,self.ik_loop_reply): 00139 (gc, error) = grasping_functions.graspingutils.callIKSolver(pgc, g); 00140 if(error.val == error.SUCCESS): 00141 raise FeasibleGraspFound(); 00142 except FeasibleGraspFound: 00143 resp.feasible_grasp_available = True; 00144 resp.grasp_configuration.append(nvg); 00145 resp.error_code.val = GraspingErrorCodes.SUCCESS 00146 00147 #order grasps 00148 if len(resp.grasp_configuration) > 0: 00149 (resp.grasp_configuration).sort(); 00150 else: 00151 resp.error_code.val = GraspingErrorCodes.GOAL_UNREACHABLE 00152 else: 00153 resp.error_code.val = error_code; 00154 00155 00156 rospy.loginfo(str(len(resp.grasp_configuration))+" valid grasps for this values."); 00157 rospy.loginfo("/get_feasible_grasps call has finished with error_code: "+str(resp.error_code)); 00158 print "Time employed: " + str(time.time() - x); 00159 print "---------------------------------------"; 00160 return resp; 00161 00162 00163 00164 def __cmp__(self, other): 00165 if other.grasp.position.z > self.grasp.position.z: 00166 return 1 00167 elif other.grasp.position.z < self.grasp.position.z: 00168 return -1 00169 else: 00170 return 0 00171 00172 00173 def get_joint_state(self, msg): 00174 self.cjc = list(msg.desired.positions); 00175 00176 00177 def get_finger_positions(self, category): 00178 fing_pos = []; 00179 trans = (self.cylopen_position, self.spheropen_position)[category == "TOP"] 00180 00181 fp1 = PoseStamped(); 00182 fp2 = PoseStamped(); 00183 fp3 = PoseStamped(); 00184 00185 for finger in range(0,len(trans)): 00186 fp1.pose.position.x = trans[finger][0][0] 00187 fp1.pose.position.y = trans[finger][0][1] 00188 fp1.pose.position.z = trans[finger][0][2] 00189 00190 fp1.pose.orientation.x = trans[finger][1][0] 00191 fp1.pose.orientation.y = trans[finger][1][1] 00192 fp1.pose.orientation.z = trans[finger][1][2] 00193 fp1.pose.orientation.w = trans[finger][1][3] 00194 00195 fp1.header.frame_id = "/sdh_finger_13_link" 00196 fp2.header.frame_id = "/sdh_finger_23_link" 00197 fp3.header.frame_id = "/sdh_thumb_3_link" 00198 fing_pos.append(fp1); 00199 fing_pos.append(fp2); 00200 fing_pos.append(fp3); 00201 00202 return fing_pos; 00203 00204 00205 def transform_finger_positions(self, fpositions, g): 00206 response = []; 00207 00208 for finger_pos in fpositions: 00209 ps = PoseStamped(); 00210 ps.header.stamp = self.listener.getLatestCommonTime("/sdh_palm_link", finger_pos.header.frame_id); 00211 ps = self.listener.transformPose("/sdh_palm_link", finger_pos); 00212 00213 #transform to object position 00214 matrix = grasping_functions.graspingutils.matrix_from_pose(g) * grasping_functions.graspingutils.matrix_from_pose(ps.pose); 00215 response.append(grasping_functions.graspingutils.pose_from_matrix(matrix)); 00216 00217 return response; 00218 00219 00220 def checkCollisions(self, fpositions, nvg, obj_pose): 00221 00222 self.finger_correction = (0, -0.0685)[nvg.category == "TOP"]; 00223 finger_pos = self.transform_finger_positions(fpositions, nvg.grasp.pose); 00224 00225 for fp in finger_pos: 00226 if (obj_pose.position.z + 0.05)> (fp.pose.position.z + self.finger_correction): 00227 return True; 00228 return False; 00229 00230 00231 def get_feasible_grasps_server(self): 00232 s = rospy.Service('/get_feasible_grasps', GetFeasibleGrasps, self.get_feasible_grasps); 00233 00234 00235 ## Main routine for running the grasp server 00236 if __name__ == '__main__': 00237 rospy.init_node('get_feasible_grasps'); 00238 SCRIPT = get_feasible_grasps(); 00239 SCRIPT.get_feasible_grasps_server(); 00240 rospy.spin();