$search
00001 #!/usr/bin/env python 00002 00003 # 00004 # Software License Agreement (BSD License) 00005 # 00006 # Copyright (c) 2010, Willow Garage, Inc. 00007 # All rights reserved. 00008 # 00009 # Redistribution and use in source and binary forms, with or without 00010 # modification, are permitted provided that the following conditions 00011 # are met: 00012 # 00013 # * Redistributions of source code must retain the above copyright 00014 # notice, this list of conditions and the following disclaimer. 00015 # * Redistributions in binary form must reproduce the above 00016 # copyright notice, this list of conditions and the following 00017 # disclaimer in the documentation and/or other materials provided 00018 # with the distribution. 00019 # * Neither the name of Willow Garage, Inc. nor the names of its 00020 # contributors may be used to endorse or promote products derived 00021 # from this software without specific prior written permission. 00022 # 00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 # POSSIBILITY OF SUCH DAMAGE. 00035 # 00036 # \author Aitor Aldoma 00037 # 00038 # Receives two parameters: 00039 # * ply_file path 00040 # * model_id 00041 # and computes stable planes, create views and the associated pose for each view 00042 # of the model and starts the normal computation + vfh descriptor for each one 00043 # of the views. 00044 00045 import roslib 00046 roslib.load_manifest('vfh_recognizer_fs') 00047 from vfh_recognizer_fs.srv import * 00048 00049 import rospy 00050 import sys 00051 import vtk 00052 import pickle 00053 00054 00055 import os 00056 import tf.transformations as tfTransformations 00057 import numpy 00058 from geometry_msgs.msg import Pose 00059 from sensor_msgs.msg import PointCloud2, PointField 00060 from std_msgs.msg import Header, Int32 as stdMsgInt32 00061 from std_msgs.msg import String as stdMsgString 00062 00063 #should import from vfh_recognition! 00064 import roslib.packages 00065 sys.path.append(roslib.packages.get_pkg_dir('vfh_recognition') + "/nodes") 00066 from utils.tesselatedSphere import TesselatedSphere 00067 import views_generator.views_generator as views_generator 00068 from utils.visualize import Visualizer 00069 00070 #this will be later in a separate file 00071 import ctypes 00072 import math 00073 import struct 00074 00075 #sys.path.append("..") 00076 #from utils.tesselatedSphere import TesselatedSphere 00077 00078 00079 _DATATYPES = {} 00080 _DATATYPES[PointField.INT8] = ('b', 1) 00081 _DATATYPES[PointField.UINT8] = ('B', 1) 00082 _DATATYPES[PointField.INT16] = ('h', 2) 00083 _DATATYPES[PointField.UINT16] = ('H', 2) 00084 _DATATYPES[PointField.INT32] = ('i', 4) 00085 _DATATYPES[PointField.UINT32] = ('I', 4) 00086 _DATATYPES[PointField.FLOAT32] = ('f', 4) 00087 _DATATYPES[PointField.FLOAT64] = ('d', 8) 00088 00089 def create_cloud_xyz32(header,points): 00090 fields = [PointField('x', 0, PointField.FLOAT32, 1), 00091 PointField('y', 4, PointField.FLOAT32, 1), 00092 PointField('z', 8, PointField.FLOAT32, 1)] 00093 return create_cloud(header, fields, points) 00094 00095 def create_cloud(header, fields, points): 00096 cloud = PointCloud2() 00097 cloud.header = header 00098 cloud.height = 1 00099 cloud.width = len(points) 00100 cloud.is_dense = False 00101 cloud.is_bigendian = False 00102 cloud.fields = fields 00103 fmt = _get_struct_fmt(cloud) 00104 cloud_struct = struct.Struct(fmt) 00105 cloud.point_step = cloud_struct.size 00106 cloud.row_step = cloud_struct.size * cloud.width 00107 00108 buffer = ctypes.create_string_buffer(cloud_struct.size * cloud.width) 00109 00110 point_step, pack_into = cloud.point_step, cloud_struct.pack_into 00111 offset = 0 00112 for p in points: 00113 pack_into(buffer, offset, *p) 00114 offset += point_step 00115 00116 cloud.data = buffer.raw 00117 00118 return cloud 00119 00120 def _get_struct_fmt(cloud, field_names=None): 00121 fmt = '>' if cloud.is_bigendian else '<' 00122 00123 offset = 0 00124 for field in (f for f in sorted(cloud.fields, key=lambda f: f.offset) if field_names is None or f.name in field_names): 00125 if offset < field.offset: 00126 fmt += 'x' * (field.offset - offset) 00127 offset = field.offset 00128 if field.datatype not in _DATATYPES: 00129 print >> sys.stderr, 'Skipping unknown PointField datatype [%d]' % field.datatype 00130 else: 00131 datatype_fmt, datatype_length = _DATATYPES[field.datatype] 00132 fmt += field.count * datatype_fmt 00133 offset += field.count * datatype_length 00134 00135 return fmt 00136 00137 #check that the transformations are done correctly... 00138 def vtkToNumpy(vtk_matrix): 00139 np_matrix = numpy.zeros((4,4)) 00140 for i in xrange(4): 00141 for j in xrange(4): 00142 np_matrix[i,j] = float(vtk_matrix.GetElement(i,j)) 00143 00144 return np_matrix 00145 00146 def numPyToVTK(numpy_mat): 00147 vtk_matrix = vtk.vtkMatrix4x4() 00148 for i in xrange(4): 00149 for j in xrange(4): 00150 vtk_matrix.SetElement(i,j,numpy_mat[i,j]) 00151 00152 return vtk_matrix 00153 00154 #Transform a vtkMatrix4x4 to geometry_msgs/Pose 00155 #Quaternions ix+jy+kz+w are represented as [x, y, z, w]. 00156 00157 def vtkTransformToPose(transform): 00158 #print transform 00159 R = vtkToNumpy(transform) 00160 #print R #numpy matrix from vtkMatrix 00161 #print "R print" 00162 q = tfTransformations.quaternion_from_matrix(R) #get quaternion from rotation matrix 00163 #print q 00164 #rotFromQuaternion = tfTransformations.quaternion_matrix(q) #get rotation matrix from quaternion 00165 #print rotFromQuaternion 00166 #print "RotationMatrix from quatenion print" 00167 pose = Pose() 00168 pose.orientation.x = q[0] 00169 pose.orientation.y = q[1] 00170 pose.orientation.z = q[2] 00171 pose.orientation.w = q[3] 00172 pose.position.x = R[0,3] 00173 pose.position.y = R[1,3] 00174 pose.position.z = R[2,3] 00175 #print pose 00176 return pose 00177 00178 #Transform a pose to a vtkTransforom 00179 00180 def poseToVTKTransform(pose): 00181 quaternion = numpy.array((pose.orientation.x,pose.orientation.y,pose.orientation.z,pose.orientation.w)) 00182 R = tfTransformations.quaternion_matrix(quaternion) 00183 R[0,3] = pose.position.x 00184 R[1,3] = pose.position.y 00185 R[2,3] = pose.position.z 00186 matrixTrans = numPyToVTK(R) 00187 trans = vtk.vtkTransform() 00188 trans.SetMatrix(matrixTrans) 00189 return trans 00190 00191 def scaleModel(filename, factor): 00192 reader1 = vtk.vtkPLYReader() 00193 reader1.SetFileName(filename) 00194 00195 trans = vtk.vtkTransform() 00196 trans.Scale(factor,factor,factor) 00197 transFilter1 = vtk.vtkTransformFilter() 00198 transFilter1.SetTransform(trans) 00199 transFilter1.SetInputConnection(reader1.GetOutputPort()) 00200 00201 mapper1 = vtk.vtkPolyDataMapper() 00202 mapper1.SetInputConnection(transFilter1.GetOutputPort()) 00203 mapper1.Update() 00204 00205 (before, sep, after) = filename.rpartition("/") 00206 output_filename = '/tmp/' + after 00207 print "Writting scaled model in:", output_filename, " scale_factor:", scale_factor 00208 00209 writer = vtk.vtkPLYWriter() 00210 writer.SetFileName(output_filename) 00211 writer.SetInput(mapper1.GetInput()) 00212 writer.Write() 00213 00214 return output_filename 00215 00216 #sys.argv[1] filename of the original model (not scaled) 00217 #sys.argv[2] scaled_model_id 00218 #sys.argv[3] scale_factor 00219 00220 if __name__ == '__main__': 00221 if len(sys.argv) < 2: 00222 print "ERROR: ply file is missing..." 00223 else: 00224 filename = sys.argv[1] 00225 00226 if len(sys.argv) < 3: 00227 print "ERROR: scale_model_id is missing..." 00228 else: 00229 scale_model_id = sys.argv[2] 00230 00231 if len(sys.argv) < 4: 00232 print "WARNING: scale_factor is missing..., using 1.0" 00233 scale_factor = 1.0 00234 else: 00235 scale_factor = float(sys.argv[3]) 00236 00237 model_id = sys.argv[2] 00238 #scale the model and overwrite filename 00239 (root_dir, sep, after) = filename.rpartition("/") 00240 00241 orig_file = filename 00242 output_filename = scaleModel(filename, scale_factor) 00243 filename = output_filename 00244 00245 [pcd_views, transforms] = views_generator.sample_views_tesselated_sphere(filename) 00246 00247 if len(pcd_views) != len(transforms): 00248 print "ERROR: Number of views does not match the number of transformations" 00249 00250 #Loop over views + pose 00251 #and call service that computes normals, VFH and store them in the database together with the pose 00252 00253 rootDirMessage = stdMsgString() 00254 rootDirMessage.data = root_dir 00255 00256 modelIdMessage = stdMsgString() 00257 modelIdMessage.data = str(model_id) 00258 00259 if True: 00260 for i in xrange(len(pcd_views)): 00261 00262 view_file = root_dir + '/' + 'last_view.txt' 00263 output = open(view_file, 'rb') 00264 view_id = pickle.load(output) + 1 00265 output.close() 00266 00267 viewIdMessage = stdMsgString() 00268 viewIdMessage.data = str(view_id) 00269 00270 view = pcd_views[i] 00271 trans = transforms[i] 00272 print "Number of points:", len(view) 00273 #transform to ROS messages to be sent to the service 00274 # # view = sensor_msgs/PointCloud2 00275 # # trans = geometry_msgs/Pose 00276 pc2_view = create_cloud_xyz32(Header(), view) 00277 pose_trans = vtkTransformToPose(trans) #transform vtk to pose message, cannot deal with scale... 00278 trans2 = poseToVTKTransform(pose_trans) 00279 00280 rospy.wait_for_service('normals_vfh_db_estimator') 00281 try: 00282 nvfhdb = rospy.ServiceProxy('normals_vfh_db_estimator', normals_vfh_db_estimator) 00283 resp = nvfhdb(pc2_view, pose_trans, viewIdMessage, modelIdMessage, rootDirMessage) 00284 except rospy.ServiceException, e: 00285 print "Service call failed: %s"%e 00286 00287 view_file = root_dir + '/' + 'last_view.txt' 00288 output = open(view_file, 'wb') 00289 pickle.dump(view_id, output) 00290 output.close() 00291 00292 #check for duplicate views 00293 if True: 00294 rospy.wait_for_service('remove_duplicate_views') 00295 try: 00296 rdviews = rospy.ServiceProxy('remove_duplicate_views', remove_duplicate_views) 00297 resp = rdviews(modelIdMessage,rootDirMessage) 00298 except rospy.ServiceException, e: 00299 print "remove_duplicate_views Service call failed: %s"%e 00300