19 #include "optedTrainerEvaluator.hpp" 21 #include "boost/filesystem/path.hpp" 26 #define ISM_DATA "/media/share/data" 29 void addVizData (map<
string, map<string, unsigned> > & target, map<
string, map<string, unsigned> >& source)
31 for (
auto it : source)
33 for (
auto voteIt : it.second)
35 target[it.first][voteIt.first] += voteIt.second;
48 void drawISM(
string model,
string patternName, map<
string, map<string, unsigned> >graphVizData,
unsigned testsPerformed,
unsigned timeSteps)
50 if (testsPerformed == 0)
55 stringstream filePath;
56 filePath<<
ISM_DATA<<patternName<<
"_"<<model<<
"_ISMWithVotes.dot";
59 vector<pair<string, string> > alreadyTakenCombinations;
60 ios_base::iostate exceptionMask = file.exceptions() | ios::failbit | ios::badbit;
61 file.exceptions(exceptionMask);
66 file<<
"digraph "<<model<<
" {\n";
67 for (
auto type : graphVizData)
69 for (
auto voteIt : type.second)
71 file<<voteIt.first<<
"[shape=\"box\"];\n";
75 for (
auto typeIt : graphVizData)
77 for (
auto voteIt : typeIt.second)
79 if (find(alreadyTakenCombinations.begin(), alreadyTakenCombinations.end(), make_pair(voteIt.first, typeIt.first)) == alreadyTakenCombinations.end())
82 file<<voteIt.first<<
" -> "<<typeIt.first<<
"[ label=\" ∪" 83 <<(unsigned)((((
double)voteIt.second) / testsPerformed) / timeSteps)<<
"|→" 85 <<(unsigned)(((
double)voteIt.second) / testsPerformed)
87 <<
"\", decorate=\"true\", labelfoat=\"true\", labelfontcolor=\"red\", dir=\"back\"];\n";
88 alreadyTakenCombinations.push_back(make_pair(voteIt.first, typeIt.first));
96 catch (ios_base::failure& e)
106 unsigned objectCount = testSpec.objectCount;
107 unsigned timesteps = testSpec.timesteps;
108 TestResult currentResult = {testSpec, 0, 0, 0, 0, 0, 0, 0};
110 map<string, map<string, unsigned> > graphVizData;
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)
118 validSets = validPatterns->objectSets;
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)
127 invalidSets = invalidPatterns->objectSets;
129 vector<Worker*> workers;
130 vector<shared_ptr<thread> > threads;
132 const bool onlyPerfectResults =
false;
133 RecognizerPtr prototype(
new Recognizer(modelDB, 0.03, 10,
false));
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));
140 threadRecognizer.reset();
141 threads.push_back(oneThread);
142 workers.push_back(worker);
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();
159 delete workers[t_id];
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;
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;
178 csvFile<<error<<endl;
181 int main (
int argc,
char** argv)
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 =
194 RandomDemoRecorder demoRec = *(
new RandomDemoRecorder());
195 double bin_size = 0.03;
196 double maxAngleDeviation = 10;
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)
202 for (
auto timesteps : timestepCounts)
204 bool useGreedyConstruction =
false;
207 useGreedyConstruction =
true;
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;
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();
231 optimizedTrainer.reset();
232 long learnTime = end.tv_sec - start.tv_sec;
233 for (
auto model : models)
235 TestSpec currentTest = {useGreedyConstruction, objectCount, timesteps, model};
237 if(model ==
"OptimizedModel")
239 modelDB = std::string(
ISM_DATA) +
"/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) +
"_" + to_string(timesteps) +
"_best";
241 else if (model ==
"OpimizedModel_naive")
247 else if (objectCount > 5)
249 if (objectCount > 6 || timesteps > 50)
254 modelDB = std::string(
ISM_DATA) +
"/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) +
"_" + to_string(timesteps) +
"_best_naive";
256 else if (model ==
"Heuristic")
258 TrainerPtr regularTrainer(
new Trainer(demoRecordingPath));
259 regularTrainer->trainPattern();
260 modelDB = demoRecordingPath;
262 regularTrainer.reset();
264 else if (model ==
"StarTopology")
266 modelDB = std::string(
ISM_DATA) +
"/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) +
"_" + to_string(timesteps) +
"_star";
268 else if (model ==
"FullyMeshed")
270 modelDB = std::string(
ISM_DATA) +
"/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) +
"_" + to_string(timesteps) +
"_fullyMeshed";
278 else if (objectCount > 5)
280 if (objectCount > 6 || timesteps > 50)
285 modelDB = std::string(
ISM_DATA) +
"/testDBs/topologies/record.sqlite.demo_recording_" + to_string(objectCount) +
"_" + to_string(timesteps) +
"_fullyMeshed_naive";
289 TestResult currentResult =
testModel(currentTest, modelDB);
290 currentResult.learnTime = learnTime;
293 catch (bad_alloc& ba)
296 writeError(to_string(timesteps) +
"," + to_string(objectCount) +
"," + model +
"," + ba.what(), csvFile);
void writeError(string error, ofstream &csvFile)
int main(int argc, char **argv)
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)
void addVizData(map< string, map< string, unsigned > > &target, map< string, map< string, unsigned > > &source)