or_grasp_generation.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 """Generates a database of grasps
00019 """
00020 #libs and modules
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                 #robot
00060                 robot = self.env.GetRobots()[0]
00061                 manip = robot.GetManipulator(gripper_type) #make sure the manipulator in the collada file is named accordingly
00062                 gmodel = databases.grasping.GraspingModel(robot,self.target)
00063 
00064                 #TCP - transformed to hand wrist
00065                 tool_trafo = manip.GetLocalToolTransform()
00066                 tool_trafo[2,3] = 0.0
00067                 manip.SetLocalToolTransform(tool_trafo)
00068 
00069                 ### Options for GraspGeneration
00070                 #~ friction = None
00071                 #~ preshapes = None
00072                 #~ manipulatordirections = None
00073                 #~ approachrays = None
00074                 #~ standoffs = None
00075                 #~ rolls = None
00076                 #~ avoidlinks = None
00077                 #~ graspingnoise = None
00078                 #~ plannername = None
00079                 #~ normalanglerange = 0
00080                 #~ directiondelta=0
00081                 #~ translationstepmult=None
00082                 #~ finestep=None
00083                 ####
00084 
00085                 options = self.configure_grasp_generation()
00086 
00087                 now_plan = time.time()
00088 
00089                 ### Do actual GraspGeneration
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                 #time diff
00101                 end_plan = time.time()
00102                 time_difference = int(end_plan - now_plan)
00103                 print "GraspGeneration took: ", time_difference
00104 
00105                 ### GetValidGrasps now
00106                 #Return all validgrasps
00107                 #@OPTIONAL: We can return a desired number of grasps
00108                 #computeValidGrasps(startindex=0, checkcollision=True, checkik=True, checkgrasper=True, backupdist=0.0, returnnum=inf)
00109                 #Note: setting backupdist does somehow not effect the validgrasps list???
00110 
00111                 validgrasps, validindicees = gmodel.computeValidGrasps(checkcollision=True, checkik=False)
00112                 #validgrasps, validindicees = gmodel.computeValidGrasps(backupdist=0.025, checkcollision=True, checkik=False)   #opt1
00113                 #validgrasps, validindicees = gmodel.computeValidGrasps(backupdist=0.0, checkcollision=True, checkik=False)             #opt2
00114                 print "TotalNumValidGrasps: ",len(validgrasps)
00115 
00116                 #prevent from saving an empty file
00117                 if len(validgrasps) == 0:
00118                         print('No valid grasps generated')
00119                         return []
00120                         databases.grasping.RaveDestroy()
00121 
00122                 #~ backupdist_array = [0.025, 0.05, 0.075, 0.1]
00123                 #~ num_grasps=numpy.inf
00124                 #~ #num_grasps = 20
00125                 #~
00126                 #~ validgrasps = []
00127                 #~ validindicees = []
00128                 #~
00129                 #~ for bd in backupdist_array:
00130                         #~ ###GRASP-PLANNING
00131                         #~ #Return all validgrasps
00132                         #~ #@OPTIONAL: We can return a desired number of grasps
00133                         #~ #computeValidGrasps(startindex=0, checkcollision=True, checkik=True, checkgrasper=True, backupdist=0.0, returnnum=inf)
00134                         #~ validgrasps_bd, validindicees_bd = gmodel.computeValidGrasps(checkcollision=True, checkik=False, backupdist=bd, returnnum=num_grasps)
00135                         #~
00136                         #~ print "Backupdist: ",bd
00137                         #~ print "NumValidGrasps: ",len(validgrasps_bd)
00138                         #~
00139                         #~ validgrasps.extend(validgrasps_bd)
00140                         #~ validindicees.extend(validindicees_bd)
00141                 #~
00142                 #~ print "TotalNumValidGrasps: ",len(validgrasps)
00143 
00144                 ##Write all validgrasps to file
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                 #@todo: for debug, remove
00153                 for graspnmb in range(0,len(validgrasps)):
00154 
00155                         #for segmentation fault purposes
00156                         auto_fill_rest = False
00157 
00158                         grasp_to_file = []
00159                         grasp_to_file.append(graspnmb) #to file grasp number for id
00160                         grasp_num = int(graspnmb)
00161 
00162                         #calculate metric and final joint configuration
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                         #show grasp before calculating the correct transformation
00172                         direction = gmodel.getGlobalApproachDir(validgrasps[graspnmb])
00173                         #gmodel.showgrasp(validgrasps[graspnmb],collisionfree=True)
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                                                 # wait while environment is locked?
00197                                                 transf = manip.GetEndEffectorTransform()
00198 
00199                         grasp_to_file.append(finalconfig[0][manip.GetGripperIndices()])
00200                         grasp_to_file.append(transf)
00201                         #gmodel.showgrasp(validgrasps[graspnmb],collisionfree=True)
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                         #print "GlobApproachDir: ",gmodel.getGlobalApproachDir(validgrasps[i])
00210                         #SDH Joint Values - Beginnend mit Daumen(1) und die Zwei Finger GUZS nummeriert(2)(3)
00211                         #[Fingerwinkel(2), Fingerknick(2), Fingerrotation(2)(3), Fingerwinkel(3), Fingerknick(3), Fingerwinkel(1), Fingerknick(1)]
00212                         grasps_to_file.append(grasp_to_file)
00213 
00214                         gmodel.getGlobalApproachDir(validgrasps[graspnmb])
00215 
00216                 #Create a csv file if needed
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                 ### Options for GraspGeneration
00225                 #~ 'preshapes'
00226                 #~ 'manipulatordirections'
00227                 #~ 'boxdelta'
00228                 #~ 'spheredelta'
00229                 #~ 'standoffs'
00230                 #~ 'rolls'
00231                 #~ 'friction'
00232                 #~ 'avoidlinks'
00233                 #~ 'graspingnoise'
00234                 #~ 'plannername'
00235                 #~ 'normalanglerange'
00236                 #~ 'directiondelta'
00237                 #~ 'translationstepmult'
00238                 #~ 'finestep'
00239                 #~ 'numthreads'
00240                 ####
00241 
00242                 #preshape --- default is 'something strange' ?
00243                 preshape_array = []
00244                 #preshape = '1.047 -0.785 1.047 -0.785 1.047 -0.785 1.047' # spheric_open
00245                 #preshape_array.append(preshape)
00246                 preshape = '0.0 -0.9854 0.9472 -0.9854 0.9472 -0.9854 0.9472' # cylindric_open
00247                 preshape_array.append(preshape)
00248                 preshape = '0.0 -0.9854 0.47 -0.9854 0.47 -0.9854 0.47' # fingers_half_straight_open
00249                 preshape_array.append(preshape)
00250                 #preshape = '0.0 -0.9854 0.0 -0.9854 0.0 -0.9854 0.0' # fingers_straight_open
00251                 #preshape_array.append(preshape)
00252                 options.preshapes = numpy.array(preshape_array)
00253 
00254                 #manipulatordirections --- default is [0.0,1.0,0.0] ?
00255                 #~ md_array = []
00256                 #~ direction1 = '0.0 0.0 1.0' #along z-axis -- points 'out of sdh'
00257                 #~ md_array.append(direction1)
00258                 #~ options.manipulatordirections = numpy.array(md_array)
00259 
00260                 #boxdelta --- default is 0.02
00261                 options.boxdelta = 0.05
00262 
00263                 #spheredelta --- default is 0.1
00264                 #~ only used if boxdelta is not set
00265 
00266                 #standoffs --- default is [0.0, 0.025] --- 0.0 is bad as we will hit the object!
00267                 standoff_array = [0.025, 0.075]
00268                 options.standoffs = numpy.array(standoff_array)
00269 
00270                 #rolls --- default is [0.0, pi/2, pi, 3*pi/2, 2*pi]
00271 
00272                 #fricion
00273                 options.friction = 1.0 #coefficient of static friction in graspit: rubber-<xobject> = 1
00274 
00275                 #avoidlinks --- default is None ?
00276 
00277                 #graspingnoise --- ?
00278 
00279                 #plannername --- ?
00280 
00281                 #normalanglerange --- default is 0.0 - used for computeXXXApproachRays
00282                 options.normalanglerange = 0.0
00283                 #options.normalanglerange = 15
00284 
00285                 #directiondelta --- default is 0.4 - used for computeXXXApproachRays
00286                 options.directiondelta = 1
00287                 #options.directiondelta = 5
00288 
00289                 #translationstepmult --- default is None ?
00290 
00291                 #finestep
00292 
00293                 #numthreads --- default is 1
00294                 #options.numthreads = 4         #--- multiple threads somehow not working
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                 #robot
00304                 robot = self.env.GetRobots()[0]
00305                 manip = robot.GetManipulator(gripper_type) #make sure the manipulator in the collada file is named accordingly
00306                 gmodel = databases.grasping.GraspingModel(robot,self.target)
00307 
00308                 #TCP - transformed to hand wrist
00309                 tool_trafo = manip.GetLocalToolTransform()
00310                 tool_trafo[2,3] = 0.0
00311                 manip.SetLocalToolTransform(tool_trafo)
00312 
00313                 #Show the grasps
00314                 #SetDOFValues
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                 #print grasp
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                         #matrix from pose
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                         #transform robot
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                         #publish update of scene
00338                         time.sleep(1)
00339                         self.env.UpdatePublishedBodies()
00340 
00341 


cob_grasp_generation
Author(s): Witalij Siebert, Felix Messmer
autogenerated on Thu Jun 6 2019 21:22:47