summarize_results.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 # The goal is to combine all the results of Obj/Trial/Servo results into
00004 # one big datastructure for easy generation of tables and figures for the dissertation!
00005 
00006 import roslib
00007 roslib.load_manifest('rfid_datacapture')
00008 roslib.load_manifest('rfid_pf')
00009 import rospy
00010 
00011 import cPickle as pkl
00012 import numpy as np, math
00013 
00014 import rfid_pf.pf_stats as pfs
00015 import rfid_pf.stats_best_uniform as sbu
00016 import scipy.stats as ss
00017 
00018 
00019 def process_summary( cr_filt='pf', servo_yn=False, print_str='PARTICLE FILTER:', combined_results=None ):
00020     # PF overall stats (SEARCH):
00021     # servo_yn = False
00022 
00023     # Only take results for this setting (eg servo state)
00024     
00025     # filt = [ res for res in combined_results['pf'] if res['servo_yn'] == servo_yn ]
00026     filt = [ res for res in combined_results[cr_filt] if res['servo_yn'] == servo_yn ]
00027 
00028 
00029     # Refine to eliminate "no read" scenarios
00030     filt = [ f for f in filt if f['dxy'].__class__ != ''.__class__ ]
00031     
00032 
00033     dist_abs = []
00034     dist_from_opt = []
00035     ang_error = []
00036 
00037     for res in filt:
00038         # The distance from the tag
00039         dist_abs.append( res['dxy'] )
00040 
00041         # The difference in distance from tag for this result versus the best possible achievable result
00042         opt_for_loc = [b for b in combined_results['best'] if b['loc'] == res['loc']][0] # it's unique
00043         dist_from_opt.append( np.abs( res['dxy'] - opt_for_loc['best_dxy'] ))
00044 
00045         # | Angular Error | (deg)
00046         ang_error.append( math.degrees( np.abs(res['dtheta']) ))
00047 
00048     if servo_yn:
00049         servo_state = 'search PLUS servo'
00050     else:
00051         servo_state = 'search ONLY'
00052         
00053     print print_str + ' ' + servo_state
00054     print 'Average Absolute Distance From Tag (meters):\n\t%2.3f (%2.3f)\n' % ( np.mean( dist_abs ),
00055                                                                                 np.std(  dist_abs ))
00056 
00057     print 'Difference between Best Possible Distance and ',
00058     print 'PF-estimated Distance From Tag (meters):\n\t%2.3f (%2.3f)\n' % ( np.mean( dist_from_opt ),
00059                                                                             np.std(  dist_from_opt ))
00060 
00061     print 'Average Angular Error Magnitude (degrees):\n\t%3.1f (%3.1f)\n' % ( np.mean( ang_error ),
00062                                                                               np.std(  ang_error ))
00063 
00064     print '\n\n'
00065     return dist_abs, dist_from_opt, ang_error
00066 
00067 
00068 def process_uniform_summary( combined_results = None):
00069 
00070     dxy_means =    [ i['dxy_mean'] for i in combined_results['uniform'] ]
00071     dtheta_means = [ i['dtheta_mean'] for i in combined_results['uniform'] ]
00072         
00073     print 'Average Absolute Distance From Tag (meters):\n\t%2.3f (%2.3f)\n' % ( np.mean( dist_abs ),
00074                                                                                 np.std(  dist_abs ))
00075 
00076     print 'Difference between Best Possible Distance and ',
00077     print 'PF-estimated Distance From Tag (meters):\n\t%2.3f (%2.3f)\n' % ( np.mean( dist_from_opt ),
00078                                                                             np.std(  dist_from_opt ))
00079 
00080     print 'Average Angular Error Magnitude (degrees):\n\t%3.1f (%3.1f)\n' % ( np.mean( ang_error ),
00081                                                                               np.std(  ang_error ))
00082 
00083     print '\n\n'
00084 
00085 
00086 def global_stats():
00087     # Get the stupid depracation warning out of the way.
00088     ss.ttest_ind( range(30), range(30))
00089 
00090     print '\n\n\n'
00091 
00092     f = open( 'summarize_results.pkl', 'r' )
00093     combined_results = pkl.load( f )
00094     f.close()
00095 
00096 
00097     pf_dist_abs, pf_dist_from_opt, pf_ang_error = process_summary( 'pf', True, 'PARTICLE FILTER:', combined_results )
00098     rel_dist_abs, rel_dist_from_opt, rel_ang_error = process_summary( 'rel', True, 'RELATIVE METHODS:', combined_results )
00099 
00100     def ttest_significance( p_value ):
00101         if p_value < 0.05:
00102             return 'YES'
00103         else:
00104             return 'NO'
00105 
00106     print 'T-TEST RESUTLS: '
00107     print 'Absolute Distance:'
00108     tvalue, pvalue = ss.ttest_ind( pf_dist_abs, rel_dist_abs )
00109     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00110 
00111     print 'Difference between Best Dist:'
00112     tvalue, pvalue = ss.ttest_ind( pf_dist_from_opt, rel_dist_from_opt )
00113     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00114 
00115     print 'Angular Error:'
00116     tvalue, pvalue = ss.ttest_ind( pf_ang_error, rel_ang_error )
00117     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00118 
00119     print '...\n\n'
00120     pf_dist_abs, pf_dist_from_opt, pf_ang_error = process_summary( 'pf', False, 'PARTICLE FILTER:', combined_results )
00121     rel_dist_abs, rel_dist_from_opt, rel_ang_error = process_summary( 'rel', False, 'RELATIVE METHODS:', combined_results )
00122 
00123     print 'T-TEST RESUTLS: '
00124     print 'Absolute Distance:'
00125     tvalue, pvalue = ss.ttest_ind( pf_dist_abs, rel_dist_abs )
00126     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00127 
00128     print 'Difference between Best Dist:'
00129     tvalue, pvalue = ss.ttest_ind( pf_dist_from_opt, rel_dist_from_opt )
00130     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00131 
00132     print 'Angular Error:'
00133     tvalue, pvalue = ss.ttest_ind( pf_ang_error, rel_ang_error )
00134     print '\tp-value: %1.7f ==> Significance: %s' % ( pvalue, ttest_significance( pvalue ))
00135 
00136 
00137 
00138 if __name__ == '__main__':
00139 
00140     import optparse
00141     p = optparse.OptionParser()
00142     p.add_option('--recalc', action='store_true', dest='recalc',
00143                  help='Recalculate the summary pickle files', default = False)
00144     opt, args = p.parse_args()
00145 
00146 
00147     if not opt.recalc:
00148         global_stats()
00149 
00150 
00151     if opt.recalc:
00152         combined_results = { 'rel':     [],
00153                              'pf' :     [],
00154                              'best':    [],
00155                              'uniform': [] }
00156 
00157         combined_results_full = { 'rel':     [],
00158                                   'pf' :     [],
00159                                   'best':    [],
00160                                   'uniform': [] }
00161 
00162         # Add the results (trial and obj) of the actual estimators (relative and pf)
00163         for trial_num in range( 0, 9 ): # trial
00164             for obj_num in range( 0, 9 ): # obj
00165                 for servo_yn in [False, True]: # servo_yn
00166 
00167                     print 'Adding Trial %d, Obj %d, Servo %d' % (trial_num, obj_num, servo_yn)
00168 
00169                     # Add the relative sensing results
00170                     rel_result_fname = '/home/travis/svn/robot1/src/projects/rfid_datacapture/src/rfid_datacapture/search_cap/'
00171                     rel_result_fname += 'Obj%d_Trial%d_Servo%d_rel_results.pkl' % ( obj_num, trial_num, int( servo_yn ))
00172 
00173                     try:
00174                         f = open( rel_result_fname, 'r' )
00175                         rel_result = pkl.load( f )
00176                         f.close()
00177 
00178                         combined_results_full['rel'].append( dict(rel_result) )  # Deep copy
00179                         rel_result['other'] = None  # Save space!
00180                         combined_results['rel'].append( rel_result )
00181                     except:
00182                         print 'File not found (skipping): ', rel_result_fname
00183                         print 'FIX THIS LATER!\n'
00184                         pass
00185 
00186 
00187                     # Add the pf results
00188                     pf_result_fname = '/home/travis/svn/robot1/src/projects/rfid_pf/src/rfid_pf/'
00189                     pf_result_fname += 'Obj%d_Trial%d_Servo%d_pf_results.pkl' % ( obj_num, trial_num, int( servo_yn ))
00190 
00191                     try:
00192                         f = open( pf_result_fname, 'r' )
00193                         pf_result = pkl.load( f )
00194                         f.close()
00195 
00196                         combined_results_full['pf'].append( dict(pf_result) )  # Deep copy
00197                         pf_result['other'] = None  # Save space
00198                         combined_results['pf'].append( pf_result )
00199                     except:
00200                         print 'File not found (skipping): ', pf_result_fname
00201                         print 'FIX THIS LATER!\n'
00202                         pass
00203 
00204 
00205         # Add the results (location by location)
00206         for loc_num in range( 0, 9 ):
00207 
00208             # Stats for the "best"
00209             best_pos, best_dxy = sbu.best_location( loc_num )
00210             res = { 'loc':loc_num,
00211                     'best_pos':best_pos,
00212                     'best_dxy':best_dxy }
00213             combined_results['best'].append( res )
00214             combined_results_full['best'].append( dict(res) )  # Deep copy
00215 
00216 
00217             # Stats for Uniform
00218             dxy_mean, dxy_std, dtheta_mean, dtheta_std = sbu.uniform_predict( loc_num )
00219             res = { 'loc':loc_num,
00220                     'dxy_mean':dxy_mean,
00221                     'dxy_std':dxy_std,
00222                     'dtheta_mean':dtheta_mean,
00223                     'dtheta_std':dtheta_std }
00224             combined_results['uniform'].append( res )
00225             combined_results_full['uniform'].append( dict(res) )  # Deep copy
00226 
00227         f = open( 'summarize_results.pkl', 'w' )
00228         pkl.dump( combined_results, f )
00229         f.close()
00230 
00231         f = open( 'summarize_results_full.pkl', 'w' )
00232         pkl.dump( combined_results_full, f )
00233         f.close()
00234 
00235         exit()
00236 
00237         # DONE WITH RECALC
00238 
00239     
00240 
00241 


rfid_pf
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 12:03:34