boosted_tree_classifier.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 '''
00031 # Location of classifier to load or save is found by: classifier.get_filename(self):
00032 #     Loc = self.processor.config.path+'/classifier_'+self.features+'_'+
00033 #           self.processor.feature_type+'_k'+str(self.processor.feature_neighborhood)+
00034 #           '_r'+str(self.processor.feature_radius)+'.XML'
00035 '''
00036 
00037 from classifier import classifier
00038 
00039 import opencv as cv
00040 import util as ut
00041 import numpy as np
00042 import os
00043 
00044 import processor ###
00045 
00046 import ransac
00047 import random
00048 
00049 
00050 class boosted_tree_classifier(classifier) :
00051     '''
00052     classdocs
00053     '''
00054 
00055     cv_classifier = None
00056 
00057     #def __init__(selfparams):
00058     #    '''
00059     #    Constructor
00060     #    '''
00061         
00062         
00063     def create_train_datastructures(self):
00064         #loop through all marked datasets
00065         self.processor.scan_dataset = self.processor.scans_database.get_dataset(0)
00066           
00067         training_set_size = 0
00068         
00069         data = []
00070         #get size of training set in total
00071         while False != self.processor.scan_dataset:
00072             if self.processor.scan_dataset.is_training_set:
00073                 
00074                 filename = self.processor.get_features_filename(True)
00075                 print 'loading', filename
00076                 dict = ut.load_pickle(filename)
00077 
00078                 # make an equal size of points for each class: use object labels more often:
00079                 difference = np.sum(dict['labels'] == processor.LABEL_SURFACE) - np.sum(dict['labels'] == processor.LABEL_CLUTTER)
00080                 #print ut.getTime(), filename
00081                 #print ut.getTime(), 'surface',np.sum(dict['labels'] == LABEL_SURFACE)
00082                 #print ut.getTime(), 'clutter',np.sum(dict['labels'] == LABEL_CLUTTER)
00083                 #print ut.getTime(), difference, "difference = np.sum(dict['labels'] == LABEL_SURFACE) - np.sum(dict['labels'] == LABEL_CLUTTER)"
00084                 #print ut.getTime(), ''
00085                 if difference > 0:
00086                     clutter_features = (dict['features'])[np.nonzero(dict['labels'] == processor.LABEL_CLUTTER)]
00087                     if len(clutter_features) > 0: #if there are none, do nothin'
00088                         dict['set_size'] += difference
00089                         dict['features'] = np.vstack((dict['features'], clutter_features[np.random.randint(0,len(clutter_features),size=difference)]))
00090                         dict['labels'] = np.hstack((dict['labels'], np.ones(difference) * processor.LABEL_CLUTTER))
00091                 elif difference < 0: 
00092                     surface_features = (dict['features'])[np.nonzero(dict['labels'] == processor.LABEL_SURFACE)]
00093                     if len(surface_features) > 0: #if there are none, do nothin'
00094                         difference = -difference
00095                         dict['set_size'] += difference
00096                         dict['features'] = np.vstack((dict['features'], surface_features[np.random.randint(0,len(surface_features),size=difference)]))
00097                         dict['labels'] = np.hstack((dict['labels'], np.ones(difference) * processor.LABEL_SURFACE))
00098                     
00099                 training_set_size += dict['set_size']
00100                 data.append(dict)
00101             #get next one
00102             self.processor.scan_dataset = self.processor.scans_database.get_next_dataset()
00103             #print ut.getTime(),  self.scan_dataset
00104         
00105         #create training set:
00106         self.processor.scan_dataset = self.processor.scans_database.get_dataset(0)
00107         current_training_set_index = 0
00108         
00109        
00110         feature_vector_length = len(self.processor.features.get_indexvector(self.features))
00111         print ut.getTime(), feature_vector_length
00112         #create dataset matrices:
00113         print ut.getTime(), '#training set size ', training_set_size 
00114         
00115         #deactivate for now:
00116         max_traning_size = 1800000#2040000
00117         #if training_set_size < max_traning_size:
00118         #if True:       
00119         train_data = cv.cvCreateMat(training_set_size,feature_vector_length,cv.CV_32FC1) #CvMat* cvCreateMat(int rows, int cols, int type)
00120         train_labels = cv.cvCreateMat(training_set_size,1,cv.CV_32FC1)
00121         
00122         for dict in data:        
00123             for index in range(dict['set_size']):
00124                 #only train on surface and clutter
00125                 if dict['labels'][index] == processor.LABEL_SURFACE or dict['labels'][index]== processor.LABEL_CLUTTER:
00126                 
00127                     #print ut.getTime(), point3d
00128                     #print ut.getTime(), 'fvindexv',self.get_features_indexvector(features)
00129                     #print ut.getTime(), 'len', len(self.get_features_indexvector(features))
00130                     fv = (dict['features'][index])[self.processor.features.get_indexvector(self.features)]
00131 
00132                     #print ut.getTime(), 'fv',fv
00133                     #print ut.getTime(), np.shape(fv)
00134                     for fv_index, fv_value in enumerate(fv):
00135                         train_data[current_training_set_index][fv_index] = fv_value
00136                     train_labels[current_training_set_index] = dict['labels'][index]
00137 #                    for fv_index, fv_value in enumerate(fv):
00138 #                        print ut.getTime(), train_data[current_training_set_index][fv_index]
00139 #                    print ut.getTime(), '##',train_labels[current_training_set_index],'##'                    
00140                     #print ut.getTime(), 'fv ', fv
00141                     #print ut.getTime(), 'tr ',train_data[index]
00142                     current_training_set_index = current_training_set_index + 1
00143         
00144                     #if current_training_set_index % 4096 == 0:
00145                     #    print ut.getTime(), 'label', dict['labels'][index], 'fv', fv        
00146                     if current_training_set_index %  16384 == 0:
00147                         print ut.getTime(), 'reading features:', current_training_set_index, 'of', training_set_size, '(',(float(current_training_set_index)/float(training_set_size)*100.0),'%)'
00148 ##subsample from the features, NOT USED/NOT WORKING?
00149 #        else:
00150 #            print ut.getTime(), 'more than',max_traning_size,'features, sample from them...'
00151 #            #select 2040000 features:
00152 #            all_data = []
00153 #            all_labels = []
00154 #            for dict in data:  
00155 #                for index in range(dict['set_size']):
00156 #                    if dict['labels'][index] == processor.LABEL_SURFACE or dict['labels'][index]== processor.LABEL_CLUTTER:
00157 #                        fv = (dict['features'][index])[self.processor.features.get_indexvector(self.features)]
00158 #                        all_data += [fv]
00159 #                        all_labels += [dict['labels'][index]]
00160 #                        
00161 #                        current_training_set_index = current_training_set_index + 1    
00162 #                        if current_training_set_index %  16384 == 0:
00163 #                            print ut.getTime(), 'reading features:', current_training_set_index, 'of', training_set_size, '(',(float(current_training_set_index)/float(training_set_size)*100.0),'%)'
00164 #            
00165 #            del data
00166 #            indices = np.array(random.sample(xrange(len(all_labels)),max_traning_size))
00167 #            all_data = np.asarray(all_data)
00168 #            all_labels = np.asarray(all_labels)
00169 #            
00170 #            all_data = all_data[indices]
00171 #            all_labels = all_labels[indices]
00172 #            
00173 #            train_data = cv.cvCreateMat(max_traning_size,feature_vector_length,cv.CV_32FC1) #CvMat* cvCreateMat(int rows, int cols, int type)
00174 #            train_labels = cv.cvCreateMat(max_traning_size,1,cv.CV_32FC1)
00175 #                        
00176 #            for index in range(max_traning_size):
00177 #                for fv_index, fv_value in enumerate(all_data[index]):
00178 #                    train_data[index][fv_index] = fv_value
00179 #                    train_labels[index] = all_labels[index]
00180 #                if index % 16384 == 0:
00181 #                    print ut.getTime(), 'setting features:', (float(index)/float(max_traning_size))
00182 #          
00183           
00184         print ut.getTime(), 'start training Classifier'
00185 
00186         type_mask = cv.cvCreateMat(1, feature_vector_length+1, cv.CV_8UC1)
00187         cv.cvSet( type_mask, cv.CV_VAR_NUMERICAL, 0)
00188         type_mask[feature_vector_length] = cv.CV_VAR_CATEGORICAL
00189         
00190         return (train_data, train_labels, type_mask)
00191     
00192 
00193     
00194     def train(self):
00195         #cv_boost_params = cv.CvBoostParams()
00196 
00197         #priors = cv.cvCreateMat(1,2,cv.CV_32FC1)
00198         #priors[0] = 10
00199         #priors[1] = 1
00200         
00201         #cv_boost_params.max_categories = 2
00202         #cv_boost_params.priors = priors #TODO: activate them
00203         self.cv_classifier = cv.CvDTree() #cv.CvBoost() #TODO: CHANGE CLASSIFIER HERE
00204         train_datastructures = self.create_train_datastructures()
00205             
00206         (train_data, train_labels, type_mask) = train_datastructures
00207         print 'WARNING! use CvDTree (single decision trees) for now as load/save works!'#'boost'
00208         print ut.getTime(), self.cv_classifier.train(train_data, cv.CV_ROW_SAMPLE, train_labels, None, None, type_mask ) #TODO: CHANGE CLASSIFIER HERE
00209        
00210         print ut.getTime(), 'traning finished'
00211        
00212         #self.release_train_datastructures(train_datastructures)
00213 
00214     #unused - is that necessary in python? how does it work??
00215     def release_train_datastructures(self, train_datastructures):
00216         if None != train_datastructures:
00217             (train_data, train_labels, type_mask) = train_datastructures
00218             cv.cvReleaseMat(train_data)
00219             cv.cvReleaseMat(train_labels)
00220             cv.cvReleaseMat(type_mask)
00221     
00222     #test on current scan:
00223     def test(self, feature_data = None):
00224         #test on current scan:
00225         print ut.getTime(), 'test on:', self.processor.scan_dataset.id    
00226             
00227         if feature_data == None:
00228             filename = self.processor.get_features_filename()
00229             print 'loading', filename
00230             dict = ut.load_pickle(filename)
00231         else:
00232             dict = feature_data
00233         
00234         #print ut.getTime(), dict
00235         current_set_size = dict['set_size']
00236         feature_vector_length = len(self.processor.features.get_indexvector(self.features))
00237         print ut.getTime(), feature_vector_length
00238         labels = np.array(np.zeros(len(self.processor.map_polys)))
00239         print 'test: length of labels vector:', len(labels)
00240         test = cv.cvCreateMat(1,feature_vector_length,cv.CV_32FC1)
00241         
00242         if current_set_size == 0:
00243             print ut.getTime(), 'ERROR: test dataset is empty!'
00244             return labels, 1, 1, 1
00245 
00246         count = 0
00247         for index in dict['point_indices']:
00248             fv = (dict['features'][count])[self.processor.features.get_indexvector(self.features)]
00249             #print ut.getTime(), fv, dict['features'][count]
00250 
00251             for fv_index, fv_value in enumerate(fv):
00252                 test[fv_index] = fv_value
00253              
00254             #print 'class',self.cv_classifier
00255             label = self.cv_classifier.predict(test)
00256             #print label.value
00257             labels[index] = label.value
00258             #print 'tdone'
00259             if count % 4096 == 0:
00260                 print ut.getTime(), 'testing:', count, 'of', current_set_size, '(',(float(count)/float(current_set_size)*100.0),'%)'
00261                 
00262             count += 1
00263 
00264 
00265         #save for later use for postprocessing:
00266         self.test_feature_dict = dict
00267         self.test_labels = labels
00268         #cv.cvReleaseMat(test)
00269         return labels, self.test_results(dict, labels)  
00270         
00271     
00272     #test() has to be called before to create intermediate results!
00273     def test_postprocess(self):
00274         labels = self.postprocess(self.test_labels)
00275         return labels, self.test_results(self.test_feature_dict, labels)
00276     
00277     def postprocess(self, labels):
00278         
00279         debug = False
00280         model = ransac.PlaneLeastSquaresModel(debug)
00281         data_idx = np.where(np.asarray(labels) == processor.LABEL_SURFACE)[0]
00282         data = np.asarray(self.processor.pts3d_bound).T[data_idx]
00283         n, _ = np.shape(data)
00284         if n < 5000:
00285             k = 700
00286         else:
00287             k = 2000
00288         # run RANSAC algorithm
00289         ransac_fit, ransac_data = ransac.ransac(data,model,
00290                                          3, k, 0.04, len(data_idx)/2.5, # misc. parameters
00291                                          debug=debug,return_all=True)
00292         print 'ransac: model',ransac_fit
00293         print 'ransac:',ransac_data    
00294         print 'len inlier',len(ransac_data['inliers']),'shape pts',np.shape(self.processor.pts3d_bound)
00295 
00296         #labels[data_idx[ransac_data['inliers']]] = processor.LABEL_CLUTTER #all non-plane pts
00297         fancy = np.zeros(len(np.asarray(labels))).astype(bool)
00298         fancy[data_idx] = True
00299         fancy[data_idx[ransac_data['inliers']]] = False 
00300         labels[fancy] = processor.LABEL_CLUTTER #all surface-labeled non-plane pts
00301         
00302         return labels
00303         
00304     def save(self):
00305         classifier_filename = self.get_filename()
00306         
00307         #if file doesn't exist: create it
00308         if False == os.path.isfile(classifier_filename):
00309             open(classifier_filename,'w')
00310         self.cv_classifier.save(classifier_filename)
00311         
00312         
00313     def load(self):
00314         self.cv_classifier = cv.CvDTree() #cv.CvBoost() #TODO: CHANGE CLASSIFIER HERE
00315         print ut.getTime(), 'loading Classifier',self.features
00316         self.cv_classifier.load(self.get_filename())
00317         
00318         


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