analyzegrasp3d.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 """Analyze Grasp 3D - own module: a collection of several function for analyzing the grasps
00019 """
00020 from openravepy import *
00021 import numpy, time, scipy, csv, os
00022 import roslib.packages
00023 
00024 #converts all openrave grasps to csv format for scripting
00025 #input-first-line (meta-info): object_name, gripper_type, time (@todo: add planner infos)
00026 #input-struct: number, jointconf, trafo, epsilon, volume, forceclosure, validindicees, direction
00027 def or_to_csv(validgrasps):
00028         meta_info = validgrasps[0]
00029         object_name = meta_info[0]
00030         gripper_type = meta_info[1]
00031 
00032         #create directories
00033         directory = roslib.packages.get_pkg_dir('cob_grasp_generation')+'/files/database/'+object_name
00034         if not os.path.exists(directory):
00035                 os.makedirs(directory)
00036         pathname_out = directory+'/'+gripper_type+'_'+object_name+'.csv'
00037         f_out = open(pathname_out, 'w+')
00038 
00039         wr = csv.writer(f_out, delimiter=',', quotechar='"', quoting=csv.QUOTE_ALL)
00040         wr.writerow(['id', 'object', 'sdh_knuckle_joint', 'sdh_finger_12_joint', 'sdh_finger_13_joint', 'sdh_finger_22_joint', 'sdh_finger_23_joint', 'sdh_thumb_2_joint', 'sdh_thumb_3_joint', 'direction', 'qw', 'qx', 'qy', 'qz','pos-x', 'pos-y', 'pos-z', 'eps_l1', 'vol_l1'])
00041         # ToDo: This will not work for grippers other than SDH
00042 
00043         for i in range (1,len(validgrasps)): #because line 0 is meta-info
00044                 row = [] #create/empty row for new grasp
00045                 actual_grasp = validgrasps[i]
00046                 row.append(str(actual_grasp[0])) #ID
00047                 row.append(object_name)
00048 
00049                 ##SOLL
00050                 #SDH Joint Values - Beginnend mit Daumen(1) und die Zwei Finger GUZS nummeriert(2)(3)
00051                 #[Fingerwinkel(2)(3), Fingerwinkel(2), Fingerknick(2), Fingerwinkel(3), Fingerknick(3), Fingerwinkel(1), Fingerknick(1)]
00052                 joint_values = actual_grasp[1]
00053 
00054                 #Check Knuckle_joint of SDH for values < 0
00055                 #Reason: Openrave generates some zero values that are slighlty below zero
00056                 if joint_values[0] < 0:
00057                         joint_values[0] = 0
00058 
00059                 #assign joint values in the right order
00060                 joint_values_sorted = [joint_values[0], joint_values[3], joint_values[4], joint_values[1], joint_values[2], joint_values[5], joint_values[6]]
00061                 for i in range(0,len(joint_values)):
00062                         row.append(joint_values_sorted[i])
00063 
00064                 #grasp-direction
00065                 globApproach = actual_grasp[7] #globalApproachDir
00066                 if globApproach[2] < -0.7: #if hand approaches > 63 degrees
00067                         row.append('TOP')
00068                 else:
00069                         row.append('SIDE')
00070 
00071                 #convert 4x4 matrix to pose
00072                 trafo4x4 = actual_grasp[2]
00073                 m_in_mm = 1000
00074                 pose = poseFromMatrix(trafo4x4) #returns [w, q0, q1, q2, x, y, z]
00075                 pose[4] = m_in_mm * pose[4] #x-koord
00076                 pose[5] = m_in_mm * pose[5] #y-koord
00077                 pose[6] = m_in_mm * pose[6] #z-koord
00078                 for i in range(0,len(pose)):
00079                         row.append(pose[i])
00080 
00081                 #quality
00082                 row.append("%.9f" % actual_grasp[3]) #epsilon with precision
00083                 row.append("%.9f" % actual_grasp[4]) #volume with precision
00084 
00085                 #misc
00086                 row.append(actual_grasp[6]) #validindicees
00087 
00088                 #write this grasp as row to file
00089                 if (not actual_grasp[3] == 0.0) and (not actual_grasp[4] == 0.0):
00090                         wr.writerow(row)
00091 
00092         f_out.close()
00093         print "Finished."


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