gaussian_histogram_features.py
Go to the documentation of this file.
00001 #
00002 # Copyright (c) 2010, Georgia Tech Research Corporation
00003 # All rights reserved.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 #     * Redistributions of source code must retain the above copyright
00008 #       notice, this list of conditions and the following disclaimer.
00009 #     * Redistributions in binary form must reproduce the above copyright
00010 #       notice, this list of conditions and the following disclaimer in the
00011 #       documentation and/or other materials provided with the distribution.
00012 #     * Neither the name of the Georgia Tech Research Corporation nor the
00013 #       names of its contributors may be used to endorse or promote products
00014 #       derived from this software without specific prior written permission.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00017 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00020 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00021 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00022 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00023 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00024 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00025 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 #
00027 
00028 #  \author Martin Schuster (Healthcare Robotics Lab, Georgia Tech.)
00029 
00030 from features import features
00031 import texture_features
00032 import gaussian_curvature
00033 
00034 import scipy.stats as stats
00035 import numpy as np
00036 import opencv as cv
00037 import scipy.spatial.kdtree as kdtree
00038 import util as ut # used for getTime, and cv2np, load_pickle, save_pickle
00039 
00040 import os #[for os.path.exists(...)]
00041 import copy #[to copy VOI indices]
00042 
00043 import processor ###
00044 
00045 #The source file:
00046 #    Has a file import statement which uses config.path, etc.
00047 #    Heavily uses internal variables of processor.Processor object (called 'processor', must be passed).
00048 #    Uses no functions from processor except for rotate_to_plane()
00049 #    Vars: pts3d_bound, img, map2d (=camPts_bound), config.path, scan_dataset.id,  feature_radius,
00050 #          voi_width, rotate_to_plane(), scan_dataset.ground_plane_normal, intensities_bound
00051 
00052 
00053 class gaussian_histogram_features(features):
00054     '''
00055     classdocs
00056     '''
00057     
00058     #all_save_load: set to true only if nonzero_indices contain all pts in pt-cloud!
00059     def prepare(self, features_k_nearest_neighbors, nonzero_indices = None, all_save_load = False, regenerate_neightborhood_indices = False):
00060         #print np.shape(self.processor.pts3d_bound), 'shape pts3d_bound'
00061 
00062         imgTmp = cv.cvCloneImage(self.processor.img)
00063         self.imNP = ut.cv2np(imgTmp,format='BGR')
00064         ###self.processor.map2d = np.asarray(self.processor.camPts_bound) #copied from laser to image mapping
00065         
00066         if features_k_nearest_neighbors == None or features_k_nearest_neighbors == False: #use range
00067             self.kdtree2d = kdtree.KDTree(self.processor.pts3d_bound.T)
00068             
00069             #print len(nonzero_indices)
00070             #print np.shape(np.asarray((self.processor.pts3d_bound.T)[nonzero_indices]))
00071             
00072             if nonzero_indices != None:
00073                 print ut.getTime(), 'query ball tree for ', len(nonzero_indices), 'points'
00074                 kdtree_query = kdtree.KDTree((self.processor.pts3d_bound.T)[nonzero_indices])
00075             else:
00076                 print ut.getTime(), 'query ball tree'
00077                 kdtree_query = kdtree.KDTree(self.processor.pts3d_bound.T)
00078             
00079             filename = self.processor.config.path+'/data/'+self.processor.scan_dataset.id+'_sphere_neighborhood_indices_'+str(self.processor.feature_radius)+'.pkl'
00080             if all_save_load == True and os.path.exists(filename) and regenerate_neightborhood_indices == False:
00081                 #if its already there, load it:
00082                 print ut.getTime(), 'loading',filename
00083                 self.kdtree_queried_indices = ut.load_pickle(filename)    
00084             else:
00085                 self.kdtree_queried_indices = kdtree_query.query_ball_tree(self.kdtree2d, self.processor.feature_radius, 2.0, 0.2) #approximate
00086                 print ut.getTime(), 'queried kdtree: ',len(self.kdtree_queried_indices),'points, radius:',self.processor.feature_radius
00087                 if all_save_load == True:
00088                     ut.save_pickle(self.kdtree_queried_indices, filename)
00089                     
00090             #make dict out of list for faster operations? (doesn't seem to change speed significantly):
00091             #self.kdtree_queried_indices = dict(zip(xrange(len(self.kdtree_queried_indices)), self.kdtree_queried_indices))
00092         
00093         else: #experiemental: use_20_nearest_neighbors == True
00094             #TODO: exclude invalid values in get_featurevector (uncomment code there)
00095            
00096             self.kdtree2d = kdtree.KDTree(self.processor.pts3d_bound.T)
00097             self.kdtree_queried_indices = []
00098             print ut.getTime(), 'kdtree single queries for kNN start, k=', features_k_nearest_neighbors
00099             count = 0
00100             for point in ((self.processor.pts3d_bound.T)[nonzero_indices]):
00101                 count = count + 1
00102                 result = self.kdtree2d.query(point, features_k_nearest_neighbors,0.2,2,self.processor.feature_radius)
00103                 #existing = result[0][0] != np.Inf
00104                 #print existing
00105                 #print result[1]
00106                 self.kdtree_queried_indices += [result[1]] #[existing]
00107                 if count % 4096 == 0:
00108                     print ut.getTime(),count
00109             print ut.getTime(), 'kdtree singe queries end'
00110             
00111             #convert to numpy array -> faster access
00112             self.kdtree_queried_indices = np.asarray(self.kdtree_queried_indices)
00113         
00114         #print self.kdtree_queried_indices
00115         #takes long to compute:
00116         #avg_len = 0
00117         #minlen = 999999
00118         #maxlen = 0
00119         #for x in self.kdtree_queried_indices:
00120         #    avg_len += len(x)
00121         #    minlen = min(minlen, len(x))
00122         #    maxlen = max(maxlen, len(x))
00123         #avg_len = avg_len / len(self.kdtree_queried_indices)
00124         #print ut.getTime(), "range neighbors: avg_len", avg_len, 'minlen', minlen, 'maxlen', maxlen
00125         
00126         
00127         #create HSV numpy images:
00128         # compute the hsv version of the image 
00129         image_size = cv.cvGetSize(self.processor.img)
00130         img_h = cv.cvCreateImage (image_size, 8, 1)
00131         img_s = cv.cvCreateImage (image_size, 8, 1)
00132         img_v = cv.cvCreateImage (image_size, 8, 1)
00133         img_hsv = cv.cvCreateImage (image_size, 8, 3)
00134         
00135         cv.cvCvtColor (self.processor.img, img_hsv, cv.CV_BGR2HSV)
00136         
00137         cv.cvSplit (img_hsv, img_h, img_s, img_v, None)
00138         self.imNP_h = ut.cv2np(img_h)
00139         self.imNP_s = ut.cv2np(img_s)
00140         self.imNP_v = ut.cv2np(img_v)
00141         
00142         textures = texture_features.eigen_texture(self.processor.img)
00143         self.imNP_tex1 = textures[:,:,0]
00144         self.imNP_tex2 = textures[:,:,1]
00145         
00146         self.debug_before_first_featurevector = True
00147         
00148         self.generate_voi_histogram(self.processor.point_of_interest,self.processor.voi_width)
00149               
00150 
00151 
00152     #has to have at least length 2 because of openCV matrices!!!!
00153     def get_indexvector(self, type):
00154         
00155         var_idx = []
00156         #start indices
00157         rh1 = 0 #zhist, normal, eigenvalue1, ev2
00158         ch1 = rh1 + 6 #hsi zhist, maxheight-diff, tex1, tex2
00159         ci = ch1 + 25
00160         end = ci + 4 #
00161         if type=='range':
00162             for i in range(rh1, ch1):
00163                 var_idx.append(i) 
00164         elif type=='color':
00165             for i in range(ch1, end):
00166                 var_idx.append(i)                                        
00167         #for plotting:
00168         elif type=='hsvi':
00169             for i in range(ci,end):
00170                 var_idx.append(i)                         
00171         else: #all
00172             for i in range(rh1, end):
00173                 var_idx.append(i)   
00174 
00175         return np.array(var_idx)    
00176         
00177         
00178         
00179     #get the feature vector for a specific point
00180     def get_featurevector(self, index, count, pts = None):
00181         if pts == None:
00182             pts = self.processor.pts3d_bound
00183 
00184         #print 'i',index,'c', count
00185         fv = [] 
00186         
00187         indices = np.asarray(self.kdtree_queried_indices[count])
00188         invalid_value = np.shape(pts)[1]
00189         #print indices
00190         #print 'iv',invalid_value
00191         indices = indices[indices != invalid_value]
00192         
00193         #print ut.getTime(), indices
00194         #print ut.getTime(), 'number of pts', len(indices)
00195         a = pts[:,indices]
00196         view = processor.rotate_to_plane(self.processor.scan_dataset.ground_plane_normal, np.matrix([-1,0,0.]).T)
00197         normal, eigenvalues = gaussian_curvature.gaussian_curvature(a,view)
00198         #eigenvalues = eigenvalues / np.square(r)
00199         #fv += [normal[0,0],0,normal[2,0]]
00200         #fv += normal.T.A[0].tolist()
00201         #fv += eigenvalues.tolist()
00202         #print np.asarray(pts[:,index].T[0])[0]
00203        # print 'pt',np.asarray(pts[:,index].T[0])
00204         point = pts[:,index]
00205         
00206         ev1, ev2 = self.get_voi_histogram_spread(point)
00207         #z_max_height_diff = pts[2,index] - self.get_voi_maxcount_height()
00208         #fv += [self.get_voi_histogram_value(point),z_max_height_diff,normal[0,0],normal[1,0],normal[2,0], ev1, ev2]
00209         fv += [self.get_voi_histogram_value(point),normal[0,0],normal[1,0],normal[2,0], ev1, ev2]
00210         
00211         h = self.imNP_h[self.processor.map2d[1,index],self.processor.map2d[0,index]]
00212         s = self.imNP_s[self.processor.map2d[1,index],self.processor.map2d[0,index]]
00213         i = self.processor.intensities_bound[index]
00214         hsi = self.get_voi_hsi_histogram_values(point,h,s,i)
00215         fv += [hsi[0],hsi[1],hsi[2]]
00216         #print np.shape(self.imNP_tex1)
00217         #print np.shape(self.map2d)
00218         tex1 = self.imNP_tex1[self.processor.map2d[1,index],self.processor.map2d[0,index]]
00219         tex2 = self.imNP_tex2[self.processor.map2d[1,index],self.processor.map2d[0,index]]
00220         fv += [tex1, tex2]
00221         #print tex1, tex2
00222         
00223 
00224         #color histograms:
00225         colors_h = []
00226         colors_s = []
00227         colors_v = []
00228         for idx in indices:
00229             colors_h.append(float(self.imNP_h[self.processor.map2d[1,idx],self.processor.map2d[0,idx]]))
00230             colors_s.append(float(self.imNP_s[self.processor.map2d[1,idx],self.processor.map2d[0,idx]]))
00231             colors_v.append(float(self.imNP_v[self.processor.map2d[1,idx],self.processor.map2d[0,idx]]))
00232         
00233         color_hist = stats.histogram2(np.array(colors_h), [0,51,102,153,204])
00234         color_hist = color_hist / float(np.sum(color_hist))
00235         color_hist = list(color_hist)
00236         fv += color_hist
00237         color_hist = stats.histogram2(np.array(colors_s), [0,51,102,153,204])
00238         color_hist = color_hist / float(np.sum(color_hist))
00239         color_hist = list(color_hist)
00240         fv += color_hist
00241         color_hist = stats.histogram2(np.array(colors_v), [0,51,102,153,204])
00242         color_hist = color_hist / float(np.sum(color_hist))
00243         color_hist = list(color_hist)
00244         fv += color_hist
00245         
00246         #intensities
00247         intensities = self.processor.intensities_bound[indices]
00248         intensities = np.asarray(intensities)
00249         #map to 0-255-range:   TODO: perhaps do some nonlinear transformation here? 
00250         intensities = intensities / 10000 * 255
00251         intensity_hist = stats.histogram2(intensities, [0,51,102,153,204])
00252         intensity_hist = intensity_hist / float(np.sum(intensity_hist))
00253         intensity_hist = list(intensity_hist)
00254         fv += intensity_hist    
00255     
00256         #current colors:
00257         fv += [float(self.imNP_h[self.processor.map2d[1,index],self.processor.map2d[0,index]]) / 255.0]
00258         fv += [float(self.imNP_s[self.processor.map2d[1,index],self.processor.map2d[0,index]]) / 255.0]
00259         fv += [float(self.imNP_v[self.processor.map2d[1,index],self.processor.map2d[0,index]]) / 255.0]  
00260         
00261         #current intensity value (scaled)
00262         intensity = self.processor.intensities_bound[index]
00263         #scale:
00264         intensity = intensity / 15000.0
00265         intensity = [intensity]
00266         fv += intensity  
00267 
00268         
00269         if self.debug_before_first_featurevector == True:
00270             self.debug_before_first_featurevector = False
00271             print ut.getTime(), 'get_featurevector: Choosing not to print Feature Vector Sample'
00272             #print ut.getTime(), 'feature vector sample(gaussian histograms):', fv
00273         return fv
00274     
00275     
00276 
00277         #poi and width: cube of interest around point
00278         #min, max, bincount gives the height slices    
00279     def generate_voi_histogram(self, poi, width):
00280         print 'poi',poi,'width',width
00281         
00282         # indices of points in volume of interest (poi)
00283         pts_indices = self.get_voi_pts_indices(poi, width)
00284         self.voi_pts_indices = pts_indices
00285         pts = np.asarray(self.processor.pts3d_bound)
00286         pts = pts[:,pts_indices] #truncate points to volume of interest
00287         self.voi_pts = pts
00288         #mlab.points3d(pts[0,:],pts[1,:],pts[2,:], mode='point')
00289         #mlab.show() 
00290         
00291         #go from 0 to 2m, create histogram with 80 bins = bin of 2.5cm (=height-slice)
00292         min = 0.
00293         max = 2.
00294         self.voi_bincount = 80
00295         self.voi_interval_size = max - min
00296         bins = np.asarray(range(self.voi_bincount)) * self.voi_interval_size/float(self.voi_bincount)
00297         #print 'bins',bins
00298         hist = stats.histogram2(pts[2],bins) / float(len(pts[2]))
00299         #print 'zhist',hist
00300         #print zip(bins, hist)
00301         self.z_hist = hist
00302         self.z_hist_bins = bins
00303         
00304         slices = self.get_voi_slice_indices()
00305         self.z_hist_slices_indices = slices
00306         
00307         #precalculate spread values:
00308         self.z_hist_spread = []
00309         for indices in self.z_hist_slices_indices:
00310             a = self.processor.pts3d_bound[:,indices]
00311             # ev12 gives an indication about how far points are spread out in a specific height-slice
00312             u, ev12 = gaussian_curvature.spread(a)
00313             self.z_hist_spread += [(ev12[0], ev12[1])]
00314         
00315         #create h,s,i histograms for each slice:
00316         pts_h = []
00317         pts_s = []
00318         #print self.processor.pts3d_bound
00319         #TODO: does this use the volume of interest? should it???
00320         n,m = np.shape(np.asarray(self.processor.pts3d_bound))
00321         #print 'm',m,'len(self.processor.pts3d_bound[2,:].A1)',len(self.processor.pts3d_bound[2,:].A1)
00322         for index in range(m):
00323             pts_h.append(float(self.imNP_h[self.processor.map2d[1,index],self.processor.map2d[0,index]]))
00324         for index in range(m):
00325             pts_s.append(float(self.imNP_s[self.processor.map2d[1,index],self.processor.map2d[0,index]]))
00326         pts_i = np.asarray(self.processor.intensities_bound)
00327         #print 'ptsi',pts_i
00328         if np.max(pts_i) > 0:
00329             self.intensity_normalization_factor = 1.0 / float(np.max(pts_i)) * 255
00330         else:
00331             self.intensity_normalization_factor = 1.
00332         #print 'self.intensity_normalization_factor', self.intensity_normalization_factor
00333         #print pts_i
00334         pts_i *= self.intensity_normalization_factor
00335         pts_h = np.asarray(pts_h)
00336         pts_s = np.asarray(pts_s)
00337         self.z_hist_h_hists = []
00338         self.z_hist_s_hists = []
00339         self.z_hist_i_hists = []
00340         
00341         #normalize by maximum slice:
00342         max_count = 0
00343         max_count_index = 0
00344         for count_idx, indices in enumerate(slices):
00345             n = np.shape(indices)
00346             if n[0] > max_count:
00347                 max_count = n[0]
00348                 max_count_index = count_idx
00349         slize_height = (self.voi_interval_size / float(self.voi_bincount))
00350         self.z_hist_height_max =  slize_height * (max_count_index + 0.5)
00351         #print 'max_count', max_count,'index',max_count_index, 'height in max bin', self.z_hist_height_max
00352 
00353         
00354         for indices in slices:
00355             pts_h_slice = pts_h[indices]
00356             pts_s_slice = pts_s[indices]
00357             pts_i_slice = pts_i[indices]
00358             self.hsi_hist_bincount = 5
00359             bins = np.asarray(range(0,self.hsi_hist_bincount))*float(255.0/float(self.hsi_hist_bincount))
00360             #print bins
00361             #todo: smooth with kernel fct
00362             count = float(len(pts_h_slice))
00363             if count == 0: 
00364                 count = 1
00365             hist_h = stats.histogram2(pts_h_slice,bins) / count
00366             self.z_hist_h_hists.append(hist_h)
00367             hist_s = stats.histogram2(pts_s_slice,bins) / count
00368             self.z_hist_s_hists.append(hist_s)
00369             hist_i = stats.histogram2(pts_i_slice,bins) / count
00370             #print 'hist_i', hist_i, pts_i_slice, bins, pts_i
00371             self.z_hist_i_hists.append(hist_i)
00372         
00373         #print 'hh',self.z_hist_h_hists
00374         #print 'sh',self.z_hist_s_hists
00375         #print 'ih',self.z_hist_i_hists
00376         
00377     def get_voi_pts_indices(self, poi, width):
00378         pts = np.asarray(self.processor.pts3d_bound)
00379         #region of interest:
00380         conditions = np.multiply(np.multiply(np.multiply(np.multiply(np.multiply(pts[0] < poi[0]+width/2.0, pts[0] > poi[0]-width/2.0), 
00381                     pts[1] < poi[1]+width/2.0), pts[1] > poi[1]-width/2.0),
00382                     pts[2] < poi[2]+width/2.0), pts[2] > poi[2]-width/2.0)
00383                     
00384         indices = np.where(conditions)[0]
00385         return indices
00386         
00387     def get_voi_slice_indices(self):
00388         
00389         slices = []
00390         last_z = -999999
00391         
00392         for z in self.z_hist_bins:
00393             indices = copy.copy(self.voi_pts_indices)
00394             pts = self.voi_pts   
00395             conditions = np.multiply(pts[2] < z, pts[2] > last_z)
00396             indices = indices[np.where(conditions)[0]]     
00397             slices += [indices]
00398             last_z = z
00399         return slices
00400         
00401     def get_voi_histogram_value(self, point):
00402         z = point[2]
00403         z = int(z*self.voi_bincount / float(self.voi_interval_size))
00404         if z >= 0 and z < self.voi_bincount:
00405             # print z, self.z_hist[z]
00406             return self.z_hist[z]
00407         else:
00408             #print z,0
00409             return 0
00410         
00411     def get_voi_histogram_spread(self, point):
00412         z = point[2]
00413         z = int(z*self.voi_bincount / float(self.voi_interval_size))
00414         if z >= 0 and z < self.voi_bincount:
00415 #            indices = self.z_hist_slices_indices[z]
00416 #            a = self.processor.pts3d_bound[:,indices]
00417 #            u, ev12 = gaussian_curvature.spread(a)
00418 #            if abs(self.z_hist_spread[z][0] - ev12[0]) > 0.0000000001 or abs(self.z_hist_spread[z][1] - ev12[1]) > 0.0000000001:
00419 #                print 'ERROR', self.z_hist_spread[z], '!=', (ev12[0], ev12[1])
00420 #            return ev12[0], ev12[1]
00421             return self.z_hist_spread[z]
00422         else:
00423             #print z,0
00424             return 0, 0
00425         
00426         
00427     def get_voi_hsi_histogram_values(self, point,h ,s, i):
00428         z = point[2]
00429         z = int(z*self.voi_bincount / float(self.voi_interval_size))
00430         if z >= 0 and z < self.voi_bincount:
00431             h_index = int(h * self.hsi_hist_bincount / 255.0)
00432             s_index = int(s * self.hsi_hist_bincount / 255.0)
00433             i *= self.intensity_normalization_factor
00434             i_index = int(i * self.hsi_hist_bincount / 255.0)
00435             
00436             h_hist = self.z_hist_h_hists[z][h_index]
00437             s_hist = self.z_hist_s_hists[z][s_index]
00438             #print 'z',z,'i_index',i_index, i
00439             #print self.z_hist_i_hists, np.shape(self.z_hist_i_hists)
00440             i_hist = self.z_hist_i_hists[z][i_index]
00441             return h_hist, s_hist, i_hist
00442         else:
00443             #print z,0
00444             return 0, 0, 0
00445         
00446     def get_voi_maxcount_height(self):
00447         return self.z_hist_height_max
00448     
00449     


clutter_segmentation
Author(s): Jason Okerman, Martin Schuster, Advisors: Prof. Charlie Kemp and Jim Regh, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 12:07:15