simpleEvaluator.cpp
Go to the documentation of this file.
1 
18 #include <fstream>
19 #include <stdio.h>
20 #include <unistd.h>
21 #include <sys/time.h>
22 
23 #include <ISM/TableHelper.hpp>
24 #include <ISM/Recognizer.hpp>
25 
26 #define ISM_DATA "/media/share/data"
27 
28 using namespace ISM;
29 using namespace std;
30 
31 void drawISM(string model, string patternName, map<string, map<string, unsigned> >graphVizData, unsigned testsPerformed, unsigned timeSteps)
32 {
33  if (testsPerformed == 0)
34  {
35  testsPerformed = 1;
36  }
37  ofstream file;
38  stringstream filePath;
39  filePath<<std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/complexity/"<<patternName<<"_"<<model<<"_ISMWithVotes.dot";
40  string filename = filePath.str();
41  filePath.str("");
42  vector<pair<string, string> > alreadyTakenCombinations;
43  ios_base::iostate exceptionMask = file.exceptions() | ios::failbit | ios::badbit;
44  file.exceptions(exceptionMask);
45  //map<string, set<string> > referencesPerObject;
46  try
47  {
48  file.open(filename);
49  file<<"digraph "<<model<<" {\n";
50  for (auto type : graphVizData)
51  {
52  for (auto voteIt : type.second)
53  {
54  file<<voteIt.first<<"[shape=\"box\"];\n";
55  //referencesPerObject[type.first].insert(voteIt.first);
56  }
57  }
58  for (auto typeIt : graphVizData)
59  {
60  for (auto voteIt : typeIt.second)
61  {
62  if (find(alreadyTakenCombinations.begin(), alreadyTakenCombinations.end(), make_pair(voteIt.first, typeIt.first)) == alreadyTakenCombinations.end())
63  {
64  //cout<<"from "<<typeIt.first<<" to "<<voteIt.first<<": "<<voteIt.second<<endl;exit(0);
65  file<<voteIt.first<<" -> "<<typeIt.first<<"[ label=\" &#8746;"
66  <<(unsigned)((((double)voteIt.second) / testsPerformed) / timeSteps)<<"&#124;&#8594;"
67  //<<(unsigned)((((double)typeIt.second.size() / testsPerformed) / timeSteps) / referencesPerObject.at(typeIt.first).size())<<"&#124;&#8594;"
68  <<(unsigned)(((double)voteIt.second) / testsPerformed)
69  //<<(unsigned)(((double)typeIt.second.size() / testsPerformed) / referencesPerObject.at(typeIt.first).size())
70  <<"\", decorate=\"true\", labelfoat=\"true\", labelfontcolor=\"red\", dir=\"back\"];\n";
71  alreadyTakenCombinations.push_back(make_pair(voteIt.first, typeIt.first));
72  }
73  }
74  }
75  file<<"}\n\n";
76  file.flush();
77  file.close();
78  }
79  catch (ios_base::failure& e)
80  {
81  cerr<<e.what()<<"\n";
82  //exit(1);
83  }
84 }
85 
86 void addVizData(std::map<std::string, std::map<std::string, unsigned> >& graphVizData, const RecognizerPtr& recognizer)
87 {
88  std::map<ObjectPtr, std::vector<VotedPosePtr> > votingCache = recognizer->getVotingCache();
89  for (auto it : votingCache)
90  {
91  for (auto voteIt : it.second)
92  {
93  ++graphVizData[it.first->getType()][voteIt->vote->patternName];
94  }
95  }
96 }
97 
98 
99 int main (int argc, char**argv)
100 {
101  std::vector<std::pair<std::string, std::string> > modeldbs =
102  {
103  std::make_pair("best", std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_best"),
104  std::make_pair("best_naive", std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_best_naive"),
105  std::make_pair("star", std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_star"),
106  std::make_pair("fully_meshed", std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_fullyMeshed"),
107  std::make_pair("fully_meshed_naive",std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_fullyMeshed_naive")
108  };
109  ofstream output;
110  output.open(std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/output.csv");
111  output<<"model, avgTime, falsePositives\n";
112  for (auto model : modeldbs)
113  {
114  std::map<std::string, std::map<std::string, unsigned> > vizData;
115  cout<<"trying to open db file\n";
116  TableHelperPtr validSetsTable(new TableHelper(std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_validTestSets"));
117  cout<<"could open valid sets\n";
118  auto validPatterns = validSetsTable->getRecordedPattern("optedTrainer_example_1");
119  vector<ObjectSetPtr> validSets;
120  if (validPatterns != 0)
121  {
122  validSets = validPatterns->objectSets;
123  }
124  struct timeval start, end;
125  long time = 0;
126  TableHelperPtr invalidSetsTable(new TableHelper(std::string(ISM_DATA)+"/evaluation/gedeck_evaluation/sourcedbs/record.sqlite.optedTrainer_example_1_invalidTestSets"));
127  cout<<"could open invalid sets\n ";
128  auto invalidPatterns = invalidSetsTable->getRecordedPattern("optedTrainer_example_1");
129  vector<ObjectSetPtr> invalidSets;
130  if (invalidPatterns != 0)
131  {
132  invalidSets = invalidPatterns->objectSets;
133  }
134  cout<<invalidSets.size()<<endl;
135  RecognizerPtr recog(new Recognizer(model.second, 0.03, 10, false));
136  cout<<"could create recognizer\n";
137  for (auto validSet : validSets)
138  {
139  if (model.first == "fully_meshed_naive")
140  {
141  break;
142  }
143  cout<<".";cout.flush();
144  gettimeofday(&start, NULL);
145  auto res = recog->recognizePattern(validSet, 0.0, 1);
146  gettimeofday(&end, NULL);
147  time += ((end.tv_sec - start.tv_sec) * 1000) + ((end.tv_usec - start.tv_usec) / 1000);
148  addVizData(vizData, recog);
149  }
150  unsigned fps = 0;
151  for (auto invalidSet : invalidSets)
152  {
153  cout<<".";cout.flush();
154  gettimeofday(&start, NULL);
155  auto res = recog->recognizePattern(invalidSet, 0.0, 1);
156  gettimeofday(&end, NULL);
157  time += ((end.tv_sec - start.tv_sec) * 1000) + ((end.tv_usec - start.tv_usec) / 1000);
158  addVizData(vizData, recog);
159  if (res.size() > 0 && res[0]->getConfidence() == 1 && res[0]->getPatternName() == "optedTrainer_example_1")
160  {
161  ++fps;
162  }
163  if (model.first == "fully_meshed_naive")
164  {
165  break;
166  }
167  }
168  double avg;
169  if (model.first == "fully_meshed_naive")
170  {
171  drawISM(model.first, "optedTrainer_example_1", vizData, 1, 112.0);
172  avg = ((double)time) / 1.0;
173  }
174  else
175  {
176  drawISM(model.first, "optedTrainer_example_1", vizData, validSets.size() + invalidSets.size(), 112.0);
177  avg = ((double)time) / (validSets.size() + invalidSets.size());
178  }
179  cout<<fps<<endl;
180  output<<model.first<<","<<avg<<","<<fps<<endl;
181  }
182  output.close();
183 }
184 
filename
#define ISM_DATA
void addVizData(std::map< std::string, std::map< std::string, unsigned > > &graphVizData, const RecognizerPtr &recognizer)
int main(int argc, char **argv)
void drawISM(string model, string patternName, map< string, map< string, unsigned > >graphVizData, unsigned testsPerformed, unsigned timeSteps)


asr_ism
Author(s): Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Thu Jan 9 2020 07:20:58