$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_recognition') 00047 import rospy 00048 import sys 00049 from ground_plane.groundPlane import groundPlaneFunction 00050 from ground_plane.tesselatedSphere import TesselatedSphere 00051 import views_generator.views_generator as views_generator 00052 import vtk 00053 import os 00054 import tf.transformations as tfTransformations 00055 import numpy 00056 from geometry_msgs.msg import Pose 00057 from sensor_msgs.msg import PointCloud2, PointField 00058 from std_msgs.msg import Header, Int32 as stdMsgInt32 00059 from vfh_recognition.srv import * 00060 00061 #this will be later in a separate file 00062 import ctypes 00063 import math 00064 import struct 00065 00066 #sys.path.append("..") 00067 #from utils.tesselatedSphere import TesselatedSphere 00068 from utils.visualize import Visualizer 00069 00070 _DATATYPES = {} 00071 _DATATYPES[PointField.INT8] = ('b', 1) 00072 _DATATYPES[PointField.UINT8] = ('B', 1) 00073 _DATATYPES[PointField.INT16] = ('h', 2) 00074 _DATATYPES[PointField.UINT16] = ('H', 2) 00075 _DATATYPES[PointField.INT32] = ('i', 4) 00076 _DATATYPES[PointField.UINT32] = ('I', 4) 00077 _DATATYPES[PointField.FLOAT32] = ('f', 4) 00078 _DATATYPES[PointField.FLOAT64] = ('d', 8) 00079 00080 def create_cloud_xyz32(header,points): 00081 fields = [PointField('x', 0, PointField.FLOAT32, 1), 00082 PointField('y', 4, PointField.FLOAT32, 1), 00083 PointField('z', 8, PointField.FLOAT32, 1)] 00084 return create_cloud(header, fields, points) 00085 00086 def create_cloud(header, fields, points): 00087 cloud = PointCloud2() 00088 cloud.header = header 00089 cloud.height = 1 00090 cloud.width = len(points) 00091 cloud.is_dense = False 00092 cloud.is_bigendian = False 00093 cloud.fields = fields 00094 fmt = _get_struct_fmt(cloud) 00095 cloud_struct = struct.Struct(fmt) 00096 cloud.point_step = cloud_struct.size 00097 cloud.row_step = cloud_struct.size * cloud.width 00098 00099 buffer = ctypes.create_string_buffer(cloud_struct.size * cloud.width) 00100 00101 point_step, pack_into = cloud.point_step, cloud_struct.pack_into 00102 offset = 0 00103 for p in points: 00104 pack_into(buffer, offset, *p) 00105 offset += point_step 00106 00107 cloud.data = buffer.raw 00108 00109 return cloud 00110 00111 def _get_struct_fmt(cloud, field_names=None): 00112 fmt = '>' if cloud.is_bigendian else '<' 00113 00114 offset = 0 00115 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): 00116 if offset < field.offset: 00117 fmt += 'x' * (field.offset - offset) 00118 offset = field.offset 00119 if field.datatype not in _DATATYPES: 00120 print >> sys.stderr, 'Skipping unknown PointField datatype [%d]' % field.datatype 00121 else: 00122 datatype_fmt, datatype_length = _DATATYPES[field.datatype] 00123 fmt += field.count * datatype_fmt 00124 offset += field.count * datatype_length 00125 00126 return fmt 00127 00128 #check that the transformations are done correctly... 00129 def vtkToNumpy(vtk_matrix): 00130 np_matrix = numpy.zeros((4,4)) 00131 for i in xrange(4): 00132 for j in xrange(4): 00133 np_matrix[i,j] = float(vtk_matrix.GetElement(i,j)) 00134 00135 return np_matrix 00136 00137 def numPyToVTK(numpy_mat): 00138 vtk_matrix = vtk.vtkMatrix4x4() 00139 for i in xrange(4): 00140 for j in xrange(4): 00141 vtk_matrix.SetElement(i,j,numpy_mat[i,j]) 00142 00143 return vtk_matrix 00144 00145 #Transform a vtkMatrix4x4 to geometry_msgs/Pose 00146 #Quaternions ix+jy+kz+w are represented as [x, y, z, w]. 00147 00148 def vtkTransformToPose(transform): 00149 #print transform 00150 R = vtkToNumpy(transform) 00151 #print R #numpy matrix from vtkMatrix 00152 #print "R print" 00153 q = tfTransformations.quaternion_from_matrix(R) #get quaternion from rotation matrix 00154 #print q 00155 #rotFromQuaternion = tfTransformations.quaternion_matrix(q) #get rotation matrix from quaternion 00156 #print rotFromQuaternion 00157 #print "RotationMatrix from quatenion print" 00158 pose = Pose() 00159 pose.orientation.x = q[0] 00160 pose.orientation.y = q[1] 00161 pose.orientation.z = q[2] 00162 pose.orientation.w = q[3] 00163 pose.position.x = R[0,3] 00164 pose.position.y = R[1,3] 00165 pose.position.z = R[2,3] 00166 #print pose 00167 return pose 00168 00169 #Transform a pose to a vtkTransforom 00170 00171 def poseToVTKTransform(pose): 00172 quaternion = numpy.array((pose.orientation.x,pose.orientation.y,pose.orientation.z,pose.orientation.w)) 00173 R = tfTransformations.quaternion_matrix(quaternion) 00174 R[0,3] = pose.position.x 00175 R[1,3] = pose.position.y 00176 R[2,3] = pose.position.z 00177 matrixTrans = numPyToVTK(R) 00178 trans = vtk.vtkTransform() 00179 trans.SetMatrix(matrixTrans) 00180 return trans 00181 00182 def scaleModel(filename, factor): 00183 reader1 = vtk.vtkPLYReader() 00184 reader1.SetFileName(filename) 00185 00186 trans = vtk.vtkTransform() 00187 trans.Scale(factor,factor,factor) 00188 transFilter1 = vtk.vtkTransformFilter() 00189 transFilter1.SetTransform(trans) 00190 transFilter1.SetInputConnection(reader1.GetOutputPort()) 00191 00192 mapper1 = vtk.vtkPolyDataMapper() 00193 mapper1.SetInputConnection(transFilter1.GetOutputPort()) 00194 mapper1.Update() 00195 00196 (before, sep, after) = filename.rpartition("/") 00197 output_filename = '/tmp/' + after 00198 print "Writting scaled model in:", output_filename, " scale_factor:", scale_factor 00199 00200 writer = vtk.vtkPLYWriter() 00201 writer.SetFileName(output_filename) 00202 writer.SetInput(mapper1.GetInput()) 00203 writer.Write() 00204 00205 return output_filename 00206 00207 #sys.argv[1] filename of the original model (not scaled) 00208 #sys.argv[2] scaled_model_id 00209 #sys.argv[3] scale_factor 00210 00211 if __name__ == '__main__': 00212 if len(sys.argv) < 2: 00213 print "ERROR: ply file is missing..." 00214 else: 00215 filename = sys.argv[1] 00216 00217 if len(sys.argv) < 3: 00218 print "ERROR: scale_model_id is missing..." 00219 else: 00220 scale_model_id = int(sys.argv[2]) 00221 00222 if len(sys.argv) < 4: 00223 print "ERROR: scale_factor is missing..., using 1.0" 00224 scale_factor = 1.0 00225 else: 00226 scale_factor = float(sys.argv[3]) 00227 00228 iteration = int(sys.argv[4]) 00229 #scale the model and overwrite filename 00230 orig_file = filename 00231 output_filename = scaleModel(filename, scale_factor) 00232 filename = output_filename 00233 #quit() 00234 00235 #Generation of stable planes 00236 #the stable planes are stored in the same directory where the ply files are found 00237 #under tangent_planes 00238 00239 STABLE_PLANES = False 00240 if STABLE_PLANES: 00241 sphere = TesselatedSphere(1, False) 00242 sphere.construct() 00243 00244 if os.path.exists(filename): 00245 sphere.resetPolygons() 00246 groundPlaneFunction(filename,False, sphere) 00247 else: 00248 print "ERROR: File does not exist" 00249 00250 idMessage = stdMsgInt32() 00251 idMessage.data = int(sys.argv[2]) 00252 00253 iterationMessage = stdMsgInt32() 00254 iterationMessage.data = int(sys.argv[4]) 00255 00256 #if False: 00257 #Once the stable planes are generated, we can start generating the views 00258 #The views_generator returns a list of views (virtual camera coordinates) 00259 #and a transformation that transforms from model coordinates to the virtual 00260 #camera coordinates. Virtual camera coordinates map the REP 103 optical 00261 #frame coordinate system (see http://www.ros.org/reps/rep-0103.html) 00262 #[pcd_views, transforms] = views_generator.sample_views(filename) 00263 [pcd_views, transforms] = views_generator.sample_views_tesselated_sphere(filename) 00264 00265 if len(pcd_views) != len(transforms): 00266 print "ERROR: Number of views does not match the number of transformations" 00267 00268 #Loop over views + pose 00269 #and call service that computes normals, VFH and store them in the database together with the pose 00270 for i in xrange(len(pcd_views)): 00271 view = pcd_views[i] 00272 trans = transforms[i] 00273 print "Number of points:", len(view) 00274 #transform to ROS messages to be sent to the service 00275 # # view = sensor_msgs/PointCloud2 00276 # # trans = geometry_msgs/Pose 00277 pc2_view = create_cloud_xyz32(Header(), view) 00278 pose_trans = vtkTransformToPose(trans) #transform vtk to pose message, cannot deal with scale... 00279 trans2 = poseToVTKTransform(pose_trans) 00280 00281 rospy.wait_for_service('normals_vfh_db_estimator') 00282 try: 00283 nvfhdb = rospy.ServiceProxy('normals_vfh_db_estimator', normals_vfh_db_estimator) 00284 resp = nvfhdb(pc2_view, pose_trans, idMessage, iterationMessage) 00285 except rospy.ServiceException, e: 00286 print "Service call failed: %s"%e 00287 00288 #check for duplicate views 00289 rospy.wait_for_service('remove_duplicate_views') 00290 try: 00291 rdviews = rospy.ServiceProxy('remove_duplicate_views', remove_duplicate_views) 00292 resp = rdviews(idMessage, iterationMessage) 00293 except rospy.ServiceException, e: 00294 print "remove_duplicate_views Service call failed: %s"%e 00295