00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 """Generates a database of grasps
00019 """
00020
00021 from itertools import groupby
00022 import numpy, time, scipy
00023 import roslib
00024 from openravepy import *
00025 from cob_grasp_generation import analyzegrasp3d, grasp_query_utils
00026
00027
00028 class ORGraspGeneration:
00029 def __init__(self, viewer=False):
00030 self.env = None
00031 self.target = None
00032
00033 def setup_environment(self, object_name, gripper_type, viewer=False):
00034 if self.env == None:
00035 self.env = Environment()
00036 self.env.Load(roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/env/'+str(gripper_type)+'.env.xml')
00037
00038 if viewer:
00039 if self.env.GetViewer() == None:
00040 self.env.SetViewer('qtcoin')
00041 else:
00042 print "Viewer already loaded"
00043 else:
00044 print "Not using a viewer for OpenRAVE"
00045
00046 if self.target == None:
00047 self.target = self.env.ReadKinBodyURI(roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/meshes/'+str(object_name)+'.stl')
00048 self.env.Add(self.target,True)
00049
00050 if self.target.GetName() != object_name:
00051 print "Changing the target object"
00052 self.env.Remove(self.target)
00053 self.target = self.env.ReadKinBodyURI(roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/meshes/'+str(object_name)+'.stl')
00054 self.env.Add(self.target,True)
00055
00056 print "Environment set up!"
00057
00058 def generate_grasps(self, object_name, gripper_type, replan=False):
00059
00060 robot = self.env.GetRobots()[0]
00061 manip = robot.GetManipulator(gripper_type)
00062 gmodel = databases.grasping.GraspingModel(robot,self.target)
00063
00064
00065 tool_trafo = manip.GetLocalToolTransform()
00066 tool_trafo[2,3] = 0.0
00067 manip.SetLocalToolTransform(tool_trafo)
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085 options = self.configure_grasp_generation()
00086
00087 now_plan = time.time()
00088
00089
00090 if gmodel.load():
00091 if replan == True:
00092 print "Replanning database"
00093 gmodel.autogenerate(options)
00094 print "Successfully loaded a database"
00095 else:
00096 print "No database available"
00097 print "Generating a database"
00098 gmodel.autogenerate(options)
00099
00100
00101 end_plan = time.time()
00102 time_difference = int(end_plan - now_plan)
00103 print "GraspGeneration took: ", time_difference
00104
00105
00106
00107
00108
00109
00110
00111 validgrasps, validindicees = gmodel.computeValidGrasps(checkcollision=True, checkik=False)
00112
00113
00114 print "TotalNumValidGrasps: ",len(validgrasps)
00115
00116
00117 if len(validgrasps) == 0:
00118 print('No valid grasps generated')
00119 return []
00120 databases.grasping.RaveDestroy()
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145 grasps_to_file = []
00146 meta_info = []
00147 meta_info.append(object_name)
00148 meta_info.append(gripper_type)
00149 meta_info.append(time)
00150 grasps_to_file.append(meta_info)
00151
00152
00153 for graspnmb in range(0,len(validgrasps)):
00154
00155
00156 auto_fill_rest = False
00157
00158 grasp_to_file = []
00159 grasp_to_file.append(graspnmb)
00160 grasp_num = int(graspnmb)
00161
00162
00163 try:
00164 print "Grasp: ",graspnmb
00165 contacts,finalconfig,mindist,volume = gmodel.runGrasp(grasp=validgrasps[grasp_num], forceclosure=True)
00166 except:
00167 print "something went wrong"
00168 mindist = 0.0
00169 volume = 0.0
00170
00171
00172 direction = gmodel.getGlobalApproachDir(validgrasps[graspnmb])
00173
00174 transf = []
00175
00176 with gmodel.GripperVisibility(manip):
00177 with self.env:
00178 gmodel.setPreshape(validgrasps[graspnmb])
00179 Tgrasp = gmodel.getGlobalGraspTransform(validgrasps[graspnmb],collisionfree=True)
00180 Tdelta = numpy.dot(Tgrasp,numpy.linalg.inv(manip.GetEndEffectorTransform()))
00181 DOFValues = robot.GetActiveDOFValues()
00182 DOFValues[manip.GetGripperIndices()] = finalconfig[0][manip.GetGripperIndices()]
00183 robot.SetDOFValues(DOFValues)
00184 robot.SetTransform(numpy.dot(Tdelta,robot.GetTransform()))
00185 self.env.UpdatePublishedBodies()
00186 with self.target:
00187 self.target.SetTransform(numpy.eye(4))
00188 with gmodel.GripperVisibility(manip):
00189 with self.env:
00190 gmodel.setPreshape(validgrasps[graspnmb])
00191 Tgrasp = gmodel.getGlobalGraspTransform(validgrasps[graspnmb],collisionfree=True)
00192 Tdelta = numpy.dot(Tgrasp,numpy.linalg.inv(manip.GetEndEffectorTransform()))
00193 for link in manip.GetChildLinks():
00194 link.SetTransform(numpy.dot(Tdelta,link.GetTransform()))
00195 self.env.UpdatePublishedBodies()
00196
00197 transf = manip.GetEndEffectorTransform()
00198
00199 grasp_to_file.append(finalconfig[0][manip.GetGripperIndices()])
00200 grasp_to_file.append(transf)
00201
00202 grasp_to_file.append(mindist)
00203 grasp_to_file.append(volume)
00204
00205 forceclosure = validgrasps[graspnmb][gmodel.graspindices['forceclosure']]
00206 grasp_to_file.append(forceclosure)
00207 grasp_to_file.append(validindicees[graspnmb])
00208 grasp_to_file.append(direction)
00209
00210
00211
00212 grasps_to_file.append(grasp_to_file)
00213
00214 gmodel.getGlobalApproachDir(validgrasps[graspnmb])
00215
00216
00217 analyzegrasp3d.or_to_csv(grasps_to_file)
00218
00219 print('Finished.')
00220 databases.grasping.RaveDestroy()
00221 return len(validgrasps)
00222
00223 def configure_grasp_generation(self):
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243 preshape_array = []
00244
00245
00246 preshape = '0.0 -0.9854 0.9472 -0.9854 0.9472 -0.9854 0.9472'
00247 preshape_array.append(preshape)
00248 preshape = '0.0 -0.9854 0.47 -0.9854 0.47 -0.9854 0.47'
00249 preshape_array.append(preshape)
00250
00251
00252 options.preshapes = numpy.array(preshape_array)
00253
00254
00255
00256
00257
00258
00259
00260
00261 options.boxdelta = 0.05
00262
00263
00264
00265
00266
00267 standoff_array = [0.025, 0.075]
00268 options.standoffs = numpy.array(standoff_array)
00269
00270
00271
00272
00273 options.friction = 1.0
00274
00275
00276
00277
00278
00279
00280
00281
00282 options.normalanglerange = 0.0
00283
00284
00285
00286 options.directiondelta = 1
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296 return options
00297
00298 def show_grasp(self, object_name, gripper_type, grasp_id, sort_by_quality=False):
00299 self.setup_environment(object_name, gripper_type, viewer=True)
00300
00301 grasp_list = grasp_query_utils.get_grasp_list(object_name, gripper_type, sort_by_quality)
00302
00303
00304 robot = self.env.GetRobots()[0]
00305 manip = robot.GetManipulator(gripper_type)
00306 gmodel = databases.grasping.GraspingModel(robot,self.target)
00307
00308
00309 tool_trafo = manip.GetLocalToolTransform()
00310 tool_trafo[2,3] = 0.0
00311 manip.SetLocalToolTransform(tool_trafo)
00312
00313
00314
00315 grasp = grasp_list[int(grasp_id)]
00316 print 'Grasp ID: '+str(grasp['id'])
00317 print 'Grasp Quality epsilon: '+str(grasp['eps_l1'])
00318 print 'Grasp Quality volume: '+str(grasp['vol_l1'])
00319
00320
00321 with gmodel.GripperVisibility(manip):
00322 dof_array = [0]*27
00323 dof_array[7:13] =[float(grasp['sdh_finger_22_joint']),float(grasp['sdh_finger_23_joint']),float(grasp['sdh_knuckle_joint']),float(grasp['sdh_finger_12_joint']),float(grasp['sdh_finger_13_joint']),float(grasp['sdh_thumb_2_joint']),float(grasp['sdh_thumb_3_joint'])]
00324 robot.SetDOFValues(numpy.array(dof_array))
00325
00326
00327 mm_in_m = 0.001
00328 pos = [float(grasp['pos-x'])*mm_in_m, float(grasp['pos-y'])*mm_in_m, float(grasp['pos-z'])*mm_in_m]
00329 quat = [float(grasp['qw']), float(grasp['qx']), float(grasp['qy']), float(grasp['qz'])]
00330 Tgrasp = matrixFromPose(quat+pos)
00331
00332
00333 Tdelta = numpy.dot(Tgrasp,numpy.linalg.inv(manip.GetEndEffectorTransform()))
00334 for link in manip.GetChildLinks():
00335 link.SetTransform(numpy.dot(Tdelta,link.GetTransform()))
00336
00337
00338 time.sleep(1)
00339 self.env.UpdatePublishedBodies()
00340
00341