1 #include <ISM/utility/TableHelper.hpp> 39 TableHelperPtr localTableHelper(
new TableHelper(fileName));
41 for (
auto patternName: localTableHelper->getRecordedPatternNames())
42 testSet[patternName] = localTableHelper->getRecordedPattern(patternName)->objectSets;
44 }
catch (soci::soci_error& se) {
45 std::cerr <<
"Soci error " << se.what() << std::endl;
54 double fullRecognitionRuntime = 0;
56 for (std::pair<std::string, std::vector<ObjectSetPtr>> testSetsByPattern: ts)
59 if (!valid) in =
"in";
60 std::cout <<
"Evaluating " << testSetsByPattern.second.size() <<
" " << in <<
"valid test sets for pattern " << testSetsByPattern.first << std::endl;
65 for (
unsigned int testSetNumber = 0; testSetNumber < testSetsByPattern.second.size(); testSetNumber++)
67 ObjectSetPtr testSet = testSetsByPattern.second[testSetNumber];
68 std::vector<SceneIdentifier> sceneList;
74 model->loadModelFromFile(params.
sceneModel,
"maximum");
75 model->initializeVisualizer(mVisualizer);
78 gettimeofday(&start, NULL);
80 for (
unsigned int i = 0; i < testSet->objects.size(); i++)
83 model->integrateEvidence(
object);
87 model->getSceneListWithProbabilities(sceneList);
89 gettimeofday(&end, NULL);
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;
97 std::string validity =
"v";
98 if (!valid) validity =
"i";
99 std::string testSetName = testSetsByPattern.first +
"_" + validity +
"_" + std::to_string(testSetNumber);
108 double probability = sceneIdentifier.mLikelihood;
110 tssr.
sceneName = sceneIdentifier.mDescription;
128 bool find(
const std::vector<double>& in,
double toFind)
132 if (std::abs(i - toFind) < std::numeric_limits<double>::epsilon())
143 int main(
int argc,
char *argv[])
152 throw std::runtime_error(
"Please specifiy parameter recognition_threshold when starting this node.");
155 throw std::runtime_error(
"Please specifiy parameter valid_testset_db_filename when starting this node.");
157 throw std::runtime_error(
"Please specifiy parameter invalid_testset_db_filename when starting this node.");
159 throw std::runtime_error(
"Please specifiy parameter scene_model when starting this node.");
161 throw std::runtime_error(
"Please specifiy parameter output_file when starting this node.");
163 throw std::runtime_error(
"Please specifiy parameter base_frame_id when starting this node.");
165 throw std::runtime_error(
"Please specifiy parameter scale_factor when starting this node.");
167 throw std::runtime_error(
"Please specifiy parameter sigma_multiplicator when starting this node.");
188 throw std::runtime_error(
"List size not equal");
191 throw std::runtime_error(
"Order in list not equal.");
194 std::stringstream csv;
196 csv <<
"testset; recognition runtime;";
207 struct FalseRecognition
209 unsigned int number = 0;
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;
218 double recognitionRuntimeSum = 0;
252 unsigned int numberOfValidTestSets = validER.
testSetResults.size();
253 unsigned int numberOfInvalidTestSets = invalidER.
testSetResults.size();
255 std::stringstream avgprobs, avgvalp, avginvp, avgfp, avgfpi, avgfpr, avgfn, avgfnv, avgfnr, avgfr, ts, avgfrr;
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)) <<
"; ";
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;
285 std::ofstream csvfile;
287 if (!csvfile.is_open())
288 throw std::invalid_argument(
"Could not open file " + mp.
outputFile);
289 csvfile << csv.str();
292 std::cout <<
"Wrote evaluation result to file " << mp.
outputFile << std::endl;
PatternNameToObjectSet loadTestSetsFromDB(std::string fileName)
double recognitionThreshold
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< TestSetSingleResult > singleResults
bool find(const std::vector< double > &in, double toFind)
int main(int argc, char *argv[])
double recognitionRuntime
EvaluationResult evaluate(PatternNameToObjectSet ts, bool valid, const ModelParams ¶ms)
bool getParam(const std::string &key, std::string &s) const
std::vector< TestSetCompleteResult > testSetResults
double averageRecognitionRuntime
std::map< std::string, std::vector< ObjectSetPtr > > PatternNameToObjectSet