recognize_3d.py
Go to the documentation of this file.
00001 import roslib; roslib.load_manifest('hai_sandbox')
00002 import cv
00003 
00004 import rospy
00005 import sensor_msgs.msg as sm
00006 import visualization_msgs.msg as vm
00007 
00008 import numpy as np
00009 import scipy.spatial as sp
00010 import threading
00011 import Queue as qu
00012 import os.path as pt
00013 import glob
00014 #import pdb
00015 #pdb.set_trace()
00016 import libsvm.svm as svm
00017 import libsvm.svmutil as su
00018 
00019 import copy
00020 import os
00021 
00022 import ml_lib.dataset as ds
00023 import ml_lib.dimreduce as dr
00024 
00025 #import hrl_opencv.blob as blob
00026 import hrl_lib.image3d as i3d
00027 import hrl_lib.util as ut
00028 import hrl_lib.viz as viz
00029 import hrl_lib.rutils as ru
00030 import hrl_lib.tf_utils as tfu
00031 import hrl_lib.prob as pr
00032 import hai_sandbox.intensity_feature as infea
00033 
00034 
00035 #import message_filters
00036 #import feature_extractor_fpfh.msg as fmsg
00037 import time
00038 import pdb
00039 
00040 UNLABELED = 2.0
00041 POSITIVE = 1.0
00042 NEGATIVE = 0.
00043 
00044 def confusion_matrix(true_labels, predicted):
00045     posidx = np.where(true_labels == POSITIVE)[1].A1
00046     negidx = np.where(true_labels == NEGATIVE)[1].A1
00047     m00 = m01 = m10 = m11 = 0
00048     nm00 = nm01 = nm10 = nm11 = 0
00049 
00050     if len(negidx) > 0:
00051         nm00 = float(np.sum(NEGATIVE == predicted[:, negidx]))
00052         nm01 = float(np.sum(POSITIVE == predicted[:, negidx]))
00053         m00 =  nm00 / len(negidx)
00054         m01 =  nm01 / len(negidx)
00055 
00056     if len(posidx) > 0:
00057         nm10 = float(np.sum(NEGATIVE == predicted[:, posidx]))
00058         nm11 = float(np.sum(POSITIVE == predicted[:, posidx]))
00059         m10 =  nm10 / len(posidx)
00060         m11 =  nm11 / len(posidx)
00061 
00062     return np.matrix([[m00, m01], [m10, m11]], 'float')
00063     #if verbose:
00064     #    print 'Confusion matrix:'
00065     #    print '-   %5.2f, %5.2f' % (100.* m00, 100.* m01)
00066     #    print '+  %5.2f, %5.2f' % (100.* m10, 100.* m11)
00067     #    print '   Total %5.2f' % (100.* (float(np.sum(true_labels == predicted)) / true_labels.shape[1]))
00068     #return {'mat': np.matrix([[nm00, nm01], [nm10, nm11]], 'float'), 
00069     #        'neg': len(negidx), 
00070     #        'pos': len(posidx)}
00071 
00072 
00073 def instances_to_image(win_size, instances, min_val, max_val):
00074     img_arrs = []
00075     for i in range(instances.shape[1]):
00076         img_arrs.append(instance_to_image(win_size, instances[:,i], min_val, max_val).copy())
00077     return cv.fromarray(np.concatenate(img_arrs, 0).copy())
00078 
00079 def instance_to_image(win_size, instance, min_val, max_val):
00080     winside = win_size*2+1
00081     patch_size = winside*winside*3
00082     #multipliers = [1,2,4,8,16,32]
00083     srange = max_val - min_val
00084 
00085     offset = 0
00086     patches = []
00087     num_patches = instance.shape[0] / patch_size
00088     #pdb.set_trace()
00089     #for i in range(len(multipliers)):
00090     for i in range(num_patches):
00091         s = instance[offset:offset+patch_size, 0]
00092         s = np.array(np.abs(np.round(((s-min_val)/srange) * 255.)), 'uint8')
00093         patches.append(np.reshape(s, (winside, winside, 3)))
00094         offset+=patch_size
00095     #pdb.set_trace()
00096     return np.concatenate(patches, 1)
00097 
00098 def insert_folder_name(apath, folder_name):
00099     path, filename = pt.split(apath)
00100     return pt.join(pt.join(path, folder_name), filename)
00101 
00102 def load_data_from_file2(fname, rec_param):
00103     data_pkl = ut.load_pickle(fname)
00104     image_fname = pt.join(pt.split(fname)[0], data_pkl['image'])
00105     intensity_image = cv.LoadImageM(image_fname)
00106     center_point_bl = data_pkl['touch_point']
00107 
00108     print 'Robot touched point cloud at point', center_point_bl.T
00109     distance_feature_points = None
00110     syn_locs_fname = pt.splitext(fname)[0] + '_synthetic_locs3d.pkl'
00111     if pt.isfile(syn_locs_fname):
00112         print 'found synthetic locations file', syn_locs_fname
00113         distance_feature_points = ut.load_pickle(syn_locs_fname)
00114         data_pkl['synthetic_locs3d'] = distance_feature_points
00115     else:
00116         print 'synthetic loc file not found', syn_locs_fname
00117 
00118     #return IntensityCloudData(data_pkl['points3d'], intensity_image,
00119     #        data_pkl['k_T_bl'], data_pkl['cal'], center_point_bl, center_point_bl, 
00120     #        distance_feature_points, rec_param), data_pkl
00121     return infea.IntensityCloudFeatureExtractor(data_pkl['points3d'], intensity_image, center_point_bl,
00122                                             distance_feature_points, data_pkl['k_T_bl'], 
00123                                             data_pkl['cal'], rec_param), data_pkl
00124 
00125 def dataset_to_libsvm(dataset, filename):
00126     f = open(filename, 'w')
00127 
00128     for i in range(dataset.outputs.shape[1]):
00129         if dataset.outputs[0,i] == POSITIVE:
00130             f.write('+1 ')
00131         else:
00132             f.write('-1 ')
00133         #instance
00134         for j in range(dataset.inputs.shape[0]):
00135             f.write('%d:%f ' % (j, dataset.inputs[j, i]))
00136         f.write('\n')
00137 
00138     f.close()
00139 
00140 def draw_labeled_points(image, dataset, pos_color=[255,102,55], neg_color=[0,184,245], scale=1.):
00141     #pt2d = np.column_stack(dataset.pt2d)
00142     pt2d = dataset.pt2d 
00143     for l, color in [(POSITIVE, pos_color), (NEGATIVE, neg_color)]:
00144         cols = np.where(l == dataset.outputs)[1]
00145         locs2d = np.matrix(np.round(pt2d[:, cols.A1]/scale), 'int')
00146         draw_points(image, locs2d, color)
00147 
00148 def draw_points(img, img_pts, color, size=1, thickness=-1):
00149     for i in range(img_pts.shape[1]):
00150         center = tuple(np.matrix(np.round(img_pts[:,i]),'int').T.A1.tolist())
00151         cv.Circle(img, center, size, color, thickness)
00152 
00153 def draw_dataset(dataset, img, scale=1., size=2, scan_id=None):
00154     npt2d = []
00155     ppt2d = []
00156     for i in range(dataset.inputs.shape[1]):
00157         if dataset.pt2d != None and dataset.pt2d[0,i] != None:
00158             if scan_id != None and dataset.scan_ids != None:
00159                 if scan_id != dataset.scan_ids[0,i]:
00160                     continue
00161             if POSITIVE == dataset.outputs[0,i]:
00162                 ppt2d.append(dataset.pt2d[:,i]/scale)
00163             if NEGATIVE == dataset.outputs[0,i]:
00164                 npt2d.append(dataset.pt2d[:,i]/scale)
00165     if len(ppt2d) > 0:
00166         draw_points(img, np.column_stack(ppt2d), [0,255,0], size)
00167     if len(npt2d) > 0:
00168         draw_points(img, np.column_stack(npt2d), [0,0,255], size)
00169 
00170 def inverse_indices(indices_exclude, num_elements):
00171     temp_arr = np.zeros(num_elements)+1
00172     temp_arr[indices_exclude] = 0
00173     return np.where(temp_arr)[0]
00174 
00175 #'_features_dict.pkl'
00176 def preprocess_scan_extract_features(raw_data_fname, ext):
00177     rec_params = Recognize3DParam()
00178     #if not kinect:
00179     #    feature_extractor, data_pkl = load_data_from_file(raw_data_fname, rec_params)
00180     #    image_fname = pt.join(pt.split(raw_data_fname)[0], data_pkl['high_res'])
00181     #else:
00182     feature_extractor, data_pkl = load_data_from_file2(raw_data_fname, rec_params)
00183     image_fname = pt.join(pt.split(raw_data_fname)[0], data_pkl['image'])
00184     print 'Image name is', image_fname
00185     img = cv.LoadImageM(image_fname)
00186     feature_cache_fname = pt.splitext(raw_data_fname)[0] + ext
00187     instances, points2d, points3d = feature_extractor.extract_features()
00188     labels = np.matrix([UNLABELED] * instances.shape[1])
00189 
00190     #pdb.set_trace()
00191     #cv.SaveImage('DATASET_IMAGES.png', instances_to_image(rec_params.win_size, instances[38:,:], 0., 1.))
00192     preprocessed_dict = {'instances': instances,
00193                          'points2d': points2d,
00194                          'points3d': points3d,
00195                          'image': image_fname,
00196                          'labels': labels,
00197                          'sizes': feature_extractor.get_sizes()}
00198     if data_pkl.has_key('synthetic_locs3d'):
00199         preprocessed_dict['synthetic_locs3d'] = data_pkl['synthetic_locs3d']
00200 
00201     rospy.loginfo('saving results')
00202     ut.save_pickle(preprocessed_dict, feature_cache_fname)
00203     return feature_cache_fname
00204 
00205 def preprocess_data_in_dir(dirname, ext):
00206     print 'Preprocessing data in', dirname
00207     data_files = glob.glob(pt.join(dirname, '*dataset.pkl'))
00208     print 'Found %d scans' % len(data_files)
00209 
00210     for n in data_files:
00211         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
00212         print 'Loading', n
00213         cn = preprocess_scan_extract_features(n, ext)
00214         print 'Saved to', cn
00215         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
00216 
00217 def make_point_exclusion_test_set(training_dataset, all_data_dir, ext):
00218     #pdb.set_trace()
00219     scan_names = glob.glob(pt.join(all_data_dir, '*' + ext))
00220     dset = {'inputs': [], 'outputs': [], 'pt2d': [], 'pt3d': []}
00221     sizes = None
00222     i = 0
00223     for sn in scan_names:
00224         #load scan
00225         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
00226         print 'Loading scan', sn
00227         cn = ut.load_pickle(sn)
00228         if sizes == None:
00229             sizes = cn['sizes']
00230         selected_pts_in_train = np.where(training_dataset.scan_ids == sn)[1]
00231         print '  There are %d points in scan' % cn['instances'].shape[1]
00232 
00233         #if there are points in training set that are in this scan, unselect them
00234         if len(selected_pts_in_train) > 0:
00235             print '  There are %d of these points in the training set.' % len(selected_pts_in_train)
00236             scan_ind = training_dataset.idx_in_scan[0, selected_pts_in_train].A1
00237             select_ind = inverse_indices(scan_ind, cn['instances'].shape[1])
00238             assert((len(scan_ind) + len(select_ind)) == cn['instances'].shape[1])
00239         else:
00240             select_ind = np.array(range(cn['instances'].shape[1]))
00241         print '  Including %d points from this dataset' % len(select_ind)
00242         
00243         for datak, dsetk in [('instances', 'inputs'), ('labels', 'outputs'),\
00244                   ('points2d', 'pt2d'), ('points3d', 'pt3d')]:
00245             dset[dsetk].append(cn[datak][:, select_ind])
00246         i = i + 1
00247         if i > 2:
00248             break
00249 
00250     return InterestPointDataset(np.column_stack(dset['inputs']),\
00251                                 np.column_stack(dset['outputs']),\
00252                                 None, None, None, sizes = sizes)
00253 
00254 
00255 
00256 
00257 class SVM:
00258     ##
00259     # zero is on negative side of decision boundary
00260     # 0  /  1
00261     # -  /  +
00262     def __init__(self, dataset, params):
00263         samples = dataset.inputs.T.tolist()
00264         labels = dataset.outputs.T.A1.tolist()
00265         #pdb.set_trace()
00266         print 'SVM: training with params => ', params
00267         #pdb.set_trace()
00268         #dataset_to_libsvm(dataset, 'total_set_light_switch_libsvm.data')
00269         self.model = su.svm_train(labels, samples, params)
00270         self.nsamples = len(samples)
00271 
00272     def sv_indices(self):
00273         return np.where(self.model.get_support_vectors(self.nsamples))[0]
00274 
00275     def predict(self, instances):
00276         xi = instances.T.tolist()
00277         return su.svm_predict([0]*instances.shape[1], xi, self.model)[0]
00278 
00279     def distances(self, instances):
00280         xi = instances.T.tolist()
00281         dists = su.svm_predict([0]*instances.shape[1], xi, self.model)[2]
00282         return (np.matrix(dists)).T.A1.tolist()
00283 
00284 
00285 class DataScale:
00286 
00287     def __init__(self):
00288         self.maxes = None
00289         self.mins = None
00290         self.ranges = None
00291 
00292     def scale(self, data):
00293         if self.maxes == None:
00294             self.maxes = np.max(data,1)
00295             self.mins = np.min(data,1)
00296             self.ranges = self.maxes - self.mins
00297             self.ranges[np.where(self.ranges < .001)[0], :] = 1.
00298             #pdb.set_trace()
00299         #pdb.set_trace()
00300         #pdb.set_trace()
00301         scaled = (((data - self.mins) / self.ranges) * 2.) - 1
00302         return scaled
00303 
00304 
00305 class PCAIntensities:
00306 
00307     def __init__(self, intensities_index, reconstruction_std_lim, reconstruction_err_toler):
00308         self.intensities_mean     = None
00309         self.intensities_std      = None
00310         self.projection_basis     = None
00311         self.intensities_index    = intensities_index
00312         self.recon_err_raw        = None
00313         self.reconstruction_error = None
00314         self.pca_data             = None
00315         self.reconstruction_std_lim = reconstruction_std_lim
00316         self.reconstruction_err_toler = reconstruction_err_toler
00317 
00318     def calculate_pca_vectors(self, data, variance_keep):
00319         data_in = data[self.intensities_index:, :]
00320         #we already have pca vectors
00321         #pdb.set_trace()
00322         print 'PCAIntensities: data.shape', data.shape
00323         if self.intensities_mean != None:
00324             normed_data = (data_in - self.intensities_mean) / self.intensities_std
00325             if not self.is_dataset_far_from_pca_subspace(self.projection_basis.T * normed_data, normed_data):
00326                 print 'PCAIntensities: is_dataset_far_from_pca_subspace no, dataset is not far.'
00327                 return
00328             else:
00329                 print 'PCAIntensities: is_dataset_far_from_pca_subspace yes, dataset is far. recalculating pca.'
00330                 #pdb.set_trace()
00331                 nsamples = min(data_in.shape[1], 3000) #2000 is the max that we can handle
00332                 loaded_data = ut.load_pickle(self.pca_data)
00333                 data_in  = np.column_stack((data_in, loaded_data[self.intensities_index:, :]))
00334                 ntotal   = data_in.shape[1]
00335                 data_in  = data_in[:, np.random.permutation(np.array(range(ntotal)))[0:nsamples]]
00336 
00337         self.intensities_mean = np.mean(data_in, 1)
00338         self.intensities_std = np.std(data_in, 1)
00339         self.intensities_std[np.where(self.intensities_std == 0)[0].A1, :] = 1
00340 
00341         data_in_shifted = data_in - self.intensities_mean
00342         data_in_normed = data_in_shifted / self.intensities_std
00343         print 'PCAIntensities.calculate_pca_vectors: Constructing PCA basis'
00344         #self.projection_basis = dr.pca_vectors(data_in_normed, variance_keep)[:,:50]
00345         #pdb.set_trace()
00346         self.projection_basis = dr.pca_vectors(data_in_normed, variance_keep)[:,:50]
00347         #self.projection_basis = dr.pca_vectors(data_in_normed, variance_keep)
00348         print 'PCAIntensities.calculate_pca_vectors: PCA basis size -', self.projection_basis.shape
00349 
00350         projected = (self.projection_basis.T * data_in_normed)
00351         reconstruction = self.projection_basis * projected
00352         self.recon_err_raw = ut.norm(data_in_normed - reconstruction)
00353         self.recon_mean = np.mean(self.recon_err_raw)
00354         self.recon_std = np.std(self.recon_err_raw)
00355         self.reconstruction_error = self.calc_reconstruction_errors(projected, data_in_normed)
00356 
00357         pca_data_name = time.strftime('%A_%m_%d_%Y_%I:%M%p') + '_pca_data.pkl'
00358         #pdb.set_trace()
00359         ut.save_pickle(data, pca_data_name)
00360         self.pca_data = pca_data_name
00361 
00362     def calc_reconstruction_errors(self, projected_instances, original_instances):
00363         errors = ut.norm((self.projection_basis * projected_instances) - original_instances)
00364         mal_dist_errors = (errors - self.recon_mean) / (self.recon_std**2)
00365         nhigh_errors = np.sum(np.abs(mal_dist_errors).A1 > self.reconstruction_std_lim)
00366         npoints = original_instances.shape[1]
00367         percent_error = nhigh_errors / (float(npoints))
00368         rospy.loginfo('calc_reconstruction_errors: %.2f (%d / %d) with high reconstruction errors' \
00369                 % (percent_error, nhigh_errors, npoints))
00370         return percent_error
00371 
00372     def is_dataset_far_from_pca_subspace(self, projected_instances, original_instances):
00373         percent_error = self.calc_reconstruction_errors(projected_instances, original_instances)
00374         return percent_error > (self.reconstruction_error + self.reconstruction_err_toler)
00375 
00376     def partial_pca_project(self, instances):
00377         #pdb.set_trace()
00378         #self.intensities_mean = np.mean(data_in, 1)
00379         #instances1084G
00380         instance_mean = np.mean(instances[self.intensities_index:, :], 1) 
00381         #instances_in = (instances[self.intensities_index:, :] - self.intensities_mean) / self.intensities_std
00382         instances_in = (instances[self.intensities_index:, :] - instance_mean) / self.intensities_std
00383         reduced_intensities = self.projection_basis.T * instances_in
00384         return np.row_stack((instances[:self.intensities_index, :], reduced_intensities))
00385 
00386 class SVMPCA_ActiveLearner:
00387     def __init__(self, use_pca, reconstruction_std_lim=None, 
00388                  reconstruction_err_toler=None, old_learner=None, pca=None):
00389         self.classifier = 'svm' #or 'knn'
00390         self.classifiers = {}
00391         self.n = 3.
00392 
00393         #self.intensities_mean = None
00394         #self.projection_basis = None
00395         self.reduced_dataset = None
00396         self.dataset = None
00397 
00398         self.use_pca = use_pca
00399         self.reconstruction_std_lim = reconstruction_std_lim
00400         self.reconstruction_err_toler = reconstruction_err_toler
00401         self.pca = None
00402 
00403         if old_learner != None:
00404             self.pca = old_learner.pca
00405 
00406         if pca != None:
00407             self.pca = pca
00408 
00409         #pdb.set_trace()
00410         #if old_learner != None:
00411         #    self.intensities_mean = old_learner.intensities_mean
00412         #    self.intensities_std = old_learner.intensities_std
00413         #    self.projection_basis = old_learner.projection_basis
00414         #    self.intensities_index = old_learner.intensities_index
00415         #    self.recon_err_raw = old_learner.recon_err_raw
00416         #    self.reconstruction_error = old_learner.reconstruction_error
00417         #    self.pca_data = old_learner.pca_data
00418 
00419     def partial_pca_project(self, instances):
00420         if self.use_pca:
00421             return self.pca.partial_pca_project(instances)
00422         else:
00423             return instances
00424 
00425     def get_closest_instances(self, instances, n=1):
00426         #pdb.set_trace()
00427         if self.use_pca:
00428             p_instances = np.matrix(self.partial_pca_project(instances))
00429         else:
00430             p_instances = instances
00431             #pdb.set_trace()
00432         s_instances = self.scale.scale(p_instances)
00433         distances = np.array(self.classifiers['svm'].distances(s_instances))
00434         selected_indices = np.argsort(np.abs(distances))[0:n]
00435         return selected_indices.tolist(), distances[selected_indices]
00436 
00437     def select_next_instances(self, instances, n=1):
00438         #pdb.set_trace()
00439         data_idx, data_dists = self.get_closest_instances(instances, n)
00440         data_dist = abs(data_dists[0])
00441         sv_dist   = abs(self.sv_dist[0])
00442 
00443         #we've converged if distance to datapoint closest to decision boundary
00444         #is no closer than distance to the support vectors. 
00445         #So we return nothing as a proposal.
00446         print 'SVMPCA_ActiveLearner: support vector dist %f data dist %f' % (sv_dist, data_dist)
00447         if sv_dist < data_dist:
00448             return None, None
00449         else:
00450             return data_idx, data_dists
00451 
00452     def select_next_instances_no_terminate(self, instances, n=1):
00453         data_idx, data_dists = self.get_closest_instances(instances, n)
00454         data_dist = abs(data_dists[0])
00455         sv_dist   = abs(self.sv_dist[0])
00456         return data_idx, data_dists, sv_dist < data_dist
00457 
00458     def train(self, dataset, inputs_for_scaling, svm_params, variance_keep=.95):
00459         #pdb.set_trace()
00460         #pdb.set_trace()
00461         #TODO: somehow generate labels for these datasets...
00462         self.dataset = dataset
00463         trainingset = dataset.inputs
00464         responses = dataset.outputs
00465 
00466         #Calculate PCA vectors (also try do detect if our PCA vectors need updating)
00467         if self.use_pca: #and self.projection_basis == None:
00468             #self.intensities_index = self.dataset.metadata[-1].extent[0]
00469             #rebalanced_set = self._balance_classes(trainingset, responses)
00470             #self._calculate_pca_vectors(rebalanced_set, variance_keep)
00471             #self._calculate_pca_vectors(inputs_for_scaling, variance_keep)
00472             if self.pca == None:
00473                 self.pca = PCAIntensities(self.dataset.metadata[-1].extent[0], self.reconstruction_std_lim, self.reconstruction_err_toler)
00474             self.pca.calculate_pca_vectors(inputs_for_scaling, variance_keep)
00475             #self.pca.calculate_pca_vectors(rebalanced_set, variance_keep, incremental=True)
00476 
00477         trainingset = self.partial_pca_project(trainingset)
00478         inputs_for_scaling = self.partial_pca_project(inputs_for_scaling)
00479     
00480         print 'SVMPCA_ActiveLearner.train: Training classifier.'
00481         #train => float32 mat, each row is an example
00482         #responses => float32 mat, each column is a corresponding response
00483         trainingset = np.matrix(trainingset, dtype='float32').copy()
00484         responses = np.matrix(responses, dtype='float32').copy()
00485 
00486         self.reduced_dataset = ds.Dataset(trainingset.copy(), responses.copy())
00487         self.scale = DataScale()
00488         if inputs_for_scaling == None:
00489             inputs_for_scaling = self.reduced_dataset.inputs
00490         else:
00491             print 'SVMPCA_ActiveLearner.train: using large input set for setting scaling parameters'
00492         self.scale.scale(inputs_for_scaling)
00493         rescaled_inputs = self.scale.scale(self.reduced_dataset.inputs)
00494         self.rescaled_dataset = ds.Dataset(rescaled_inputs, self.reduced_dataset.outputs)
00495 
00496         #dataset_to_libsvm(self.rescaled_dataset, 'interest_point_data.libsvm')
00497         self.classifiers['svm'] = SVM(self.rescaled_dataset, svm_params)
00498         #self.classifiers['knn'] = sp.KDTree(np.array(self.rescaled_dataset.inputs.T))
00499 
00500         self.sv_instances = self.dataset.inputs[:, self.classifiers['svm'].sv_indices()]
00501         self.sv_idx, self.sv_dist = self.get_closest_instances(self.sv_instances, 1)
00502 
00503     def classify(self, instances):
00504         #pdb.set_trace()
00505         projected_inst = np.matrix(self.partial_pca_project(instances), dtype='float32').copy()
00506         scaled_inst = self.scale.scale(projected_inst)
00507         if self.classifier == 'knn':
00508             labels = self.reduced_dataset.outputs[:, \
00509                     self.classifiers['knn'].query(scaled_inst, self.n)[1].tolist()[0]]
00510             if np.sum(labels) > (self.n/2.):
00511                 return POSITIVE
00512             else:
00513                 return NEGATIVE
00514 
00515         elif self.classifier == 'svm':
00516             #pdb.set_trace()
00517             r = self.classifiers['svm'].predict(scaled_inst)
00518             return r
00519 
00520     def _balance_classes(self, data, labels):
00521         posidx = np.where(labels == POSITIVE)[1].A1
00522         negidx = np.where(labels == NEGATIVE)[1].A1
00523         diff = abs(posidx.shape[0] - negidx.shape[0])
00524         if diff == 0:
00525             return data
00526 
00527         rospy.loginfo('SVMPCA_ActiveLearner: _balance_classes difference in class sizes is %d' % diff)
00528 
00529         posex = data[:, posidx]
00530         negex = data[:, negidx]
00531         if posidx.shape[0] < negidx.shape[0]:
00532             rospy.loginfo('SVMPCA_ActiveLearner. _balance_classes making data from POSITIVE instances')
00533             sset = posex
00534         else:
00535             rospy.loginfo('SVMPCA_ActiveLearner. _balance_classes making data from NEGATIVE instances')
00536             sset = negex
00537         
00538         rsubset = sset[:, np.random.randint(0, sset.shape[1], diff)]
00539         rospy.loginfo('SVMPCA_ActiveLearner: _balance_classes created %d instances to make up for it' % rsubset.shape[1])
00540 
00541         return np.column_stack((posex, negex, rsubset))
00542 
00543 class InterestPointDataset(ds.Dataset):
00544 
00545     def __init__(self, inputs, outputs, pt2d, pt3d, feature_extractor, scan_ids=None, idx_in_scan=None, sizes=None):
00546         ds.Dataset.__init__(self, inputs, outputs)
00547         self.pt2d = pt2d
00548         self.pt3d = pt3d
00549         self.scan_ids = scan_ids
00550         #if scan_ids != None:
00551         #    print 'scan id class', self.scan_ids.__class__
00552         self.idx_in_scan = idx_in_scan
00553         offset = 0
00554 
00555         #Intensity has to be the last feature
00556         if feature_extractor != None or sizes != None:
00557             if feature_extractor != None:
00558                 sizes = feature_extractor.get_sizes
00559             for k in ['expected_loc', 'distance', 'fpfh', 'intensity']:
00560                 if sizes.has_key(k):
00561                     start_idx = offset 
00562                     end_idx = offset + sizes[k]
00563                     self.add_attribute_descriptor(ds.AttributeDescriptor(k, (start_idx, end_idx)))
00564                     offset = end_idx
00565 
00566     def select_features(self, features):
00567         fset = set(features)
00568         selected_fea = []
00569         meta_data = []
00570         offset = 0
00571         for meta in self.metadata:
00572             m = copy.deepcopy(meta)
00573             if fset.issuperset([m.name]):
00574                 # TODO FIX THIS
00575                 #if m.name == 'distance':
00576                 #    m.extent = [0,4]
00577                 size_m = m.extent[1] - m.extent[0]
00578                 selected_fea.append(self.inputs[m.extent[0]:m.extent[1], :])
00579                 m.extent = [offset, offset+size_m]
00580                 meta_data.append(m)
00581                 offset = offset + size_m
00582         self.metadata = meta_data
00583         self.inputs = np.row_stack(selected_fea)
00584 
00585     def features_named(self, features):
00586         fset = set(features)
00587         selected_fea = []
00588         for meta in self.metadata:
00589             if fset.issuperset([meta.name]):
00590                 selected_fea.append(self.inputs[meta.extent[0]:meta.extent[1], :])
00591         return np.row_stack(selected_fea)
00592 
00593     def add(self, features, label, pt2d, pt3d, scan_id=None, idx_in_scan=None):
00594         print 'added point', pt2d[0,0], pt2d[1,0]
00595         if np.abs(pt2d[1,0]) > 10000:
00596             pdb.set_trace()
00597         if np.abs(pt2d[0,0]) > 10000:
00598             pdb.set_trace()
00599         self.inputs = np.column_stack((self.inputs, features))
00600         self.outputs = np.column_stack((self.outputs, label))
00601         self.pt2d = np.column_stack((self.pt2d, pt2d))
00602         self.pt3d = np.column_stack((self.pt3d, pt3d))
00603         if scan_id != None:
00604             self.scan_ids = np.column_stack((self.scan_ids, scan_id))
00605         if idx_in_scan != None:
00606             self.idx_in_scan = np.column_stack((self.idx_in_scan, idx_in_scan))
00607         
00608     def remove(self, instance_idx):
00609         self.inputs = np.column_stack((self.inputs[:,0:instance_idx], self.inputs[:,instance_idx+1:]))
00610         self.outputs = np.column_stack((self.outputs[:,0:instance_idx], self.outputs[:,instance_idx+1:]))
00611         self.pt2d = np.column_stack((self.pt2d[:,0:instance_idx], self.pt2d[:,instance_idx+1:]))
00612         self.pt3d = np.column_stack((self.pt3d[:,0:instance_idx], self.pt3d[:,instance_idx+1:]))
00613         if self.scan_ids != None:
00614             self.scan_ids = np.column_stack((self.scan_ids[:,0:instance_idx], self.scan_ids[:,instance_idx+1:]))
00615         if self.idx_in_scan != None:
00616             self.idx_in_scan = np.column_stack((self.idx_in_scan[:,0:instance_idx], self.idx_in_scan[:,instance_idx+1:]))
00617 
00618     def copy(self):
00619         ipd = InterestPointDataset(self.inputs.copy(), self.outputs.copy(), 
00620                 copy.copy(self.pt2d), copy.copy(self.pt3d), None)
00621         ipd.metadata = copy.deepcopy(self.metadata)
00622         return ipd
00623 
00624     def subset(self, indices):
00625         ipd = InterestPointDataset(self.inputs[:, indices].copy(), self.outputs[:, indices].copy(), 
00626                 copy.copy(self.pt2d[:, indices]), copy.copy(self.pt3d[:, indices]), None)
00627         ipd.metadata = copy.deepcopy(self.metadata)
00628         return ipd
00629 
00630     @classmethod
00631     def add_to_dataset(cls, dataset, features, label, pt2d, pt3d, scan_id, idx_in_scan, sizes):
00632         if dataset == None:
00633             dataset = InterestPointDataset(features, label, pt2d, pt3d, None, scan_id, idx_in_scan, sizes)
00634         else:
00635             dataset.add(features, label, pt2d, pt3d, scan_id=scan_id, idx_in_scan=idx_in_scan)
00636         return dataset
00637 
00638 
00639 class Recognize3DParam:
00640 
00641     def __init__(self):
00642         #Data extraction parameters
00643         self.grid_resolution = .01
00644         self.win_size = 15
00645         #self.win_multipliers = [1,2,4,8,16,32] for prosilica
00646         #self.win_multipliers = [1,2,4,8,16,32]
00647         self.win_multipliers = [2,4,8,16]
00648 
00649         self.win3d_size = .02
00650         self.voi_bl = [.5, .5, .5]
00651         self.radius = .5
00652         self.robot_reach_radius = 2.5
00653         #self.svm_params = '-s 0 -t 2 -g .0625 -c 4'
00654         #self.svm_params = '-s 0 -t 2 -g .0625 -c 4'
00655         #self.svm_params = '-s 0 -t 2 -g .4 -c 4'
00656         #self.svm_params = '-s 0 -t 2 -g 3.0 -c 4'
00657         #self.svm_params = '-s 0 -t 2 -g 5. -c 4'
00658         #self.svm_params = '-s 0 -t 2 -g .01 -c 4'
00659         #self.svm_params = '-s 0 -t 2 -g .2 -c 4'
00660         self.svm_params = '-s 0 -t 2 -g .5 -c .5'
00661         #self.svm_params = '-s 0 -t 2 -g 100 -c .5'
00662 
00663         #sampling parameters
00664         #self.n_samples = 5000
00665         #self.n_samples = 5000
00666         self.n_samples = 1500
00667         self.uni_mix = .3
00668         self.max_points_per_site = 5
00669 
00670         self.uncertainty_x = .1
00671         self.uncertainty_y = .1
00672         self.uncertainty_z = .1
00673         #print "Uncertainty is:", self.uncertainty
00674 
00675         #variance
00676         self.variance_keep = .99
00677         self.reconstruction_std_lim = 1.
00678         self.reconstruction_err_toler = .05
00679 
00680 
00681 class ImagePublisher:
00682 
00683     def __init__(self, channel, cal=None):
00684         from cv_bridge import CvBridge, CvBridgeError
00685         from sensor_msgs.msg import Image
00686 
00687         self.bridge = CvBridge()
00688         self.image_pub = rospy.Publisher(channel + '/image', Image)
00689         if cal != None:
00690             self.image_cal_pub = rospy.Publisher(channel + '/camera_info', sm.CameraInfo)
00691             self.cal = cal
00692         else:
00693             self.image_cal_pub = None
00694 
00695     def publish(self, cv_image): 
00696         self.image_pub.publish(self.bridge.cv_to_imgmsg(cv_image, "bgr8"))
00697         if self.image_cal_pub != None:
00698             self.image_cal_pub.publish(self.cal.msg)
00699 
00700 def find_max_in_density(locs2d):
00701     import scipy.stats as sct
00702     import scipy
00703     x = locs2d[0,:]
00704     y = locs2d[1,:]
00705 
00706     max_x = np.max(x)
00707     max_y = np.max(y)
00708     min_x = np.min(x)
00709     min_y = np.min(y)
00710 
00711     X, Y      = scipy.mgrid[min_x:max_x:500j, min_y:max_y:500j]
00712     positions = scipy.c_[X.ravel(), Y.ravel()]
00713     values    = scipy.c_[locs2d[0,:].A1, locs2d[1,:].A1]
00714     kernel    = sct.kde.gaussian_kde(values.T)
00715     Z         = np.reshape(kernel(positions.T).T, X.T.shape)
00716     loc_max   = np.argmax(Z)
00717     loc2d_max = np.matrix([X.flatten()[loc_max], Y.flatten()[loc_max]]).T
00718     
00719     #pylab.imshow(np.rot90(Z, 2), cmap=pylab.cm.gist_earth_r, extent=[0,img.cols, 0, img.rows])
00720     #pylab.imshow(img, cmap=pylab.cm.gist_earth_r, extent=[0,img.cols, 0, img.rows])
00721     #pylab.plot(locs2d[0,:].A1, locs2d[1,:].A1, 'k.', markersize=2)
00722     #pylab.plot([loc2d_max[0,0]], [loc2d_max[1,0]], 'gx')
00723     #cv.ShowImage("Positive Density", 255 * (np.rot90(Z)/np.max(Z)))
00724     #pdb.set_trace()
00725 
00726     return loc2d_max, Z
00727 
00728 class ScanLabeler:
00729 
00730     def __init__(self, dirname, ext, scan_to_train_on, seed_dset, features_to_use):
00731         self.scan_dir_name = dirname
00732         self.scan_names = glob.glob(pt.join(dirname, '*' + ext))
00733         self.scan_names.append(self.scan_names.pop(0))
00734         self.feature_file_ext = ext
00735         self.features_to_use = features_to_use
00736 
00737         self.current_scan_pred = None
00738         self.current_scan = None
00739         self.cdisp = None
00740 
00741         self.scan_idx = self.search_dataset_id(scan_to_train_on)
00742         if self.scan_idx == None:
00743             print 'ERROR: %s not found in dir %s' % (scan_to_train_on, dirname)
00744             self.scan_idx = 0
00745 
00746         self.scale = 1/3.
00747         #self.scale = 1.
00748         self.mode = 'GROUND_TRUTH'
00749         if seed_dset == None:
00750             self.training_sname = pt.splitext(self.scan_names[self.scan_idx])[0] + '_seed.pkl'
00751         else:
00752             self.training_sname = seed_dset
00753         print 'Using seed dataset name', self.training_sname
00754         self.frame_number = 0
00755 
00756         self.rec_params = Recognize3DParam()
00757         self.learner = None
00758         self.dataset = None #Training dataset
00759 
00760         cv.NamedWindow('Scan', cv.CV_WINDOW_AUTOSIZE)
00761         cv.NamedWindow('Positive Density', cv.CV_WINDOW_AUTOSIZE)
00762         self.load_scan(self.scan_names[self.scan_idx])
00763         cv.SetMouseCallback('Scan', self.mouse_cb, None)
00764 
00765 
00766     def search_dataset_id(self, scan_name):
00767         scan_idx = None
00768         for i, n in enumerate(self.scan_names):
00769             if n == scan_name:
00770                 scan_idx = i
00771         return scan_idx
00772 
00773 
00774     def classify_current_scan(self):
00775         if self.learner != None:
00776             sdset = self.select_features(self.current_scan['instances'], 
00777                     self.features_to_use, self.current_scan['sizes'])
00778             results = np.matrix(self.learner.classify(sdset))
00779             self.current_scan_pred = InterestPointDataset(sdset, results,
00780                                         self.current_scan['points2d'], self.current_scan['points3d'], None)
00781             if np.any(self.current_scan['labels'] == UNLABELED):
00782                 return
00783         
00784     def load_scan(self, fname):
00785         print 'Loading scan', fname
00786         self.cdisp = {}
00787         self.current_scan = ut.load_pickle(fname)
00788         #image_fname = pt.join(pt.split(fname)[0], self.current_scan['image'])
00789         img = cv.LoadImageM(self.current_scan['image'])
00790         self.cdisp['tree'] = sp.KDTree(np.array(self.current_scan['points2d'].T))
00791         self.cdisp['cv'] = cv.CreateMat(int(round(img.rows*self.scale)), 
00792                                         int(round(img.cols*self.scale)), cv.CV_8UC3)
00793         cv.Resize(img, self.cdisp['cv'])
00794         print 'loaded!'
00795         self.classify_current_scan()
00796         self.draw()
00797 
00798     def save_current(self):
00799         print 'saving current scan\'s data'
00800         fname = self.scan_names[self.scan_idx]
00801         print 'WARNING: THIS SHOULD NOT BE CALLED.'
00802         ut.save_pickle(self.current_scan, fname)
00803         print 'done saving!'
00804 
00805     def load_next(self):
00806         self.scan_idx = max(min(self.scan_idx+1, len(self.scan_names)-1), 0)
00807         self.load_scan(self.scan_names[self.scan_idx])
00808 
00809     def load_prev(self):
00810         self.scan_idx = min(max(self.scan_idx-1, 0), len(self.scan_names)-1)
00811         self.load_scan(self.scan_names[self.scan_idx])
00812 
00813     def draw(self, save_postf=""):
00814         img = cv.CloneMat(self.cdisp['cv'])
00815         #density_img = cv.fromarray(np.zeros((img.rows, img.cols)))
00816 
00817         #Draw ground truth labels
00818         #pdb.set_trace()
00819         pidx = np.where(self.current_scan['labels'] == POSITIVE)[1].A1.tolist()
00820         nidx = np.where(self.current_scan['labels'] == NEGATIVE)[1].A1.tolist()
00821         uidx = np.where(self.current_scan['labels'] == UNLABELED)[1].A1.tolist()
00822 
00823         if len(pidx) > 0:
00824             ppoints = self.current_scan['points2d'][:, pidx]
00825             draw_points(img, ppoints * self.scale, [0,255,0], 2, 1)
00826 
00827         if len(nidx) > 0:
00828             npoints = self.current_scan['points2d'][:, nidx]
00829             draw_points(img, npoints * self.scale, [0,0,255], 2, 1)
00830 
00831         if len(uidx) > 0:
00832             upoints = self.current_scan['points2d'][:, uidx]
00833             draw_points(img, upoints * self.scale, [255,255,255], 2, 1)
00834 
00835         #Draw training set
00836         if self.dataset != None:
00837             #pdb.set_trace()
00838             draw_dataset(self.dataset, img, 1./self.scale, 4, scan_id=self.scan_names[self.scan_idx])
00839 
00840         if self.current_scan_pred != None:
00841             draw_labeled_points(img, self.current_scan_pred, scale=1./self.scale)
00842             locs2d = self.current_scan_pred.pt2d[:, (np.where(POSITIVE == self.current_scan_pred.outputs)[1]).A1]
00843 
00844         #    loc_max, Z = find_max_in_density(locs2d)
00845         #    print 'Max location is', loc_max.T
00846         #    cv.ShowImage("Positive Density", 255 * (np.rot90(Z)/np.max(Z)))
00847 
00848             #X, Y = scipy.mgrid[0:img.cols:500j, 0:img.rows:500j]
00849             #positions = scipy.c_[X.ravel(), Y.ravel()]
00850             #values = scipy.c_[locs2d[0,:].A1, locs2d[1,:].A1]
00851             #kernel = sct.kde.gaussian_kde(values.T)
00852             #Z = np.reshape(kernel(positions.T).T, X.T.shape)
00853             #loc_max = np.argmax(Z)
00854             #loc2d_max = np.matrix([X.flatten()[loc_max], Y.flatten()[loc_max]]).T
00855             ##pdb.set_trace()
00856 
00857             #pylab.imshow(np.rot90(Z, 2), cmap=pylab.cm.gist_earth_r, extent=[0,img.cols, 0, img.rows])
00858             ##pylab.imshow(img, cmap=pylab.cm.gist_earth_r, extent=[0,img.cols, 0, img.rows])
00859             #pylab.plot(locs2d[0,:].A1, locs2d[1,:].A1, 'k.', markersize=2)
00860             #pylab.plot([loc2d_max[0,0]], [loc2d_max[1,0]], 'gx')
00861             #pdb.set_trace()
00862             #pylab.show()
00863             #draw_labeled_points(density_img, self.current_scan_pred, 
00864             #        scale=1./self.scale, pos_color=[255, 255, 255], neg_color=[0,0,0])
00865             #cv.Smooth(density_img, density_img, cv.CV_GAUSSIAN, 151, 151, 2)
00866 
00867         #Display
00868         #cv.ShowImage('Positive Density', density_img)
00869         cv.ShowImage('Scan', img)
00870         path = pt.splitext(insert_folder_name(self.scan_names[self.scan_idx], save_postf))[0]
00871         img_name = path + ('_active_learn%d.png' % (self.frame_number))
00872         cv.SaveImage(img_name, img)
00873         self.frame_number = self.frame_number + 1
00874         print '- refreshed display - %s' % img_name
00875 
00876     def step(self):
00877         k = cv.WaitKey(33)
00878         if k == ord('n'):
00879             print 'Loading next scan..'
00880             self.load_next()
00881 
00882         if k == ord('p'):
00883             print 'loading previous scan..'
00884             self.load_prev()
00885 
00886         if k == ord('0'):
00887             self.current_scan['labels'][0, :] = NEGATIVE
00888             self.draw()
00889             print 'Labeling everything as negative!'
00890 
00891         if k == ord('`'):
00892             if self.mode == 'TRAINING_SET':
00893                 self.mode = 'GROUND_TRUTH'
00894             else:
00895                 self.mode = 'TRAINING_SET'
00896             print 'ScanLabeler GUI mode changed to', self.mode
00897 
00898         if k == ord('c'):
00899             self.save_current()
00900             
00901         if k == ord('s'):
00902             if self.dataset != None:
00903                 #pdb.set_trace()
00904                 ut.save_pickle(self.dataset, self.training_sname)
00905                 print 'saved to', self.training_sname
00906 
00907         if k == ord('l'):
00908             if self.dataset == None and pt.isfile(self.training_sname):
00909                 print 'loading training set from disk'
00910                 self.dataset = ut.load_pickle(self.training_sname)
00911                 print 'loaded', self.training_sname
00912                 self.draw()
00913 
00914         if k == ord('t'):
00915             if self.dataset != None:
00916                 print 'Making test set.'
00917                 curr_test_set = make_point_exclusion_test_set(self.dataset, self.scan_dir_name)
00918                 print 'Test set has %d instances' % curr_test_set.inputs.shape[1]
00919                 fname = raw_input('Enter test set name to save to: ')
00920                 print 'Saving to', fname
00921                 ut.save_pickle(curr_test_set, fname)
00922                 print 'Saved!'
00923 
00924         if k == ord('r'):
00925             print "Training"
00926             #pdb.set_trace()
00927             self.train(self.select_features(self.current_scan['instances'], 
00928                 self.features_to_use, self.current_scan['sizes']))
00929             self.classify_current_scan()
00930             self.draw()
00931 
00932         if k == ord(' '):
00933             if self.learner != None:
00934                 print "selecting.."
00935                 #pdb.set_trace()
00936                 dset = self.select_features(self.current_scan['instances'], 
00937                         self.features_to_use, self.current_scan['sizes'])
00938                 #self.current_scan['instances']
00939                 selected_idx, selected_dist = self.learner.select_next_instances(dset)
00940                 if selected_idx != None:
00941                     self.add_to_training_set(selected_idx)
00942                     #self.train(self.train(self.current_scan['instances']))
00943                     self.train(self.select_features(self.current_scan['instances'], 
00944                         self.features_to_use, self.current_scan['sizes']))
00945                     self.classify_current_scan()
00946                     self.draw()
00947                 else:
00948                     print '======================='
00949                     print '>> LEARNER CONVERGED <<'
00950                     print '======================='
00951 
00952         if k == ord('z'):
00953             #d = self.dataset
00954             #d1 = InterestPointDataset(self.current_scan['instances'], self.current_scan['labels'],
00955             #        self.current_scan['points2d'], self.current_scan['points3d'], 
00956             #        None, sizes=self.current_scan['sizes'])
00957             # self.load_next()
00958             # d1.add(self.current_scan['instances'], self.current_scan['labels'],
00959             #         self.current_scan['points2d'], self.current_scan['points3d'])
00960 
00961             #self.dataset = d1
00962             #self.train()
00963             print 'generating libsvm dataset'
00964             dfname = raw_input('enter dataset filename: ')
00965             dataset_to_libsvm(self.learner.rescaled_dataset, dfname)
00966             #self.dataset = d
00967             print 'done'
00968 
00969     #def instances_to_image(self, instances, min_val, max_val):
00970     #    img_arrs = []
00971     #    for i in range(instances.shape[1]):
00972     #        img_arrs.append(self.instance_to_image(instances[:,i], min_val, max_val).copy())
00973     #    return cv.fromarray(np.concatenate(img_arrs, 0).copy())
00974 
00975     #def instance_to_image(self, instance, min_val, max_val):
00976     #    winside = self.rec_params.win_size * 2 + 1
00977     #    patch_size = winside*winside*3
00978     #    multipliers = [1,2,4,8,16,32]
00979     #    srange = max_val - min_val
00980 
00981     #    offset = 0
00982     #    patches = []
00983     #    for i in range(len(multipliers)):
00984     #        s = instance[offset:offset+patch_size, 0]
00985     #        s = np.array(np.abs(np.round(((s-min_val)/srange) * 255.)), 'uint8')
00986     #        patches.append(np.reshape(s, (winside, winside, 3)))
00987     #    return np.concatenate(patches, 1)
00988 
00989     def select_features(self, instances, features_to_use, sizes):
00990         offset = 0
00991         fset = set(features_to_use)
00992         selected_fea = []
00993         for k in ['expected_loc', 'distance', 'fpfh', 'intensity']:
00994             if not sizes.has_key(k):
00995                 continue
00996             start_idx = offset 
00997             end_idx = offset + sizes[k]
00998 
00999             if fset.issuperset([k]):
01000                 selected_fea.append(instances[start_idx:end_idx, :])
01001             offset = end_idx
01002 
01003         #pdb.set_trace()
01004         return np.row_stack(selected_fea)
01005 
01006     def automatic_label(self):
01007         self.dataset = ut.load_pickle(self.training_sname)
01008         fea = self.select_features(self.current_scan['instances'], ['distance'], self.current_scan['sizes'])
01009         #pdb.set_trace()
01010         self.train(fea)
01011         #for name in ['4_20_2011/down/Monday_04_18_2011_11_20PM_interest_point_dataset_features_df2_dict.pkl']:
01012         for idx, name in enumerate(self.scan_names):
01013             self.scan_idx = idx
01014             self.load_scan(name)
01015             self.classify_current_scan()
01016             self.draw()
01017             #pdb.set_trace()
01018             self.current_scan['labels'][0,:] = self.current_scan_pred.outputs[0,:]
01019             self.draw()
01020             self.save_current()
01021 
01022         #for k in ['expected_loc', 'distance', 'fpfh', 'intensity']:
01023 
01024 
01025     def test_feature_perf(self, scans_to_train_on, features_to_use, exp_name, use_pca=None):
01026         #Make folder for results
01027         BASE_FILE_NAME = pt.splitext(insert_folder_name(self.scan_names[self.scan_idx], exp_name))[0] #pt.splitext(self.scan_names[self.scan_idx])[0]
01028         try:
01029             os.mkdir(pt.split(BASE_FILE_NAME)[0])
01030         except OSError, e:
01031             if e.errno != 17:
01032                 pdb.set_trace()
01033                 raise e
01034 
01035         #Decide whether to use PCA
01036         if use_pca == None:
01037             if set(features_to_use).issuperset(['intensity']):
01038                 use_pca = True
01039             else:
01040                 use_pca = False
01041 
01042         if not pt.isfile(self.training_sname):
01043             print 'test_feature_perf: Training file', self.training_sname, 'not found! exiting.'
01044             return
01045 
01046         #Construct new dataset
01047         feature_sizes = self.current_scan['sizes']
01048         nsizes = {}
01049         for f in features_to_use:
01050             nsizes[f] = feature_sizes[f]
01051 
01052         dset_trained_on = []
01053         for sname in scans_to_train_on:
01054             scan_idx = self.search_dataset_id(sname)
01055             if scan_idx == None:
01056                 print 'ERROR: %s not found in dir given' % (sname)
01057             dset_trained_on.append(scan_idx)
01058             self.load_scan(self.scan_names[scan_idx])
01059             rcurrent_scan = self.select_features(self.current_scan['instances'], features_to_use, feature_sizes)
01060             scan_ids = np.matrix([sname]*rcurrent_scan.shape[1])
01061             idx_in_scan = np.matrix(range(rcurrent_scan.shape[1]))
01062             if self.dataset == None:
01063                 self.dataset = InterestPointDataset(rcurrent_scan, self.current_scan['labels'], 
01064                                     self.current_scan['points2d'], self.current_scan['points3d'], 
01065                                     None, scan_ids=scan_ids, idx_in_scan=idx_in_scan, sizes=nsizes)
01066             else:
01067                 self.dataset.add(rcurrent_scan, self.current_scan['labels'], self.current_scan['points2d'],
01068                                  self.current_scan['points3d'], scan_id=scan_ids, idx_in_scan=idx_in_scan)
01069 
01070         self.train(self.dataset.inputs, use_pca)
01071         #pdb.set_trace()
01072         for d in dset_trained_on:
01073             self.load_scan(self.scan_names[d])
01074             self.scan_idx = d
01075             self.classify_current_scan()
01076             self.draw(exp_name)
01077 
01078         k = cv.WaitKey(33)
01079 
01080         print '>>>> Training set peformance'
01081         _, train_conf = self.evaluate_learner(self.dataset.inputs, self.dataset.outputs)
01082         train_set_statistics = []
01083         train_set_statistics.append({'conf': train_conf, 
01084                                      'size': self.dataset.inputs.shape[1]})
01085 
01086         print '>>>> Performance on unseen scans'
01087         print 'Loading scans we\'ll be testing on'
01088         #all_scans_except_current = []
01089         indices_of_other_scans = inverse_indices(dset_trained_on, len(self.scan_names))
01090         print 'Trained on', dset_trained_on
01091         print 'Testing with', indices_of_other_scans
01092 
01093         self.dataset=None
01094         conf_unseen = []
01095         for i in indices_of_other_scans:
01096             self.load_scan(self.scan_names[i])
01097             self.scan_idx = i
01098             self.classify_current_scan()
01099             self.draw(exp_name)
01100             k = cv.WaitKey(33)
01101             sdset = self.select_features(self.current_scan['instances'], self.features_to_use, self.current_scan['sizes'])
01102             _, conf = self.evaluate_learner(sdset, self.current_scan['labels'])
01103             conf_unseen.append({'name': self.scan_names[i], 'conf': conf})
01104         perf_on_other_scans = []
01105         perf_on_other_scans.append(conf_unseen)
01106 
01107         #Save training results
01108         training_results_name = BASE_FILE_NAME + 'active_train_iter_results.pkl'
01109         ut.save_pickle({'train_set_statistics': train_set_statistics,
01110                         #'current_scan_statistics': current_scan_statistics,
01111                         'perf_on_other_scans': perf_on_other_scans}, training_results_name)
01112         print 'Saved training results to', training_results_name
01113 
01114 
01115     def generate_dataset_for_hyperparameter_grid_search(self, features_to_use):
01116         feature_sizes = self.current_scan['sizes']
01117 
01118         for sname in self.scan_names:
01119             print 'generate_dataset_for_hyperparameter_grid_search: loading %s' % sname
01120             self.load_scan(sname)
01121             rcurrent_scan = self.select_features(self.current_scan['instances'], features_to_use, feature_sizes)
01122             scan_ids = np.matrix([sname]*rcurrent_scan.shape[1])
01123             idx_in_scan = np.matrix(range(rcurrent_scan.shape[1]))
01124             if self.dataset == None:
01125                 self.dataset = InterestPointDataset(rcurrent_scan, self.current_scan['labels'], 
01126                                     self.current_scan['points2d'], self.current_scan['points3d'], 
01127                                     None, scan_ids=scan_ids, idx_in_scan=idx_in_scan, sizes=nsizes)
01128             else:
01129                 self.dataset.add(rcurrent_scan, self.current_scan['labels'], self.current_scan['points2d'],
01130                                  self.current_scan['points3d'], scan_id=scan_ids, idx_in_scan=idx_in_scan)
01131 
01132         self.train(self.dataset.inputs, True)
01133 
01134 
01135     def construct_learner(self, seed_set, prev_pca, g, c, ratio=None):
01136         features_used = ['intensity']
01137         learner = SVMPCA_ActiveLearner(use_pca=True, 
01138                         reconstruction_std_lim = self.rec_params.reconstruction_std_lim, 
01139                         reconstruction_err_toler = self.rec_params.reconstruction_err_toler,
01140                         old_learner=self.learner, pca=prev_pca)
01141         if ratio == None:
01142             nneg = np.sum(seed_set.outputs == NEGATIVE) #
01143             npos = np.sum(seed_set.outputs == POSITIVE)
01144             neg_to_pos_ratio = float(nneg)/float(npos)
01145         else:
01146             neg_to_pos_ratio = ratio
01147         weight_balance = ' -w0 1 -w1 %.2f' % neg_to_pos_ratio
01148         #pdb.set_trace()
01149         inputs_for_pca = self.select_features(self.current_scan['instances'], features_used, self.current_scan['sizes'])
01150         svm_params = '-s 0 -t 2 -g %.6f -c %.2f' % (g, c)
01151         learner.train(seed_set, 
01152                       #self.current_scan['instances'],
01153                       inputs_for_pca,
01154                       svm_params + weight_balance,
01155                       self.rec_params.variance_keep)
01156         return learner
01157 
01158     def evaluate_over_datasets(self, test_idx, learner, exp_name):
01159         for i in test_idx:
01160             self.learner = learner
01161             name = self.scan_names[i]
01162             self.load_scan(name)
01163             self.classify_current_scan()
01164             self.draw(exp_name)
01165 
01166     def active_learn_test3(self):
01167         #pdb.set_trace()
01168         #features_used = ['expected_loc', 'fpfh', 'intensity']
01169         features_used = ['intensity']
01170         exp_name = 'fixed_intensity_bug_filtered_pca50_window15'
01171         path = pt.split(insert_folder_name(self.scan_names[self.scan_idx], exp_name))[0]
01172         g = .5
01173         c = .5
01174         #pdb.set_trace()
01175         try:
01176             os.mkdir(path)
01177         except OSError, e:
01178             pass
01179 
01180         train_idx = range(16)
01181         test_idx  = range(20,24)
01182         #test_idx  = range(8,9)
01183 
01184         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
01185         print 'Training initial learning from seed dataset'
01186         #Load seed dataset from the first scan, train initial SVM
01187         print 'using', self.training_sname
01188         seed_set = ut.load_pickle(self.training_sname)
01189         metaintensity =  seed_set.metadata[1]
01190         sizes = {'intensity': metaintensity.extent[1] - metaintensity.extent[0]}
01191         seed_set.metadata = [metaintensity]
01192         metaintensity.extent = [0, sizes['intensity']]
01193 
01194         #self.load_scan(self.scan_names[0])
01195         #Train learner
01196         #pca_fname = 'pca_active_learn_test2.pkl'
01197         #if pt.isfile(pca_fname):
01198         #    prev_pca = ut.load_pickle(pca_fname)
01199         #else:
01200         #    prev_pca = None
01201 
01202         #learner = self.construct_learner(seed_set, prev_pca, g, c)
01203         #prev_pca = learner.pca
01204         #ut.save_pickle(prev_pca, pca_fname)
01205         test_inputs = []
01206         test_outputs = []
01207         print 'Loading test sets'
01208         for i in test_idx:
01209             name = self.scan_names[i]
01210             print 'loading', name
01211             eval_data_set = ut.load_pickle(name)
01212             test_inputs.append(self.select_features(eval_data_set['instances'], features_used, eval_data_set['sizes']))
01213             test_outputs.append(eval_data_set['labels'])
01214             #pdb.set_trace()
01215         test_inputs  = np.column_stack(test_inputs)
01216         test_outputs = np.column_stack(test_outputs)
01217 
01218         #Active learning train phase
01219         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
01220         print 'Learning phase'
01221         conf_mats = []
01222         #current_idx = 0
01223         #number_of_converged_scans = 0
01224         #iteration_number = 0
01225         for i in train_idx[0:5]:
01226             self.scan_idx = i
01227             self.load_scan(name)
01228             cur_instances = self.select_features(self.current_scan['instances'], 
01229                     features_used, self.current_scan['sizes'])
01230             seed_set = InterestPointDataset.add_to_dataset(seed_set, 
01231                             cur_instances[:, :],
01232                             self.current_scan['labels'][:, :],
01233                             self.current_scan['points2d'][:, :],
01234                             self.current_scan['points3d'][:, :],
01235                             i, None, #np.matrix(range(self.current_scan['instances'].shape[1])),
01236                             sizes=sizes)
01237             #learner = self.construct_learner(seed_set, prev_pca, g, c)
01238             #prev_pca = learner.pca
01239 
01240             #predictions = np.matrix(learner.classify(test_inputs))
01241             #conf_mat = confusion_matrix(test_outputs, predictions)
01242             #conf_mats.append(conf_mat)
01243             #pdb.set_trace()
01244             #ut.save_pickle(conf_mats, exp_name + '_confusion_mats.pkl')
01245             #ut.save_pickle(seed_set, exp_name + '_seed_set.pkl')
01246             #print '---------------------------------'
01247             ##print iteration_number
01248             #print 'scan idx', i
01249             #print 'results'
01250             #print conf_mat
01251             #print conf_mat[0,0] + conf_mat[1,1]
01252 
01253         #pdb.set_trace()
01254         learner = self.construct_learner(seed_set, None, g, c)
01255         #pdb.set_trace()
01256         cv.SaveImage('pca_filtered_%s.png' % exp_name,\
01257                      instances_to_image(\
01258                         self.rec_params.win_size,\
01259                         learner.pca.projection_basis,\
01260                             np.min(learner.pca.projection_basis),\
01261                             np.max(learner.pca.projection_basis)))
01262         prev_pca = learner.pca
01263         self.evaluate_over_datasets(test_idx, learner, exp_name)
01264 
01265         pdb.set_trace()
01266         print confusion_matrix(test_outputs, np.matrix(self.construct_learner(seed_set, prev_pca, g, c).classify(test_inputs)))
01267         # self.evaluate_learner(test_idx, self.construct_learner(seed_set, prev_pca, g, c), exp_name)
01268         #pdb.set_trace()
01269 
01270         #for gv in [.1,.5, 1,2,3,4,5,10,20,30,40,50,100,200]:
01271         #    learner = self.construct_learner(seed_set, prev_pca, gv, c)
01272         #    #learner.classify(test_set.inputs)
01273         #    #conf_mat = r3d.confusion_matrix(test_set.outputs, predictions)
01274         #    #evaluate performance
01275         #    predictions = np.matrix(learner.classify(test_inputs))
01276         #    conf_mat = confusion_matrix(test_outputs, predictions)
01277         #    conf_mats.append(conf_mat)
01278         #    print '---------------------------------'
01279         #    print 'results'
01280         #    print conf_mat
01281         #    print conf_mat[0,0] + conf_mat[1,1]
01282 
01283         ut.save_pickle(conf_mats, exp_name + '_confusion_mats.pkl')
01284 
01285 
01286 
01287     #This time we train the same way that the robot runs
01288     #train each scan until convergence
01289     #run until we have seen 4 scans that don't need training
01290     #evaluate using all unseen scans
01291     def active_learn_test2(self):
01292         #pdb.set_trace()
01293         #features_used = ['expected_loc', 'fpfh', 'intensity']
01294         features_used = ['intensity']
01295         exp_name = 'autolearn_g05_c05_max5_pca50_fast_feature_patch15_0'
01296         path = pt.split(insert_folder_name(self.scan_names[self.scan_idx], exp_name))[0]
01297         #pdb.set_trace()
01298         try:
01299             os.mkdir(path)
01300         except OSError, e:
01301             pass
01302 
01303         #train_idx = range(16)
01304         train_idx = np.random.permutation(range(16)).tolist()
01305         #test_idx  = range(16,17)
01306         test_idx  = range(18,24)
01307 
01308         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
01309         print 'Training initial learning from seed dataset'
01310         #Load seed dataset from the first scan, train initial SVM
01311         print 'using', self.training_sname
01312         seed_set = ut.load_pickle(self.training_sname)
01313         #pdb.set_trace()
01314         metaintensity =  seed_set.metadata[1]
01315         sizes = {'intensity': metaintensity.extent[1] - metaintensity.extent[0]}
01316         seed_set.metadata = [metaintensity]
01317         metaintensity.extent = [0, sizes['intensity']]
01318         #self.load_scan(self.scan_names[0])
01319 
01320         #Train learner
01321         pca_fname = 'pca_active_learn_test2.pkl'
01322         if pt.isfile(pca_fname):
01323             prev_pca = ut.load_pickle(pca_fname)
01324         else:
01325             prev_pca = None
01326         learner = SVMPCA_ActiveLearner(use_pca=True, 
01327                         reconstruction_std_lim = self.rec_params.reconstruction_std_lim, 
01328                         reconstruction_err_toler = self.rec_params.reconstruction_err_toler,
01329                         old_learner=self.learner, pca=prev_pca)
01330         nneg = np.sum(seed_set.outputs == NEGATIVE) #
01331         npos = np.sum(seed_set.outputs == POSITIVE)
01332         neg_to_pos_ratio = float(nneg)/float(npos)
01333         weight_balance = ' -w0 1 -w1 %.2f' % neg_to_pos_ratio
01334         inputs_for_pca = self.select_features(self.current_scan['instances'], 
01335                 features_used, self.current_scan['sizes'])
01336         learner.train(seed_set, 
01337                       inputs_for_pca,
01338                       self.rec_params.svm_params + weight_balance,
01339                       self.rec_params.variance_keep)
01340         prev_pca = learner.pca
01341         ut.save_pickle(prev_pca, pca_fname)
01342 
01343         test_inputs = []
01344         test_outputs = []
01345         print 'Loading test sets'
01346         for i in test_idx:
01347             name = self.scan_names[i]
01348             print 'loading', name
01349             eval_data_set = ut.load_pickle(name)
01350             test_inputs.append(self.select_features(eval_data_set['instances'], 
01351                 features_used, eval_data_set['sizes']))
01352             test_outputs.append(eval_data_set['labels'])
01353             #pdb.set_trace()
01354         test_inputs  = np.column_stack(test_inputs)
01355         test_outputs = np.column_stack(test_outputs)
01356 
01357         #Active learning train phase
01358         print '>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>'
01359         print 'Learning phase'
01360         conf_mats = []
01361         current_idx = 0
01362         number_of_converged_scans = 0
01363         iteration_number = 0
01364 
01365         for i in train_idx:
01366             #break
01367             name = self.scan_names[i]
01368             current_idx = i
01369 
01370             print '!!!!!!!!!!!!!!!!!!!!!!!!!!!'
01371             print 'loading scan %s' % name
01372             self.scan_idx = current_idx
01373             self.load_scan(name)
01374             self.draw(exp_name)
01375             cur_instances = self.select_features(self.current_scan['instances'], 
01376                     features_used, self.current_scan['sizes'])
01377             converged = False
01378 
01379             indices_added = []
01380             while True:
01381                 if len(indices_added) > 5:
01382                     #pdb.set_trace()
01383                     break
01384 
01385                 iteration_number += 1
01386                 remaining_pt_indices = inverse_indices(indices_added, cur_instances.shape[1])
01387                 remaining_instances = cur_instances[:, remaining_pt_indices]
01388                 ridx, selected_dist, converged = learner.select_next_instances_no_terminate(remaining_instances)
01389                 if converged:
01390                     print 'Converged on scan.'
01391                     break
01392 
01393                 #add to dataset 
01394                 selected_idx = remaining_pt_indices[ridx[0]]
01395                 indices_added.append(selected_idx)
01396                 seed_set = InterestPointDataset.add_to_dataset(seed_set, 
01397                         cur_instances[:, selected_idx],
01398                         self.current_scan['labels'][:, selected_idx],
01399                         self.current_scan['points2d'][:, selected_idx],
01400                         self.current_scan['points3d'][:, selected_idx],
01401                         current_idx, selected_idx,
01402                         sizes=sizes)
01403 
01404                 #retrain 
01405                 learner = SVMPCA_ActiveLearner(use_pca=True, 
01406                                 reconstruction_std_lim=self.rec_params.reconstruction_std_lim, 
01407                                 reconstruction_err_toler=self.rec_params.reconstruction_err_toler,
01408                                 old_learner=self.learner, pca=prev_pca)
01409                 nneg = np.sum(seed_set.outputs == NEGATIVE) #
01410                 npos = np.sum(seed_set.outputs == POSITIVE)
01411                 neg_to_pos_ratio = float(nneg)/float(npos)
01412                 weight_balance = ' -w0 1 -w1 %.2f' % neg_to_pos_ratio
01413                 inputs_for_pca = self.select_features(self.current_scan['instances'], features_used, self.current_scan['sizes'])
01414                 learner.train(seed_set, 
01415                               inputs_for_pca,
01416                               self.rec_params.svm_params + weight_balance,
01417                               self.rec_params.variance_keep)
01418                 prev_pca = learner.pca
01419                 ut.save_pickle(prev_pca, pca_fname)
01420 
01421                 #evaluate performance
01422                 predictions = np.matrix(learner.classify(test_inputs))
01423                 conf_mat = confusion_matrix(test_outputs, predictions)
01424                 conf_mats.append(conf_mat)
01425                 ut.save_pickle(conf_mats, exp_name + '_confusion_mats.pkl')
01426                 ut.save_pickle(seed_set, exp_name + '_seed_set.pkl')
01427                 print '---------------------------------'
01428                 print iteration_number
01429                 print 'scan idx', i
01430                 print 'results'
01431                 print conf_mat
01432                 print conf_mat[0,0] + conf_mat[1,1]
01433 
01434                 self.learner = learner
01435                 self.classify_current_scan()
01436                 self.draw(exp_name)
01437 
01438             if len(indices_added) == 0:
01439                 #pdb.set_trace()
01440                 print 'OUTER LOOP CONVERGED', number_of_converged_scans
01441                 number_of_converged_scans += 1
01442 
01443         for i in test_idx:
01444             self.learner = learner
01445             name = self.scan_names[i]
01446             self.load_scan(name)
01447             self.classify_current_scan()
01448             self.draw(exp_name)
01449 
01450         #evaluate performance
01451         predictions = np.matrix(learner.classify(test_inputs))
01452         conf_mat = confusion_matrix(test_outputs, predictions)
01453         conf_mats.append(conf_mat)
01454         ut.save_pickle(conf_mats, exp_name + '_confusion_mats.pkl')
01455         print '---------------------------------'
01456         print 'results'
01457         print conf_mat
01458         print conf_mat[0,0] + conf_mat[1,1]
01459 
01460         self.learner = learner
01461         self.dataset = seed_set
01462         print 'DO NOT SAVE'
01463         print 'DO NOT SAVE'
01464         print 'DO NOT SAVE'
01465         print 'DO NOT SAVE'
01466         print 'DO NOT SAVE'
01467         print 'DO NOT SAVE'
01468         print 'DO NOT SAVE'
01469         #self.current_scan['sizes'] = sizes
01470         self.run_gui()
01471         pdb.set_trace()
01472 
01473 
01474     def active_learn_test(self, features_to_use, exp_name, use_pca=None, run_till_end=False):
01475         BASE_FILE_NAME = pt.splitext(insert_folder_name(self.scan_names[self.scan_idx], exp_name))[0] #pt.splitext(self.scan_names[self.scan_idx])[0]
01476         try:
01477             os.mkdir(pt.split(BASE_FILE_NAME)[0])
01478         except OSError, e:
01479             if e.errno != 17:
01480                 pdb.set_trace()
01481                 raise e
01482 
01483         # Run learner until convergence on initial scan
01484         if use_pca == None:
01485             if set(features_to_use).issuperset(['intensity']):
01486                 use_pca = True
01487             else:
01488                 use_pca = False
01489 
01490         if not pt.isfile(self.training_sname):
01491             print 'active_learn_test: Training file', self.training_sname, 'not found! exiting.'
01492             return
01493 
01494         feature_sizes = self.current_scan['sizes']
01495         print 'active_learn_test: Using features', features_to_use
01496         print 'active_learn_test: feature sizes'
01497         for k in ['expected_loc', 'distance', 'fpfh', 'intensity']:
01498             if feature_sizes.has_key(k):
01499                 print k, feature_sizes[k]
01500 
01501         total_dim = 0
01502         for f in features_to_use:
01503             total_dim += feature_sizes[f]
01504 
01505         print 'active_learn_test: total feature size should be', total_dim
01506 
01507         #Select only the features we will use
01508         rcurrent_scan = self.select_features(self.current_scan['instances'], features_to_use, feature_sizes)
01509 
01510         #Load the seed dataset to initialize active learner with
01511         self.dataset = ut.load_pickle(self.training_sname)
01512         print 'active_learn_test: loaded seed training file', self.training_sname
01513         self.dataset.select_features(features_to_use)
01514 
01515         self.train(rcurrent_scan, use_pca)
01516         self.classify_current_scan()
01517         self.draw(exp_name)
01518         k = cv.WaitKey(33)
01519 
01520         #Load all the scans we'll be testing on
01521         print 'Loading scans we\'ll be testing on'
01522         print 'TRAINING ON SCAN NAMED', self.scan_names[self.scan_idx]
01523         all_scans_except_current = []
01524         indices_of_other_scans = inverse_indices(self.scan_idx, len(self.scan_names))
01525         for i in indices_of_other_scans:
01526             sn = self.scan_names[i]
01527             print '>>', sn
01528             scan_dict = ut.load_pickle(sn)
01529             reduced_sd = {}
01530             reduced_sd['instances'] = self.select_features(scan_dict['instances'], features_to_use, feature_sizes)
01531             reduced_sd['labels'] = scan_dict['labels']
01532             reduced_sd['name'] = sn
01533             all_scans_except_current.append(reduced_sd)
01534 
01535         i = 0
01536         converged = False
01537         train_set_statistics = []
01538         current_scan_statistics  = []
01539         perf_on_other_scans = []
01540         converged_at_iter = None
01541         should_run = True
01542 
01543         #Run active learner until convergence
01544         while should_run:
01545             if self.learner.pca.projection_basis != None:
01546                 cv.SaveImage(BASE_FILE_NAME + ('_iter_%d_basis.png' % i),\
01547                              instances_to_image(\
01548                                 self.rec_params.win_size,\
01549                                 self.learner.pca.projection_basis,\
01550                                 np.min(self.learner.pca.projection_basis),\
01551                                 np.max(self.learner.pca.projection_basis)))
01552                 cv.SaveImage(BASE_FILE_NAME + ('_intensity_set_%d.png' % i),\
01553                              instances_to_image(self.rec_params.win_size, self.dataset.features_named(['intensity']),\
01554                                                 0., 1.))
01555 
01556             self.classify_current_scan()
01557             self.draw(exp_name)
01558             k = cv.WaitKey(33)
01559 
01560             print '>>>> Train set peformance'
01561             _, train_conf = self.evaluate_learner(self.dataset.inputs, self.dataset.outputs)
01562             train_set_statistics.append({'conf': train_conf, 
01563                                          'size': self.dataset.inputs.shape[1]})
01564 
01565             print '>>>> Performance on current scan (correlated test set)'
01566             remaining_pt_indices = inverse_indices(self.dataset.idx_in_scan, rcurrent_scan.shape[1])
01567             remaining_instances = rcurrent_scan[:, remaining_pt_indices]
01568             remaining_outputs = self.current_scan['labels'][:, remaining_pt_indices]
01569             #remaining_outputs = rcurrent_scan[:, remaining_pt_indices]
01570             #pdb.set_trace()
01571             _, rem_conf  = self.evaluate_learner(remaining_instances, remaining_outputs)
01572             current_scan_statistics.append({'conf': rem_conf})
01573 
01574             print '>>>> Performance on unseen scans (test set)'
01575             conf_unseen = []
01576             for scan in all_scans_except_current:
01577                 _, conf = self.evaluate_learner(scan['instances'], scan['labels'], verbose=False)
01578                 conf_unseen.append({'name': scan['name'], 'conf': conf})
01579             perf_on_other_scans.append(conf_unseen)
01580 
01581             #Only select points that have *not* been added
01582             #if active_train:
01583             remaining_pt_indices = inverse_indices(self.dataset.idx_in_scan, rcurrent_scan.shape[1])
01584             if len(remaining_pt_indices) > 0:
01585                 ridx, selected_dist, converged = self.learner.select_next_instances_no_terminate(rcurrent_scan[:, remaining_pt_indices])
01586                 if not converged or run_till_end:
01587                     selected_idx = remaining_pt_indices[ridx]
01588                     self.add_to_training_set(selected_idx)
01589                     self.train(rcurrent_scan, use_pca)
01590                     i = i + 1
01591                 else:
01592                     should_run = False
01593 
01594                 if converged and converged_at_iter == None:
01595                     converged_at_iter = i
01596 
01597                 if i > 100 and converged:
01598                     should_run = False
01599 
01600             else:
01601                 should_run = False
01602 
01603         print '======================='
01604         print '>> LEARNER CONVERGED <<'
01605         print '======================='
01606         print 'saving dataset to', self.training_sname
01607         ut.save_pickle(self.dataset, BASE_FILE_NAME + '_converged_dset.pkl')
01608         print 'saved!'
01609 
01610         #Save training results
01611         training_results_name = BASE_FILE_NAME + 'active_train_iter_results.pkl'
01612         ut.save_pickle({'train_set_statistics': train_set_statistics,
01613                         'current_scan_statistics': current_scan_statistics,
01614                         'perf_on_other_scans': perf_on_other_scans,
01615                         'converged_at_iter': converged_at_iter}, training_results_name)
01616         print 'Saved training results to', training_results_name
01617 
01618     def run_gui(self):
01619         # Make a test set
01620         while not rospy.is_shutdown():
01621             self.step()
01622 
01623     def mouse_cb(self, event, x, y, flags, param):
01624         if not (event == cv.CV_EVENT_LBUTTONDOWN or \
01625                 event == cv.CV_EVENT_RBUTTONDOWN or \
01626                 event == cv.CV_EVENT_MBUTTONDOWN):
01627             return
01628         # Grab closest thing, change its label, and redraw
01629         ck = [self.cdisp['tree'].query(np.array([x,y]) / self.scale, k=1)[1]]
01630         cr = self.cdisp['tree'].query_ball_point(np.array([x,y]) / self.scale, 5.)
01631         
01632         print 'k nearest', len(ck), 'radius', len(cr)
01633 
01634         if len(ck) > len(cr):
01635             closest_idx = ck
01636         else:
01637             closest_idx = cr
01638 
01639         if self.mode == 'GROUND_TRUTH':
01640             if event == cv.CV_EVENT_LBUTTONDOWN:
01641                 label = POSITIVE
01642             elif event == cv.CV_EVENT_RBUTTONDOWN:
01643                 label = NEGATIVE
01644             elif event == cv.CV_EVENT_MBUTTONDOWN:
01645                 label = UNLABELED
01646             else:
01647                 return
01648 
01649             print 'Current mode is', self.mode
01650             #print 'old labels', self.current_scan['labels'][0, closest_idx]
01651             self.current_scan['labels'][0, closest_idx] = label
01652             #print 'new labels', self.current_scan['labels'][0, closest_idx]
01653 
01654         
01655         if self.mode == 'TRAINING_SET':
01656             # Try to add selected point
01657             if event == cv.CV_EVENT_LBUTTONDOWN:
01658                 self.add_to_training_set(closest_idx)
01659 
01660             # Try to remove the selected point
01661             elif event == cv.CV_EVENT_RBUTTONDOWN:
01662                 self.remove_from_training_set(closest_idx)
01663         self.draw()
01664 
01665     def add_to_training_set(self, indices):
01666         # Don't add examples that have not been labeled (remove examples with the label UNLABELED)
01667         labeled_idx = []
01668         for idx in indices:
01669             #print 'add_to_training_set:', self.current_scan['labels'][0, idx].__class__
01670             #if np.array([self.current_scan['labels'][0, idx]]).shape[0] > 1:
01671             #    pdb.set_trace()
01672             #if len(np.array([self.current_scan['labels'][0, idx]]).shape) > 1:
01673             #    pdb.set_trace()
01674 
01675             if self.current_scan['labels'][0, idx] != UNLABELED:
01676                 labeled_idx.append(idx)
01677         
01678         # Don't add examples that have been added (keep index of examples added from this scan).
01679         # Search the list of labeled examples.
01680         filtered_idx = []
01681         if self.dataset != None:
01682             for idx in labeled_idx:
01683                 #pdb.set_trace()
01684                 if self.dataset.idx_in_scan == None:
01685                     matched_idx = []
01686                 else:
01687                     matched_idx = np.where(self.dataset.idx_in_scan == idx)[1].A1
01688                 if len(matched_idx) > 0:
01689                     if np.any(self.scan_names[self.scan_idx] == self.dataset.scan_ids[:, matched_idx]):
01690                         continue
01691                 filtered_idx.append(idx)
01692         else:
01693             filtered_idx += labeled_idx
01694        
01695         if len(filtered_idx) < 1:
01696             print 'add_to_training_set: returned point #', labeled_idx, 'as it is already in the dataset'
01697             return
01698             #pdb.set_trace()
01699         filtered_idx = [filtered_idx[0]]
01700         pinfo = [self.current_scan[k][:, filtered_idx] for k in \
01701                         ['instances', 'labels', 'points2d', 'points3d']]
01702         pinfo.append(np.matrix([self.scan_names[self.scan_idx]] * len(filtered_idx)))
01703         pinfo.append(np.matrix(filtered_idx))
01704 
01705         if self.dataset == None:
01706             #pdb.set_trace()
01707             print 'WARNING: THIS BRANCH SHOULD BE REACHED DURING AUTONOMOUS RUN. add_to_training_set'
01708             #pdb.set_trace()
01709             self.dataset = InterestPointDataset(self.select_features(pinfo[0], self.features_to_use, self.current_scan['sizes']),
01710                                                 pinfo[1], pinfo[2], pinfo[3], None, pinfo[4], pinfo[5], 
01711                                                 sizes=self.current_scan['sizes'])
01712         else:
01713             self.dataset.add(self.select_features(pinfo[0], self.features_to_use, self.current_scan['sizes']), pinfo[1], \
01714                                                   pinfo[2], pinfo[3], pinfo[4], pinfo[5])
01715 
01716         print '>> Number of examples in dataset:', self.dataset.inputs.shape[1]
01717 
01718     def remove_from_training_set(self, indices):
01719         if self.dataset != None:
01720             for idx in indices:
01721                 matched_idx = np.where(self.dataset.idx_in_scan == idx)[1].A1
01722                 if len(matched_idx) > 0:
01723                     sm = np.where(self.scan_names[self.scan_idx] == self.dataset.scan_ids[:, matched_idx])[1]
01724                     if len(sm) > 0:
01725                         to_remove = matched_idx[sm]
01726                         print 'removing', len(sm), 'points'
01727                         for ridx in to_remove:
01728                             self.dataset.remove(ridx)
01729 
01730     def has_enough_data(self):
01731         pos_ex = np.sum(self.dataset.outputs)
01732         neg_ex = self.dataset.outputs.shape[1] - pos_ex
01733         if pos_ex > 0 and neg_ex > 0:
01734             return True
01735 
01736     def train(self, inputs_for_scaling):
01737         if self.dataset != None and self.has_enough_data():
01738             use_pca=False
01739             for f in self.features_to_use:
01740                 if f == 'intensity':
01741                     use_pca=True
01742             nneg = np.sum(self.dataset.outputs == NEGATIVE)
01743             npos = np.sum(self.dataset.outputs == POSITIVE)
01744             print '================= Training ================='
01745             print 'NEG examples', nneg
01746             print 'POS examples', npos
01747             print 'TOTAL', self.dataset.outputs.shape[1]
01748             neg_to_pos_ratio = float(nneg)/float(npos)
01749             #weight_balance = ' -w0 1 -w1 %.2f' % neg_to_pos_ratio
01750             #weight_balance = ' -w0 1 -w1 %.2f' % 2.
01751             #weight_balance = ""
01752             #weight_balance = ' -w0 1 -w1 5.0'
01753             weight_balance = ' -w0 1 -w1 %.2f' % (neg_to_pos_ratio)
01754             #weight_balance = ""
01755 
01756             self.learner = SVMPCA_ActiveLearner(use_pca, 
01757                     self.rec_params.reconstruction_std_lim, 
01758                     self.rec_params.reconstruction_err_toler,
01759                     old_learner=self.learner)
01760 
01761             self.learner.train(self.dataset, 
01762                                inputs_for_scaling,
01763                                self.rec_params.svm_params + weight_balance,
01764                                self.rec_params.variance_keep)
01765 
01766             #correct = np.sum(self.dataset.outputs == np.matrix(self.learner.classify(self.dataset.inputs)))
01767             #pdb.set_trace()
01768             #print 'Test set: %.2f' % (100.* (float(correct)/float(self.dataset.outputs.shape[1]))), '% correct'
01769             #self.evaluate_learner(self.dataset.inputs, self.dataset.outputs)
01770 
01771             if use_pca:
01772                 BASE_FILE_NAME = 'pca_fast'
01773                 i = 111
01774                 cv.SaveImage(BASE_FILE_NAME + ('_iter_%d_basis.png' % i),\
01775                              instances_to_image(\
01776                                 self.rec_params.win_size,\
01777                                 self.learner.pca.projection_basis,\
01778                                 np.min(self.learner.pca.projection_basis),\
01779                                 np.max(self.learner.pca.projection_basis)))
01780 
01781 
01782             print '=================  DONE  =================' 
01783 
01784     def evaluate_learner(self, instances, true_labels, verbose=True):
01785         predicted = np.matrix(self.learner.classify(instances))
01786 
01787         posidx = np.where(true_labels == POSITIVE)[1].A1
01788         negidx = np.where(true_labels == NEGATIVE)[1].A1
01789         m00 = m01 = m10 = m11 = 0
01790         nm00 = nm01 = nm10 = nm11 = 0
01791         if len(negidx) > 0:
01792             nm00 = float(np.sum(NEGATIVE == predicted[:, negidx]))
01793             nm01 = float(np.sum(POSITIVE == predicted[:, negidx]))
01794             m00 =  nm00 / len(negidx)
01795             m01 =  nm01 / len(negidx)
01796 
01797         if len(posidx) > 0:
01798             nm10 = float(np.sum(NEGATIVE == predicted[:, posidx]))
01799             nm11 = float(np.sum(POSITIVE == predicted[:, posidx]))
01800             m10 =  nm10 / len(posidx)
01801             m11 =  nm11 / len(posidx)
01802 
01803         conf_mat = np.matrix([[m00, m01], [m10, m11]], 'float')
01804         if verbose:
01805             print 'Confusion matrix:'
01806             print '-   %5.2f, %5.2f' % (100.* m00, 100.* m01)
01807             print '+  %5.2f, %5.2f' % (100.* m10, 100.* m11)
01808             print '   Total %5.2f' % (100.* (float(np.sum(true_labels == predicted)) / true_labels.shape[1]))
01809 
01810         return predicted, {'mat': np.matrix([[nm00, nm01], [nm10, nm11]], 'float'), 
01811                            'neg': len(negidx), 
01812                            'pos': len(posidx)}
01813         #print 'POS correct %.2f' % 100. * float(pcor) / len(posidx)
01814         #print 'NEG correct %.2f' % 100. * float(ncor) / len(negidx)
01815 
01816     def add_to_dataset(self, pinfo):
01817         if self.dataset == None:
01818             self.dataset = InterestPointDataset(pinfo[0], pinfo[1], pinfo[2], \
01819                     pinfo[3], None, pinfo[4], pinfo[5], sizes=self.current_scan['sizes'])
01820         else:
01821             self.dataset.add(pinfo[0], pinfo[1], \
01822                     pinfo[2], pinfo[3], pinfo[4], pinfo[5])
01823 
01824 class FiducialPicker:
01825 
01826     def __init__(self, fname):
01827         #load pickle and display image
01828         self.fname = fname
01829         self.data_pkl = ut.load_pickle(fname)
01830         image_fname = pt.join(pt.split(fname)[0], self.data_pkl['image'])
01831         self.img = cv.LoadImageM(image_fname)
01832         self.clicked_points = None
01833         self.clicked_points3d = None
01834 
01835         #make a map in image coordinates
01836         #bl_pc = ru.pointcloud_to_np(self.data_pkl['points3d'])
01837         bl_pc = self.data_pkl['points3d']
01838         self.image_T_laser = self.data_pkl['k_T_bl']
01839         self.image_arr = np.asarray(self.img)
01840         self.calibration_obj = self.data_pkl['cal']
01841         self.points_valid_image, self.colors_valid, self.points2d_valid = \
01842                 i3d.combine_scan_and_image_laser_frame(bl_pc, self.image_T_laser,\
01843                                             self.image_arr, self.calibration_obj)
01844 
01845         laser_T_image = np.linalg.inv(self.image_T_laser)
01846         self.points_valid_laser = tfu.transform_points(laser_T_image, self.points_valid_image[0:3,:])
01847         self.ptree = sp.KDTree(np.array(self.points2d_valid.T))
01848 
01849         cv.NamedWindow('image', cv.CV_WINDOW_AUTOSIZE)
01850         cv.ShowImage('image', self.img)
01851         cv.SetMouseCallback('image', self.mouse_cb, None)
01852         self.exit = False
01853         
01854 
01855     def mouse_cb(self, event, x, y, flags, param):
01856         if event != cv.CV_EVENT_LBUTTONDOWN:
01857             return
01858 
01859         pt = np.array([x,float(y)]).T
01860         idx = self.ptree.query(pt.T, k=1)[1]
01861         #pdb.set_trace()
01862         if self.clicked_points != None:
01863             self.clicked_points = np.column_stack((self.clicked_points, self.points2d_valid[:, idx]))
01864             self.clicked_points3d = np.column_stack((self.clicked_points3d, self.points_valid_laser[:,idx]))
01865         else:
01866             self.clicked_points = self.points2d_valid[:, idx]
01867             self.clicked_points3d = self.points_valid_laser[:,idx]
01868 
01869         #self.clicked_points
01870 
01871         #    label = POSITIVE
01872         #elif event == cv.CV_EVENT_RBUTTONDOWN:
01873         #    label = NEGATIVE
01874         #else:
01875         #    return
01876 
01877     def step(self):
01878         k = cv.WaitKey(33)
01879         if k == ord('s'):
01880             if self.clicked_points.shape[1] > 3:
01881                 fname = pt.splitext(self.fname)[0] + '_synthetic_locs3d.pkl'
01882                 print 'saving data to file:', fname
01883                 #self.data_pkl['synthetic_locs3d'] = self.clicked_points3d
01884                 #ut.save_pickle(self.data_pkl, self.fname)
01885                 ut.save_pickle(self.clicked_points3d, fname)
01886             else:
01887                 print 'ignored save command, need more points. only has', self.clicked_points3d.shape[1]
01888 
01889         if k == ord('x'):
01890             self.exit = True
01891 
01892         ibuffer = cv.CloneMat(self.img)
01893         draw_points(ibuffer, self.points2d_valid, [0,255,0], 1)
01894         #if self.clicked_points.shape[1] > 0:
01895         if self.clicked_points != None:
01896             draw_points(ibuffer, self.clicked_points, [0,0,255], 3)
01897         cv.ShowImage('image', ibuffer)
01898 
01899     def run(self):
01900         while not rospy.is_shutdown():
01901             self.step()
01902             if self.exit:
01903                 return
01904 
01905 class NarrowTextureFeatureExtractor:
01906     def __init__(self, prosilica, narrow_texture, prosilica_cal, projector, tf_listener, rec_params=None):
01907         self.cal = prosilica_cal
01908         self.prosilica = prosilica
01909         self.narrow_texture = narrow_texture
01910         self.tf_listener = tf_listener
01911         self.projector = projector
01912 
01913         if rec_params == None:
01914             rec_params = Recognize3DParam()
01915         self.rec_params = rec_params
01916 
01917     def read(self, expected_loc_bl, params=None):
01918         #self.laser_scan.scan(math.radians(180.), math.radians(-180.), 2.315)
01919         rospy.loginfo('grabbing point cloud')
01920         pointcloud_msg = self.narrow_texture.read()
01921         rospy.loginfo('grabbing prosilica frame')
01922         self.projector.set(False)
01923         for i in range(3):
01924             cvimage_mat = self.prosilica.get_frame()
01925         self.projector.set(True)
01926         rospy.loginfo('processing')
01927         pointcloud_ns = ru.pointcloud_to_np(pointcloud_msg)
01928         pointcloud_bl = tfu.transform_points(tfu.transform('base_link',\
01929                                                             'narrow_stereo_optical_frame', self.tf_listener),\
01930                                             pointcloud_ns)
01931 
01932         image_T_bl = tfu.transform('high_def_optical_frame', 'base_link', self.tf_listener)
01933 
01934         if params == None:
01935             params = self.rec_params
01936 
01937         #laser_T_bl = tfu.transform('/laser_tilt_link', '/base_link', self.tf_listener)
01938         #extractor = IntensityCloudData(pointcloud_bl, cvimage_mat, image_T_bl, self.cal, 
01939         #                     expected_loc_bl, expected_loc_bl, None, params)
01940         extractor = infea.IntensityCloudFeatureExtractor(pointcloud_bl, cvimage_mat, expected_loc_bl, 
01941                                                     None, image_T_bl, self.cal, params)
01942         xs, locs2d, locs3d = extractor.extract_features()
01943 
01944         rdict = {#'histogram': extractor.fpfh_hist,
01945                  #'hpoints3d': extractor.fpfh_points,
01946                  'points3d': pointcloud_bl,
01947                  'image': cvimage_mat}
01948 
01949         return {'instances': xs, 
01950                 'points2d': locs2d, 
01951                 'points3d': locs3d, 
01952                 'image': cvimage_mat, #rdict['image'], 
01953                 'rdict': rdict,
01954                 'sizes': extractor.sizes}
01955 
01956 
01957 if __name__ == '__main__':
01958     import sys
01959     import optparse
01960     p = optparse.OptionParser()
01961     p.add_option('-m', '--mode', action='store',
01962                 dest='mode', default='label', 
01963                 help='fiducialpicker, preprocess, or label')
01964     p.add_option("-f", "--feature", action="append", type="string")
01965     p.add_option("-t", "--test", action="store_true")
01966     p.add_option("-r", "--train", action="append", type="string")
01967     p.add_option("-n", "--expname", action="store", default="")
01968     p.add_option("-p", "--pca", action="store_true", default=None)
01969     p.add_option("-s", "--seed", action="store", default=None, help='not strictly neccessary if you use pickles ending with _seed.pkl')
01970     p.add_option("-e", "--end", action="store_true", default=False)
01971     p.add_option("-l", "--locations", action="store", default=None)
01972     p.add_option("-a", "--autolabel", action="store_true", default=None)
01973     #p.add_option("-k", "--kinect", action="store_true", default=True)
01974     opt, args = p.parse_args()
01975     mode = opt.mode
01976 
01977     print '======================================='
01978     print 'mode:', mode
01979     print '======================================='
01980     print args
01981 
01982     if mode == 'fiducialpicker':
01983         fp = FiducialPicker(args[0])
01984         fp.run()
01985 
01986     #if mode == 'standalone':
01987     #    object_name = args[0]
01988     #    raw_data_fname = args[1]
01989     #    if len(sys.argv) > 3:
01990     #        labeled_data_fname = args[2]
01991     #    else:
01992     #        labeled_data_fname = None
01993 
01994     #    cvgui = CVGUI4(raw_data_fname, object_name, labeled_data_fname)
01995     #    cvgui.run()
01996 
01997     if mode == 'preprocess':
01998         rospy.init_node('detect_fpfh', anonymous=True)
01999         preprocess_data_in_dir(args[0], ext='_features_df2_dict.pkl')
02000 
02001     if mode == 'locations':
02002         if opt.locations != None:
02003             locations = ut.load_pickle(opt.locations)
02004             keys = locations['data'].keys()
02005             for i, key in enumerate(keys):
02006                 print i, key
02007             picked_i = int(raw_input('pick a key to use'))
02008             seed_dset = keys[i]
02009             fname = raw_input('pick a file name')
02010             dset = locations['data'][seed_dset]['dataset']
02011             dset.idx_in_scan = np.matrix(dset.inputs.shape[1] * [0])
02012             dset.scan_ids = np.matrix(dset.inputs.shape[1] * [''])
02013             #dset.pt2d = None
02014             ut.save_pickle(dset, fname)
02015             pdb.set_trace()
02016             print 'saved %s' % fname
02017 
02018 
02019     if mode == 'hyper':
02020         s = ScanLabeler(args[0], ext='_features_df2_dict.pkl', scan_to_train_on=opt.train, 
02021                 seed_dset=opt.seed, features_to_use=opt.feature)
02022         s.generate_dataset_for_hyperparameter_grid_search(opt.feature)
02023 
02024 
02025     if mode == 'label':
02026         s = ScanLabeler(args[0], ext='_features_df2_dict.pkl', scan_to_train_on=opt.train, 
02027                 seed_dset=opt.seed, features_to_use=opt.feature)
02028         #s.automatic_label()
02029         #pdb.set_trace()
02030         if opt.autolabel:
02031             s.automatic_label()
02032         elif opt.test:
02033             print 'Running automated tests'
02034             print 'Using features', opt.feature
02035             s.active_learn_test2()
02036             #if len(opt.feature) == 1 and opt.feature[0] == 'distance':
02037             #    s.active_learn_test(['distance'], opt.expname, opt.pca, run_till_end=opt.end)
02038             #else:
02039             #    s.active_learn_test(opt.feature, opt.expname, opt.pca, run_till_end=opt.end)
02040         else:
02041             print 'launching gui.'
02042             s.run_gui()
02043 
02044     if mode == 'feature':
02045         s = ScanLabeler(args[0], ext='_features_df2_dict.pkl', scan_to_train_on=opt.train[0], 
02046                 seed_dset=opt.seed, features_to_use=opt.feature)
02047         if len(opt.feature) == 1 and opt.feature[0] == 'distance':
02048             s.test_feature_perf(opt.train, ['distance'], opt.expname, opt.pca)
02049         else:
02050             s.test_feature_perf(opt.train, opt.feature, opt.expname, opt.pca)
02051 
02052     if mode == 'call_fpfh':
02053         rospy.init_node('detect_fpfh', anonymous=True)
02054         fpfh = rospy.ServiceProxy('fpfh', fsrv.FPFHCalc)
02055 
02056         print 'loading'
02057         extractor, _ = load_data_from_file(args[0], Recognize3DParam())
02058         #data_pkl = ut.load_pickle(sys.argv[1])
02059         req = fsrv.FPFHCalcRequest()
02060         print 'npoints', extractor.points3d_valid_laser.shape[1]
02061         req.input = ru.np_to_pointcloud(extractor.points3d_valid_laser, 'base_link')
02062         #data_pkl['points_laser']
02063         print 'requesting'
02064         res = fpfh(req)
02065         print 'response received'
02066         #res.hist.histograms
02067         #res.hist.npoints
02068         #pdb.set_trace()
02069         histogram = np.matrix(res.hist.histograms).reshape((res.hist.npoints,33)).T
02070         points3d = np.matrix(res.hist.points3d).reshape((res.hist.npoints,3)).T
02071         print 'done'
02072         print 'done'
02073         print 'done'
02074         print 'done'
02075         print 'done'
02076 
02077     if mode == 'kinect':
02078         #import roslib; roslib.load_manifest('hai_sandbox')
02079         #import rospy
02080         #from sensor_msgs.msg import Image
02081         rospy.init_node('kinect_features')
02082         kfe = KinectFeatureExtractor()
02083         fname = opt.train[0]
02084 
02085         dataset = ut.load_pickle(fname)
02086         nneg = np.sum(dataset.outputs == NEGATIVE)
02087         npos = np.sum(dataset.outputs == POSITIVE)
02088         print '================= Training ================='
02089         print 'NEG examples', nneg
02090         print 'POS examples', npos
02091         print 'TOTAL', dataset.outputs.shape[1]
02092         neg_to_pos_ratio = float(nneg)/float(npos)
02093         weight_balance = ' -w0 1 -w1 %.2f' % neg_to_pos_ratio
02094         learner = SVMPCA_ActiveLearner(use_pca=True)
02095         trained = False
02096         ip = ImagePublisher('active_learn')
02097 
02098         while not rospy.is_shutdown():
02099             #calculate features
02100             xs, locs2d, locs3d, rdict['image'], rdict = kfe.read()
02101             if not trained:
02102                 learner.train(dataset, xs, kfe.rec_params.svm_params + weight_balance,
02103                               kfe.rec_params.variance_keep)
02104                 trained = True
02105             
02106             #predict
02107             results = np.matrix(learner.classify(sdset))
02108             current_scan_pred = InterestPointDataset(xs, results, locs2d, locs3d, None)
02109 
02110             #Draw
02111             img = cv.CloneMat(cdisp['cv'])
02112             draw_labeled_points(img, current_scan_pred, scale=1./self.scale)
02113             ip.publish(img)
02114 
02115         rospy.spin()
02116 


hai_sandbox
Author(s): Hai Nguyen
autogenerated on Wed Nov 27 2013 11:46:56