optedTrainerEvaluator.cpp
Go to the documentation of this file.
1 
18 #include <thread>
19 #include "optedTrainerEvaluator.hpp"
20 #include "worker.hpp"
21 #include "boost/filesystem/path.hpp"
22 
23 using path;
24 unsigned AMOUNT_OF_THREADS = 4;
25 
26 #define ISM_DATA "/media/share/data"
27 
28 
29 void addVizData (map<string, map<string, unsigned> > & target, map<string, map<string, unsigned> >& source)
30  {
31  for (auto it : source)
32  {
33  for (auto voteIt : it.second)
34  {
35  target[it.first][voteIt.first] += voteIt.second;
36  }
37  }
38  }
39 /*
40 void addVizData(map<string, vector<VotedPosePtr> >& target, map<string, vector<VotedPosePtr> >& source)
41  {
42  for (auto it : source)
43  {
44  target[it.first].insert(target[it.first].end(), it.second.begin(), it.second.end());
45  }
46  }
47 */
48 void drawISM(string model, string patternName, map<string, map<string, unsigned> >graphVizData, unsigned testsPerformed, unsigned timeSteps)
49 {
50  if (testsPerformed == 0)
51  {
52  testsPerformed = 1;
53  }
54  ofstream file;
55  stringstream filePath;
56  filePath<<ISM_DATA<<patternName<<"_"<<model<<"_ISMWithVotes.dot";
57  string filename = filePath.str();
58  filePath.str("");
59  vector<pair<string, string> > alreadyTakenCombinations;
60  ios_base::iostate exceptionMask = file.exceptions() | ios::failbit | ios::badbit;
61  file.exceptions(exceptionMask);
62  //map<string, set<string> > referencesPerObject;
63  try
64  {
65  file.open(filename);
66  file<<"digraph "<<model<<" {\n";
67  for (auto type : graphVizData)
68  {
69  for (auto voteIt : type.second)
70  {
71  file<<voteIt.first<<"[shape=\"box\"];\n";
72  //referencesPerObject[type.first].insert(voteIt.first);
73  }
74  }
75  for (auto typeIt : graphVizData)
76  {
77  for (auto voteIt : typeIt.second)
78  {
79  if (find(alreadyTakenCombinations.begin(), alreadyTakenCombinations.end(), make_pair(voteIt.first, typeIt.first)) == alreadyTakenCombinations.end())
80  {
81  // cout<<"from "<<typeIt.first<<" to "<<voteIt.first<<": "<<voteIt.second<<endl;exit(0);
82  file<<voteIt.first<<" -> "<<typeIt.first<<"[ label=\" &#8746;"
83  <<(unsigned)((((double)voteIt.second) / testsPerformed) / timeSteps)<<"&#124;&#8594;"
84  //<<(unsigned)((((double)typeIt.second.size() / testsPerformed) / timeSteps) / referencesPerObject.at(typeIt.first).size())<<"&#124;&#8594;"
85  <<(unsigned)(((double)voteIt.second) / testsPerformed)
86  //<<(unsigned)(((double)typeIt.second.size() / testsPerformed) / referencesPerObject.at(typeIt.first).size())
87  <<"\", decorate=\"true\", labelfoat=\"true\", labelfontcolor=\"red\", dir=\"back\"];\n";
88  alreadyTakenCombinations.push_back(make_pair(voteIt.first, typeIt.first));
89  }
90  }
91  }
92  file<<"}\n\n";
93  file.flush();
94  file.close();
95  }
96  catch (ios_base::failure& e)
97  {
98  cerr<<e.what()<<"\n";
99  //exit(1);
100  }
101 }
102 
103 
104 TestResult testModel(TestSpec testSpec, string modelDB)
105 {
106  unsigned objectCount = testSpec.objectCount;
107  unsigned timesteps = testSpec.timesteps;
108  TestResult currentResult = {testSpec, 0, 0, 0, 0, 0, 0, 0};
109  //map<string, vector<VotedPosePtr> > graphVizData;
110  map<string, map<string, unsigned> > graphVizData;
111  //struct timeval start, end;
112  auto validSetsPath = std::string(ISM_DATA) + "/testDBs/testSets/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_validTestSets\n";
113  TableHelperPtr validSetsTable(new TableHelper(validSetsPath));
114  auto validPatterns = validSetsTable->getRecordedPattern("demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps));
115  vector<ObjectSetPtr> validSets;
116  if (validPatterns != 0)
117  {
118  validSets = validPatterns->objectSets;
119  }
120 
121  auto invalidSetsPath = std::string(ISM_DATA) + "/testDBs/testSets/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_invalidTestSets";
122  TableHelperPtr invalidSetsTable(new TableHelper(invalidSetsPath));
123  auto invalidPatterns = invalidSetsTable->getRecordedPattern("demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps));
124  vector<ObjectSetPtr> invalidSets;
125  if (invalidPatterns != 0)
126  {
127  invalidSets = invalidPatterns->objectSets;
128  }
129  vector<Worker*> workers;
130  vector<shared_ptr<thread> > threads;
131  //Recognizer is not thread safe
132  const bool onlyPerfectResults = false;
133  RecognizerPtr prototype(new Recognizer(modelDB, 0.03, 10, false));
134  for (unsigned t_id = 0; t_id < AMOUNT_OF_THREADS; ++t_id)
135  {
136  Worker* worker = new Worker();
137  RecognizerPtr threadRecognizer(new Recognizer(*prototype));
138  shared_ptr<thread> oneThread(new thread(&Worker::test, worker, threadRecognizer, t_id, modelDB, validSets, invalidSets, testSpec));
139  //We need the memory
140  threadRecognizer.reset();
141  threads.push_back(oneThread);
142  workers.push_back(worker);
143  }
144  //We need the memory
145  prototype.reset();
146  for (unsigned t_id = 0; t_id < AMOUNT_OF_THREADS; ++t_id)
147  {
148  threads[t_id]->join();
149  TestResult workerTestResult = workers[t_id]->getTestResult();
150  currentResult.avgRuntimeForInvalidSets += workerTestResult.avgRuntimeForInvalidSets;
151  currentResult.avgRuntimeForValidSets += workerTestResult.avgRuntimeForValidSets;
152  currentResult.avgConfidenceForInvalidSets += workerTestResult.avgConfidenceForInvalidSets;
153  currentResult.avgConfidenceForValidSets += workerTestResult.avgConfidenceForValidSets;
154  currentResult.falsePositivesWithConfidence_1 += workerTestResult.falsePositivesWithConfidence_1;
155  currentResult.falseNegativesWithConfidenceSmaller_1 += workerTestResult.falseNegativesWithConfidenceSmaller_1;
156  auto workerVizData = workers[t_id]->getVizData();
157  addVizData(graphVizData, workerVizData);
158  //Enjoy garbage collection, IF YOU HAVE ONE
159  delete workers[t_id];
160  }
161  currentResult.avgRuntimeForInvalidSets /= (max((int)invalidSets.size(), 1));
162  currentResult.avgRuntimeForValidSets /= (max((int)validSets.size(), 1));
163  currentResult.avgConfidenceForInvalidSets /= (max((int)invalidSets.size(), 1));
164  currentResult.avgConfidenceForValidSets /= (max((int)validSets.size(), 1));
165  currentResult.falsePositivesWithConfidence_1 /= (max((int)invalidSets.size(), 1));
166  currentResult.falseNegativesWithConfidenceSmaller_1 /= (max((int)validSets.size(), 1));
167  drawISM(testSpec.usedModel, "demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps), graphVizData, validSets.size() + invalidSets.size(), timesteps);
168  return currentResult;
169 }
170 
171 void writeTestResult(const TestResult& r, ofstream& csvFile) {
172  csvFile << r.testSpec.timesteps << "," << r.testSpec.objectCount << "," << r.testSpec.usedModel << "," << r.testSpec.useGreedyConstruction
173  << "," << r.avgRuntimeForValidSets << "," << r.avgConfidenceForValidSets << "," << r.avgRuntimeForInvalidSets << "," << r.avgConfidenceForInvalidSets
174  << ","<< r.falsePositivesWithConfidence_1 << "," << r.falseNegativesWithConfidenceSmaller_1 << "," << r.learnTime << endl;
175 }
176 void writeError(string error, ofstream& csvFile)
177 {
178  csvFile<<error<<endl;
179 }
180 
181 int main (int argc, char** argv)
182 {
183  vector<unsigned> objectCounts = {3, 4, 5, 6, 7, 10, 15, 20};
184  vector<unsigned> timestepCounts = {10, 15, 20, 30, 50, 100, 200};
185  vector<string> models =
186  {
187  "OptimizedModel",
188  //"OpimizedModel_naive",
189  "Heuristic",
190  "StarTopology",
191  //"FullyMeshed",
192  //"FullyMeshed_naive"
193  };
194  RandomDemoRecorder demoRec = *(new RandomDemoRecorder());
195  double bin_size = 0.03;
196  double maxAngleDeviation = 10;
197  ofstream csvFile;
198  csvFile.open(std::string(ISM_DATA) + "/evaluation/result-csvs/result.csv");
199  csvFile << "timesteps,objectCount,usedModel,useGreedyConstruction,avgRuntimeForValidSets,avgConfideneForValidSets,avgRuntimForInvalidSets,avgConfidenceForInvalidSets,falsePositivesWithConfidence_1_in_%,falseNegativesWithConfidenceSmaller_1_in_%,learnTime" << endl;
200  for (auto objectCount : objectCounts)
201  {
202  for (auto timesteps : timestepCounts)
203  {
204  bool useGreedyConstruction = false;
205  if (objectCount > 5)
206  {
207  useGreedyConstruction = true;
208  }
209  auto demoRecordingPath = std::string(ISM_DATA) + "/testDBs/demo_recordings/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps);
210  TableHelperPtr recordingsTable(new TableHelper(demoRecordingPath));
211  recordingsTable->dropTables();
212  cout<<"inserting demo recording"<<endl;
213  demoRec.generateDemoRecording(demoRecordingPath, objectCount, timesteps);
214  cout<<"inserted demo recording"<<endl;
215  /*
216  OptedTrainer(std::string dbfilename, path outputDataPath, bool useClassifier, double bin_size,
217  double maxAngleDeviation, unsigned falsePositiveTolerance, unsigned maxRelations,
218  bool useGreedyConstruction, bool useThreads,
219  bool usePredefinedSeedGenTestSets = false, unsigned int genTestSetsSeed = 0);
220  */
221 
222  OptedTrainerPtr optimizedTrainer(new OptedTrainer(demoRecordingPath, path("."), false, bin_size, maxAngleDeviation, 0, 0, useGreedyConstruction, true));
223  struct timeval start, end;
224  cout<<"training for "<<objectCount<<" objects recorded over "<<timesteps<<" started"<<endl;
225  gettimeofday(&start, NULL);
226  optimizedTrainer->learn();
227  gettimeofday(&end, NULL);
228  cout<<"training for "<<objectCount<<" objects recorded over "<<timesteps<<" ended"<<endl;
229  recordingsTable->dropModelTables();
230  //We need the memory
231  optimizedTrainer.reset();
232  long learnTime = end.tv_sec - start.tv_sec;
233  for (auto model : models)
234  {
235  TestSpec currentTest = {useGreedyConstruction, objectCount, timesteps, model};
236  string modelDB;
237  if(model == "OptimizedModel")
238  {
239  modelDB = std::string(ISM_DATA) + "/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_best";
240  }
241  else if (model == "OpimizedModel_naive")
242  {
243  if (timesteps > 100)
244  {
245  continue;
246  }
247  else if (objectCount > 5)
248  {
249  if (objectCount > 6 || timesteps > 50)
250  {
251  continue;
252  }
253  }
254  modelDB = std::string(ISM_DATA) + "/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_best_naive";
255  }
256  else if (model == "Heuristic")
257  {
258  TrainerPtr regularTrainer(new Trainer(demoRecordingPath));
259  regularTrainer->trainPattern();
260  modelDB = demoRecordingPath;
261  //We need the memory
262  regularTrainer.reset();
263  }
264  else if (model == "StarTopology")
265  {
266  modelDB = std::string(ISM_DATA) + "/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_star";
267  }
268  else if (model == "FullyMeshed")
269  {
270  modelDB = std::string(ISM_DATA) + "/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_fullyMeshed";
271  }
272  else
273  {
274  if (timesteps > 100)
275  {
276  continue;
277  }
278  else if (objectCount > 5)
279  {
280  if (objectCount > 6 || timesteps > 50)
281  {
282  continue;
283  }
284  }
285  modelDB = std::string(ISM_DATA) + "/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) + "_" + to_string(timesteps) + "_fullyMeshed_naive";
286  }
287  try
288  {
289  TestResult currentResult = testModel(currentTest, modelDB);
290  currentResult.learnTime = learnTime;
291  writeTestResult(currentResult, csvFile);
292  }
293  catch (bad_alloc& ba)
294  {
295  cerr<<ba.what();
296  writeError(to_string(timesteps) + "," + to_string(objectCount) + "," + model + "," + ba.what(), csvFile);
297  }
298  }
299  }
300  }
301  csvFile.close();
302 }
void writeError(string error, ofstream &csvFile)
int main(int argc, char **argv)
filename
TestResult testModel(TestSpec testSpec, string modelDB)
void writeTestResult(const TestResult &r, ofstream &csvFile)
unsigned AMOUNT_OF_THREADS
void drawISM(string model, string patternName, map< string, map< string, unsigned > >graphVizData, unsigned testsPerformed, unsigned timeSteps)
#define ISM_DATA
void addVizData(map< string, map< string, unsigned > > &target, map< string, map< string, unsigned > > &source)


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