stats_01_leave_one_out.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 #
00004 # Copyright (c) 2010, Georgia Tech Research Corporation
00005 # All rights reserved.
00006 # 
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions are met:
00009 #     * Redistributions of source code must retain the above copyright
00010 #       notice, this list of conditions and the following disclaimer.
00011 #     * Redistributions in binary form must reproduce the above copyright
00012 #       notice, this list of conditions and the following disclaimer in the
00013 #       documentation and/or other materials provided with the distribution.
00014 #     * Neither the name of the Georgia Tech Research Corporation nor the
00015 #       names of its contributors may be used to endorse or promote products
00016 #       derived from this software without specific prior written permission.
00017 # 
00018 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00019 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 #
00029 
00030 import roslib; roslib.load_manifest('trf_learn')
00031 import rospy
00032 import trf_learn.recognize_3d as r3d
00033 import trf_learn.locations_manager as lcm
00034 import sys
00035 import optparse
00036 import pdb
00037 import numpy as np
00038 import ml_lib.dataset as ds
00039 
00040 class LeaveOneOut:
00041 
00042     def __init__(self, filename, dataset_name):
00043         self.rec_params = r3d.Recognize3DParam()
00044         self.locations_man = lcm.LocationsManager(filename, rec_params=self.rec_params, train=True)
00045         self.dataset_name = dataset_name
00046         pdb.set_trace()
00047         print 'The following datasets are available:', self.locations_man.data.keys()
00048 
00049     def leave_one_out(self):
00050         #For each data set in locations man, for each data point, remove one data point, train, test on that point
00051         dataset = self.locations_man.data[self.dataset_name]['dataset']
00052         num_datapoints = dataset.inputs.shape[1]
00053         #dataset.inputs = np.row_stack((np.matrix(range(num_datapoints)), dataset.inputs))
00054 
00055         predicted_values = []
00056         correct = 0
00057         incorrect = 0
00058         confusion = np.matrix([[0,0], [0,0.]])
00059         num_pos = np.sum(dataset.outputs)
00060         num_neg = num_datapoints-num_pos
00061         #for i in range(2):
00062         for i in range(num_datapoints):
00063             loo_dataset, left_out_input, left_out_output = ds.leave_one_out(dataset, i)
00064             self.locations_man.data[self.dataset_name]['dataset'] = loo_dataset
00065             self.locations_man.train(self.dataset_name, save_pca_images=False)
00066             learner = self.locations_man.learners[self.dataset_name]
00067             predicted = learner.classify(left_out_input)
00068             predicted_values += predicted
00069             if predicted[0] == 0:
00070                 if left_out_output[0,0] == 0:
00071                     confusion[0,0] += 1
00072                 else:
00073                     confusion[0,1] += 1
00074             else:
00075                 #predicted[0] == 1
00076                 if left_out_output[0,0] == 0:
00077                     confusion[1,0] += 1
00078                 else:
00079                     confusion[1,1] += 1
00080 
00081             if predicted[0] == left_out_output[0,0]:
00082                 correct += 1
00083             else:
00084                 incorrect += 1
00085 
00086         print '============================================'
00087         print 'dataset', self.dataset_name
00088         print 'confusion matrix\n', confusion
00089         confusion[:,0] = confusion[:,0] / num_neg
00090         confusion[:,1] = confusion[:,1] / num_pos
00091         print 'correct', correct, '\nincorrect', incorrect, '\npercentage', 100.* (correct/float(num_datapoints))
00092         print predicted_values
00093         print '============================================'
00094 
00095 
00096         #predicted_values += predicted
00097         #np.matrix(predicted_values)
00098         #print 'result', predicted[0], predicted.__class__, left_out_output[0,0]
00099 
00100 if __name__ == '__main__':
00101     #p = optparse.OptionParser()
00102     #p.add_option("-d", "--display", action="store", default='locations_narrow_v11.pkl')
00103 
00104     if len(sys.argv) > 1:
00105         name = sys.argv[1]
00106     else:
00107         name = 'locations_narrow_v11.pkl'
00108 
00109     loo = LeaveOneOut(name, sys.argv[2])
00110     loo.leave_one_out()
00111     print 'end!'
00112 
00113 


trf_learn
Author(s): Hai Nguyen (hai@gatech.edu) Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 11:47:18