validator.cpp
Go to the documentation of this file.
1 #include <ISM/utility/TableHelper.hpp>
3 
4 using namespace ISM;
5 using namespace ProbabilisticSceneRecognition;
6 
7 typedef std::map<std::string, std::vector<ObjectSetPtr> > PatternNameToObjectSet;
8 
10 {
11  std::string sceneName;
12  double probability;
13  double correct;
14 };
15 
17 {
18  std::string testSetName;
21  std::vector<TestSetSingleResult> singleResults;
22 };
23 
25 {
27  std::vector<TestSetCompleteResult> testSetResults;
28 };
29 
31 {
33  std::string validfile, invalidfile, sceneModel, outputFile, frameId;
34 };
35 
37 {
38  try {
39  TableHelperPtr localTableHelper(new TableHelper(fileName));
40  PatternNameToObjectSet testSet;
41  for (auto patternName: localTableHelper->getRecordedPatternNames())
42  testSet[patternName] = localTableHelper->getRecordedPattern(patternName)->objectSets;
43  return testSet;
44  } catch (soci::soci_error& se) {
45  std::cerr << "Soci error " << se.what() << std::endl;
46  throw se;
47  }
48 }
49 
51 {
53 
54  double fullRecognitionRuntime = 0;
55 
56  for (std::pair<std::string, std::vector<ObjectSetPtr>> testSetsByPattern: ts)
57  {
58  std::string in = "";
59  if (!valid) in = "in";
60  std::cout << "Evaluating " << testSetsByPattern.second.size() << " " << in << "valid test sets for pattern " << testSetsByPattern.first << std::endl;
61 
63  boost::shared_ptr<Visualization::ProbabilisticSceneModelVisualization> mVisualizer(new Visualization::ProbabilisticSceneModelVisualization());
64 
65  for (unsigned int testSetNumber = 0; testSetNumber < testSetsByPattern.second.size(); testSetNumber++)
66  {
67  ObjectSetPtr testSet = testSetsByPattern.second[testSetNumber];
68  std::vector<SceneIdentifier> sceneList;
69 
70  struct timeval start;
71  struct timeval end;
72 
73  model.reset(new SceneModelDescription());
74  model->loadModelFromFile(params.sceneModel, "maximum");
75  model->initializeVisualizer(mVisualizer);
76  mVisualizer->setDrawingParameters(params.scale, params.sigma, params.frameId);
77 
78  gettimeofday(&start, NULL);
79 
80  for (unsigned int i = 0; i < testSet->objects.size(); i++)
81  {
82  boost::shared_ptr<Object> object(new Object(*(testSet->objects[i])));
83  model->integrateEvidence(object);
84  }
85 
86  model->updateModel();
87  model->getSceneListWithProbabilities(sceneList);
88 
89  gettimeofday(&end, NULL);
90 
91  double recognitionRuntime, seconds, useconds;
92  seconds = end.tv_sec - start.tv_sec;
93  useconds = end.tv_usec - start.tv_usec;
94  recognitionRuntime = seconds + useconds / 1000000;
95  fullRecognitionRuntime += recognitionRuntime;
96 
97  std::string validity = "v";
98  if (!valid) validity = "i";
99  std::string testSetName = testSetsByPattern.first + "_" + validity + "_" + std::to_string(testSetNumber);
100 
102  tscr.testSetValid = valid;
103  tscr.testSetName = testSetName;
104  tscr.recognitionRuntime = recognitionRuntime;
105 
106  for (SceneIdentifier sceneIdentifier: sceneList)
107  {
108  double probability = sceneIdentifier.mLikelihood;
109  TestSetSingleResult tssr;
110  tssr.sceneName = sceneIdentifier.mDescription;
111  tssr.probability = probability;
112  tssr.correct = true;
113  if (valid && probability <= params.recognitionThreshold)
114  tssr.correct = false;
115  if (!valid && probability > params.recognitionThreshold)
116  tssr.correct = false;
117 
118  tscr.singleResults.push_back(tssr);
119  }
120  er.testSetResults.push_back(tscr);
121  }
122  }
123  er.averageRecognitionRuntime = fullRecognitionRuntime / ((double) er.testSetResults.size());
124 
125  return er;
126 }
127 
128 bool find(const std::vector<double>& in, double toFind)
129 {
130  for (double i: in)
131  {
132  if (std::abs(i - toFind) < std::numeric_limits<double>::epsilon())
133  return true;
134  }
135  return false;
136 }
137 
143 int main(int argc, char *argv[])
144 {
145  ros::init(argc, argv, "js_validator");
146  ros::NodeHandle n;
147  ros::NodeHandle nh("~");
148 
149  ModelParams mp;
150 
151  if (!nh.getParam("recognition_threshold", mp.recognitionThreshold))
152  throw std::runtime_error("Please specifiy parameter recognition_threshold when starting this node.");
153 
154  if (!nh.getParam("valid_testset_db_filename", mp.validfile))
155  throw std::runtime_error("Please specifiy parameter valid_testset_db_filename when starting this node.");
156  if (!nh.getParam("invalid_testset_db_filename", mp.invalidfile))
157  throw std::runtime_error("Please specifiy parameter invalid_testset_db_filename when starting this node.");
158  if (!nh.getParam("scene_model", mp.sceneModel))
159  throw std::runtime_error("Please specifiy parameter scene_model when starting this node.");
160  if (!nh.getParam("output_file", mp.outputFile))
161  throw std::runtime_error("Please specifiy parameter output_file when starting this node.");
162  if (!nh.getParam("base_frame_id", mp.frameId))
163  throw std::runtime_error("Please specifiy parameter base_frame_id when starting this node.");
164  if (!nh.getParam("scale_factor", mp.scale))
165  throw std::runtime_error("Please specifiy parameter scale_factor when starting this node.");
166  if (!nh.getParam("sigma_multiplicator", mp.sigma))
167  throw std::runtime_error("Please specifiy parameter sigma_multiplicator when starting this node.");
168 
171 
172  vts = loadTestSetsFromDB(mp.validfile);
174 
175  EvaluationResult validER = evaluate(vts, true, mp);
176  EvaluationResult invalidER = evaluate(its, false, mp);
177 
178  EvaluationResult er;
179 
180  er.testSetResults = validER.testSetResults;
181  er.testSetResults.insert(er.testSetResults.end(), invalidER.testSetResults.begin(), invalidER.testSetResults.end());
182 
183  // Make sure all lists have the same order:
186  {
187  if (tscr.singleResults.size() != ref.singleResults.size())
188  throw std::runtime_error("List size not equal");
189  for (unsigned int i = 0; i < ref.singleResults.size(); i++)
190  if (tscr.singleResults[i].sceneName != ref.singleResults[i].sceneName)
191  throw std::runtime_error("Order in list not equal.");
192  }
193 
194  std::stringstream csv;
195  csv << mp.sceneModel << std::endl;
196  csv << "testset; recognition runtime;";
197  for (TestSetSingleResult tssr: er.testSetResults[0].singleResults)
198  csv << "P(" << tssr.sceneName << "); ";
199  csv << std::endl;
200 
201  struct ProbSum
202  {
203  double sum = 0;
204  double amount = 0;
205  };
206 
207  struct FalseRecognition
208  {
209  unsigned int number = 0;
210  };
211 
212  std::map<std::string, ProbSum> allProbs;
213  std::map<std::string, ProbSum> valProbs;
214  std::map<std::string, ProbSum> invProbs;
215  std::map<std::string, FalseRecognition> falsePositives;
216  std::map<std::string, FalseRecognition> falseNegatives;
217 
218  double recognitionRuntimeSum = 0;
219 
221  {
222  csv << tscr.testSetName << "; ";
223  recognitionRuntimeSum += tscr.recognitionRuntime;
224  csv << tscr.recognitionRuntime << "; ";
225  for (TestSetSingleResult tssr: tscr.singleResults)
226  {
227  csv << tssr.probability << "; ";
228  allProbs[tssr.sceneName].sum += tssr.probability;
229  allProbs[tssr.sceneName].amount++;
230 
231  if (tscr.testSetValid)
232  {
233  valProbs[tssr.sceneName].sum += tssr.probability;
234  valProbs[tssr.sceneName].amount++;
235  if (!tssr.correct)
236  falseNegatives[tssr.sceneName].number++;
237  }
238  else
239  {
240  invProbs[tssr.sceneName].sum += tssr.probability;
241  invProbs[tssr.sceneName].amount++;
242  if (!tssr.correct)
243  falsePositives[tssr.sceneName].number++;
244  }
245  }
246  csv << std::endl;
247  }
248  csv << std::endl;
249 
250  er.averageRecognitionRuntime = recognitionRuntimeSum / ((double) er.testSetResults.size());
251 
252  unsigned int numberOfValidTestSets = validER.testSetResults.size();
253  unsigned int numberOfInvalidTestSets = invalidER.testSetResults.size();
254 
255  std::stringstream avgprobs, avgvalp, avginvp, avgfp, avgfpi, avgfpr, avgfn, avgfnv, avgfnr, avgfr, ts, avgfrr;
256  for (TestSetSingleResult tssr: ref.singleResults)
257  {
258  avgprobs << allProbs[tssr.sceneName].sum / ((double) allProbs[tssr.sceneName].amount) << "; ";
259  avgvalp << valProbs[tssr.sceneName].sum / ((double) valProbs[tssr.sceneName].amount) << "; ";
260  avginvp << invProbs[tssr.sceneName].sum / ((double) invProbs[tssr.sceneName].amount) << "; ";
261  avgfp << falsePositives[tssr.sceneName].number << "; ";
262  avgfpi << numberOfInvalidTestSets << "; ";
263  avgfpr << ((double) falsePositives[tssr.sceneName].number) / ((double) numberOfInvalidTestSets) << "; ";
264  avgfn << falseNegatives[tssr.sceneName].number << "; ";
265  avgfnv << numberOfValidTestSets << "; ";
266  avgfnr << ((double) falseNegatives[tssr.sceneName].number) / ((double) numberOfValidTestSets) << "; ";
267  avgfr << falsePositives[tssr.sceneName].number + falseNegatives[tssr.sceneName].number << "; ";
268  ts << numberOfInvalidTestSets + numberOfValidTestSets << "; ";
269  avgfrr << ((double) (falsePositives[tssr.sceneName].number + falseNegatives[tssr.sceneName].number)) / ((double) (numberOfInvalidTestSets + numberOfValidTestSets)) << "; ";
270  }
271 
272  csv << "average; " << er.averageRecognitionRuntime << "; " << avgprobs.str() << std::endl;
273  csv << "average of valid sets; " << validER.averageRecognitionRuntime << "; " << avgvalp.str() << std::endl;
274  csv << "average of invalid sets; " << invalidER.averageRecognitionRuntime << "; " << avginvp.str() << std::endl;
275  csv << "false positives; ; " << avgfp.str() << std::endl;
276  csv << "invalid sets; ; " << avgfpi.str() << std::endl;
277  csv << "ratio; ; " << avgfpr.str() << std::endl;
278  csv << "false negatives; ; " << avgfn.str() << std::endl;
279  csv << "valid sets; ; " << avgfnv.str() << std::endl;
280  csv << "ratio; ; " << avgfnr.str() << std::endl;
281  csv << "false recognitions; ; " << avgfr.str() << std::endl;
282  csv << "test sets; ; " << ts.str() << std::endl;
283  csv << "ratio; ; " << avgfrr.str() << std::endl;
284 
285  std::ofstream csvfile;
286  csvfile.open(mp.outputFile);
287  if (!csvfile.is_open())
288  throw std::invalid_argument("Could not open file " + mp.outputFile);
289  csvfile << csv.str();
290  csvfile.close();
291 
292  std::cout << "Wrote evaluation result to file " << mp.outputFile << std::endl;
293 }
294 
PatternNameToObjectSet loadTestSetsFromDB(std::string fileName)
Definition: validator.cpp:36
double scale
Definition: validator.cpp:32
double recognitionThreshold
Definition: validator.cpp:32
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< TestSetSingleResult > singleResults
Definition: validator.cpp:21
bool find(const std::vector< double > &in, double toFind)
Definition: validator.cpp:128
int main(int argc, char *argv[])
Definition: validator.cpp:143
std::string testSetName
Definition: validator.cpp:18
std::string frameId
std::string sceneModel
Definition: validator.cpp:33
std::string outputFile
Definition: validator.cpp:33
double recognitionThreshold
std::string frameId
Definition: validator.cpp:33
EvaluationResult evaluate(PatternNameToObjectSet ts, bool valid, const ModelParams &params)
Definition: validator.cpp:50
std::string invalidfile
Definition: validator.cpp:33
std::string validfile
Definition: validator.cpp:33
std::string sceneName
Definition: validator.cpp:11
bool getParam(const std::string &key, std::string &s) const
std::vector< TestSetCompleteResult > testSetResults
Definition: validator.cpp:27
double sigma
Definition: validator.cpp:32
double scale
double averageRecognitionRuntime
Definition: validator.cpp:26
std::map< std::string, std::vector< ObjectSetPtr > > PatternNameToObjectSet
Definition: validator.cpp:7


asr_psm
Author(s): Braun Kai, Gehrung Joachim, Heizmann Heinrich, Meißner Pascal
autogenerated on Fri Nov 15 2019 04:00:08