Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 from classifier import classifier
00031
00032 import util as ut
00033 import numpy as np
00034
00035 import processor
00036
00037
00038
00039
00040
00041
00042
00043 class baseline_classifier(classifier):
00044 '''
00045 classdocs
00046 '''
00047
00048
00049
00050
00051
00052
00053
00054
00055 def test(self, feature_data = None):
00056
00057 print ut.getTime(), 'test on:', self.processor.scan_dataset.id
00058
00059 if feature_data == None:
00060 filename = self.processor.get_features_filename()
00061 dict = ut.load_pickle(filename)
00062 else:
00063 dict = feature_data
00064
00065 baseline_labels = self.classify_baseline_code()
00066
00067 return baseline_labels, self.test_results(dict, baseline_labels)
00068
00069
00070 def classify_baseline_code(self):
00071
00072
00073 import hrl_tilting_hokuyo.occupancy_grid_3d as og3d
00074
00075 pt = np.matrix(self.processor.point_of_interest).T
00076
00077 width_half = self.processor.voi_width / 2.0
00078 brf = pt+np.matrix([-width_half,-width_half,-width_half]).T
00079 tlb = pt+np.matrix([width_half, width_half, width_half]).T
00080 resolution = np.matrix([0.1,0.1,0.0025]).T
00081 max_dist = 15
00082 min_dist = -15
00083 gr = og3d.occupancy_grid_3d(brf,tlb,resolution)
00084 print 'filling grid...'
00085 gr.fill_grid(self.processor.pts3d_bound)
00086 print '...filled.'
00087 gr.to_binary(1)
00088 l = gr.find_plane_indices(assume_plane=True,hmin=0.3,hmax=2)
00089 z_min = min(l)*gr.resolution[2,0]+gr.brf[2,0]
00090 z_max = max(l)*gr.resolution[2,0]+gr.brf[2,0]
00091
00092 pts = np.asarray(self.processor.pts3d_bound)
00093 conditions_surface = np.multiply(pts[2,:] > z_min, pts[2,:] < z_max)
00094 print 'cf',conditions_surface
00095 conditions_clutter = np.invert(conditions_surface)
00096 conditions_surface = np.multiply(conditions_surface, np.array(self.processor.map_polys) > 0)
00097 print 'cf',conditions_surface
00098 idx_surface = np.where(conditions_surface)
00099 conditions_clutter = np.multiply(conditions_clutter, np.array(self.processor.map_polys) > 0)
00100 idx_clutter = np.where(conditions_clutter)
00101
00102 n, m = np.shape(self.processor.pts3d_bound)
00103 print n,m
00104 labels = np.zeros(m)
00105 print np.shape(labels), labels
00106 print np.shape(idx_surface), idx_surface
00107 labels[idx_surface] = processor.LABEL_SURFACE
00108 labels[idx_clutter] = processor.LABEL_CLUTTER
00109
00110 print labels
00111
00112 return labels
00113
00114
clutter_segmentation
Author(s): Jason Okerman, Martin Schuster, Advisors: Prof. Charlie Kemp and Jim Regh, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 12:07:15