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


asr_lib_ism
Author(s): Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Wed Jan 8 2020 04:02:41