tools/Report/main.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <rtabmap/core/DBDriver.h>
29 #include <rtabmap/core/Graph.h>
30 #include <rtabmap/core/Optimizer.h>
32 #include <rtabmap/utilite/UFile.h>
33 #include <rtabmap/utilite/UStl.h>
34 #include <rtabmap/utilite/UMath.h>
35 #include <rtabmap/utilite/UPlot.h>
37 #include <QApplication>
38 #include <stdio.h>
39 
40 using namespace rtabmap;
41 
42 void showUsage()
43 {
44  printf("\nUsage:\n"
45  "rtabmap-report [\"Statistic/Id\"] [--latex] [--kitti] [--scale] [--poses] path\n"
46  " path Directory containing rtabmap databases or path of a database.\n"
47  " --latex Print table formatted in LaTeX with results.\n"
48  " --kitti Compute error based on KITTI benchmark.\n"
49  " --scale Find the best scale for the map against the ground truth\n"
50  " and compute error based on the scaled path.\n"
51  " --poses Export poses to [path]_poses.txt, ground truth to [path]_gt.txt\n"
52  " and valid ground truth indices to [path]_indices.txt \n\n");
53  exit(1);
54 }
55 
56 int main(int argc, char * argv[])
57 {
58  if(argc < 2)
59  {
60  showUsage();
61  }
62 
65 
66  QApplication app(argc, argv);
67 
68  bool outputLatex = false;
69  bool outputScaled = false;
70  bool outputPoses = false;
71  bool outputKittiError = false;
72  std::map<std::string, UPlot*> figures;
73  for(int i=1; i<argc-1; ++i)
74  {
75  if(strcmp(argv[i], "--latex") == 0)
76  {
77  outputLatex = true;
78  }
79  else if(strcmp(argv[i], "--kitti") == 0)
80  {
81  outputKittiError = true;
82  }
83  else if(strcmp(argv[i], "--scale") == 0)
84  {
85  outputScaled = true;
86  }
87  else if(strcmp(argv[i], "--poses") == 0)
88  {
89  outputPoses = true;
90  }
91  else
92  {
93  std::string figureTitle = argv[i];
94  printf("Plot %s\n", figureTitle.c_str());
95  UPlot * fig = new UPlot();
96  fig->setTitle(figureTitle.c_str());
97  fig->setXLabel("Time (s)");
98  figures.insert(std::make_pair(figureTitle, fig));
99  }
100  }
101 
102  std::string path = argv[argc-1];
103  path = uReplaceChar(path, '~', UDirectory::homeDir());
104 
105  std::string fileName;
106  std::list<std::string> paths;
107  paths.push_back(path);
108  std::vector<std::map<std::string, std::vector<float> > > outputLatexStatistics;
109  std::map<std::string, std::vector<float> > outputLatexStatisticsMap;
110  bool odomRAMSet = false;
111  std::set<std::string> topDirs;
112  while(paths.size())
113  {
114  std::string currentPath = paths.front();
115  UDirectory currentDir(currentPath);
116  paths.pop_front();
117  bool currentPathIsDatabase = false;
118  if(!currentDir.isValid())
119  {
120  if(UFile::getExtension(currentPath).compare("db") == 0)
121  {
122  currentPathIsDatabase=true;
123  printf("Database: %s\n", currentPath.c_str());
124  }
125  else
126  {
127  continue;
128  }
129  }
130  std::list<std::string> subDirs;
131  if(!currentPathIsDatabase)
132  {
133  printf("Directory: %s\n", currentPath.c_str());
134  std::list<std::string> fileNames = currentDir.getFileNames();
135  if(topDirs.empty())
136  {
137  for(std::list<std::string>::iterator iter = fileNames.begin(); iter!=fileNames.end(); ++iter)
138  {
139  topDirs.insert(currentPath+"/"+*iter);
140  }
141  }
142  else
143  {
144  if(topDirs.find(currentPath) != topDirs.end())
145  {
146  if(outputLatexStatisticsMap.size())
147  {
148  outputLatexStatistics.push_back(outputLatexStatisticsMap);
149  outputLatexStatisticsMap.clear();
150  }
151  }
152  }
153  }
154 
155  while(currentPathIsDatabase || !(fileName = currentDir.getNextFileName()).empty())
156  {
157  if(currentPathIsDatabase || UFile::getExtension(fileName).compare("db") == 0)
158  {
159  std::string filePath;
160  if(currentPathIsDatabase)
161  {
162  filePath = currentPath;
163  }
164  else
165  {
166  filePath = currentPath + UDirectory::separator() + fileName;
167  }
168 
169  DBDriver * driver = DBDriver::create();
170  ParametersMap params;
171  if(driver->openConnection(filePath))
172  {
173  ULogger::setLevel(ULogger::kError); // to suppress parameter warnings
174  params = driver->getLastParameters();
176  std::set<int> ids;
177  driver->getAllNodeIds(ids);
178  std::map<int, std::pair<std::map<std::string, float>, double> > stats = driver->getAllStatistics();
179  std::map<int, Transform> odomPoses, gtPoses;
180  std::vector<float> cameraTime;
181  cameraTime.reserve(ids.size());
182  std::vector<float> odomTime;
183  odomTime.reserve(ids.size());
184  std::vector<float> slamTime;
185  slamTime.reserve(ids.size());
186  float rmse = -1;
187  float maxRMSE = -1;
188  float maxOdomRAM = -1;
189  float maxMapRAM = -1;
190  std::map<std::string, UPlotCurve*> curves;
191  std::map<std::string, double> firstStamps;
192  for(std::map<std::string, UPlot*>::iterator iter=figures.begin(); iter!=figures.end(); ++iter)
193  {
194  curves.insert(std::make_pair(iter->first, iter->second->addCurve(filePath.c_str())));
195  }
196 
197  for(std::set<int>::iterator iter=ids.begin(); iter!=ids.end(); ++iter)
198  {
199  Transform p, gt;
200  GPS gps;
201  int m=-1, w=-1;
202  std::string l;
203  double s;
204  std::vector<float> v;
205  if(driver->getNodeInfo(*iter, p, m, w, l, s, gt, v, gps))
206  {
207  odomPoses.insert(std::make_pair(*iter, p));
208  if(!gt.isNull())
209  {
210  gtPoses.insert(std::make_pair(*iter, gt));
211  }
212  if(uContains(stats, *iter))
213  {
214  const std::map<std::string, float> & stat = stats.at(*iter).first;
215  if(uContains(stat, Statistics::kGtTranslational_rmse()))
216  {
217  rmse = stat.at(Statistics::kGtTranslational_rmse());
218  if(maxRMSE==-1 || maxRMSE < rmse)
219  {
220  maxRMSE = rmse;
221  }
222  }
223  if(uContains(stat, std::string("Camera/TotalTime/ms")))
224  {
225  cameraTime.push_back(stat.at(std::string("Camera/TotalTime/ms")));
226  }
227  if(uContains(stat, std::string("Odometry/TotalTime/ms")))
228  {
229  odomTime.push_back(stat.at(std::string("Odometry/TotalTime/ms")));
230  }
231 
232  if(uContains(stat, std::string("RtabmapROS/TotalTime/ms")))
233  {
234  if(w>=0 || stat.at("RtabmapROS/TotalTime/ms") > 10.0f)
235  {
236  slamTime.push_back(stat.at("RtabmapROS/TotalTime/ms"));
237  }
238  }
239  else if(uContains(stat, Statistics::kTimingTotal()))
240  {
241  if(w>=0 || stat.at(Statistics::kTimingTotal()) > 10.0f)
242  {
243  slamTime.push_back(stat.at(Statistics::kTimingTotal()));
244  }
245  }
246 
247  if(uContains(stat, std::string(Statistics::kMemoryRAM_usage())))
248  {
249  float ram = stat.at(Statistics::kMemoryRAM_usage());
250  if(maxMapRAM==-1 || maxMapRAM < ram)
251  {
252  maxMapRAM = ram;
253  }
254  }
255  if(uContains(stat, std::string("Odometry/RAM_usage/MB")))
256  {
257  float ram = stat.at("Odometry/RAM_usage/MB");
258  if(maxOdomRAM==-1 || maxOdomRAM < ram)
259  {
260  maxOdomRAM = ram;
261  }
262  }
263 
264  for(std::map<std::string, UPlotCurve*>::iterator jter=curves.begin(); jter!=curves.end(); ++jter)
265  {
266  if(uContains(stat, jter->first))
267  {
268  if(!uContains(firstStamps, jter->first))
269  {
270  firstStamps.insert(std::make_pair(jter->first, s));
271  }
272  float x = s - firstStamps.at(jter->first);
273  float y = stat.at(jter->first);
274  jter->second->addValue(x,y);
275  }
276  }
277  }
278  }
279  }
280 
281  std::multimap<int, Link> links;
282  driver->getAllLinks(links, true);
283  std::multimap<int, Link> loopClosureLinks;
284  for(std::multimap<int, Link>::iterator jter=links.begin(); jter!=links.end(); ++jter)
285  {
286  if(jter->second.type() == Link::kGlobalClosure &&
287  graph::findLink(loopClosureLinks, jter->second.from(), jter->second.to()) == loopClosureLinks.end())
288  {
289  loopClosureLinks.insert(*jter);
290  }
291  }
292 
293  float bestScale = 1.0f;
294  float bestRMSE = -1;
295  float bestRMSEAng = -1;
296  float bestVoRMSE = -1;
297  Transform bestGtToMap = Transform::getIdentity();
298  float kitti_t_err = 0.0f;
299  float kitti_r_err = 0.0f;
300  if(ids.size())
301  {
302  std::map<int, Transform> posesOut;
303  std::multimap<int, Link> linksOut;
304  int firstId = *ids.begin();
305  rtabmap::Optimizer * optimizer = rtabmap::Optimizer::create(params);
306  optimizer->getConnectedGraph(firstId, odomPoses, graph::filterDuplicateLinks(links), posesOut, linksOut);
307 
308  std::map<int, Transform> poses = optimizer->optimize(firstId, posesOut, linksOut);
309  if(poses.empty())
310  {
311  // try incremental optimization
312  UWARN("Optimization failed! Try incremental optimization...");
313  poses = optimizer->optimizeIncremental(firstId, posesOut, linksOut);
314  if(poses.empty())
315  {
316  UERROR("Incremental optimization also failed! Only original RMSE will be shown.");
317  bestRMSE = rmse;
318  }
319  else
320  {
321  UWARN("Incremental optimization succeeded!");
322  }
323  }
324 
325  if(poses.size())
326  {
327  std::map<int, Transform> groundTruth;
328  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
329  {
330  if(gtPoses.find(iter->first) != gtPoses.end())
331  {
332  groundTruth.insert(*gtPoses.find(iter->first));
333  }
334  }
335 
336  outputScaled = outputScaled && groundTruth.size();
337  for(float scale=outputScaled?0.900f:1.0f; scale<1.100f; scale+=0.001)
338  {
339  std::map<int, Transform> scaledPoses;
340  std::map<int, Transform> scaledOdomPoses;
341 
342  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
343  {
344  Transform t = iter->second.clone();
345  t.x() *= scale;
346  t.y() *= scale;
347  t.z() *= scale;
348  scaledPoses.insert(std::make_pair(iter->first, t));
349 
350  UASSERT(posesOut.find(iter->first)!=posesOut.end());
351  t = posesOut.at(iter->first).clone();
352  t.x() *= scale;
353  t.y() *= scale;
354  t.z() *= scale;
355  scaledOdomPoses.insert(std::make_pair(iter->first, t));
356  }
357  // compute RMSE statistics
358  float translational_rmse = 0.0f;
359  float translational_mean = 0.0f;
360  float translational_median = 0.0f;
361  float translational_std = 0.0f;
362  float translational_min = 0.0f;
363  float translational_max = 0.0f;
364  float rotational_rmse = 0.0f;
365  float rotational_mean = 0.0f;
366  float rotational_median = 0.0f;
367  float rotational_std = 0.0f;
368  float rotational_min = 0.0f;
369  float rotational_max = 0.0f;
370 
372  groundTruth,
373  scaledOdomPoses,
374  translational_rmse,
375  translational_mean,
376  translational_median,
377  translational_std,
378  translational_min,
379  translational_max,
380  rotational_rmse,
381  rotational_mean,
382  rotational_median,
383  rotational_std,
384  rotational_min,
385  rotational_max);
386  float translational_rmse_vo = translational_rmse;
387 
388  Transform gtToMap = graph::calcRMSE(
389  groundTruth,
390  scaledPoses,
391  translational_rmse,
392  translational_mean,
393  translational_median,
394  translational_std,
395  translational_min,
396  translational_max,
397  rotational_rmse,
398  rotational_mean,
399  rotational_median,
400  rotational_std,
401  rotational_min,
402  rotational_max);
403 
404  if(bestRMSE!=-1 && translational_rmse > bestRMSE)
405  {
406  break;
407  }
408  bestRMSE = translational_rmse;
409  bestVoRMSE = translational_rmse_vo;
410  bestRMSEAng = rotational_rmse;
411  bestScale = scale;
412  bestGtToMap = gtToMap;
413  if(!outputScaled)
414  {
415  // just did iteration without any scale, then exit
416  break;
417  }
418  }
419 
420  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
421  {
422  iter->second.x()*=bestScale;
423  iter->second.y()*=bestScale;
424  iter->second.z()*=bestScale;
425  iter->second = bestGtToMap * iter->second;
426  }
427 
428  if(outputKittiError)
429  {
430  if(groundTruth.size() == poses.size())
431  {
432  // compute KITTI statistics
433  graph::calcKittiSequenceErrors(uValues(groundTruth), uValues(poses), kitti_t_err, kitti_r_err);
434  }
435  else
436  {
437  printf("Cannot compute KITTI statistics as optimized poses and ground truth don't have the same size (%d vs %d).\n",
438  (int)poses.size(), (int)groundTruth.size());
439  }
440  }
441 
442  if(outputPoses)
443  {
444  std::string dir = UDirectory::getDir(filePath);
445  std::string dbName = UFile::getName(filePath);
446  dbName = dbName.substr(0, dbName.size()-3); // remove db
447  std::string path = dir+UDirectory::separator()+dbName+"_poses.txt";
448  if(!graph::exportPoses(path, outputKittiError?2:0, poses))
449  {
450  printf("Could not export the poses to \"%s\"!?!\n", path.c_str());
451  }
452  if(groundTruth.size())
453  {
454  // For missing ground truth poses, set them to null
455  std::vector<int> validIndices(poses.size(), 1);
456  int i=0;
457  for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter, ++i)
458  {
459  if(groundTruth.find(iter->first) == groundTruth.end())
460  {
461  groundTruth.insert(std::make_pair(iter->first, Transform()));
462  validIndices[i] = 0;
463  }
464  }
465  path = dir+UDirectory::separator()+dbName+"_gt.txt";
466  if(!graph::exportPoses(path, outputKittiError?2:0, groundTruth))
467  {
468  printf("Could not export the ground truth to \"%s\"!?!\n", path.c_str());
469  }
470  else
471  {
472  // save valid indices
473  path = dir+UDirectory::separator()+dbName+"_indices.txt";
474  FILE * file = 0;
475  #ifdef _MSC_VER
476  fopen_s(&file, path.c_str(), "w");
477  #else
478  file = fopen(path.c_str(), "w");
479  #endif
480  if(file)
481  {
482  // VERTEX3 id x y z phi theta psi
483  for(unsigned int k=0; k<validIndices.size(); ++k)
484  {
485  fprintf(file, "%d\n", validIndices[k]);
486  }
487  fclose(file);
488  }
489  }
490  }
491  }
492  }
493  }
494  printf(" %s (%d, s=%.3f):\terror lin=%.3fm (max=%.3fm, odom=%.3fm) ang=%.1fdeg%s, slam: avg=%dms (max=%dms) loops=%d, odom: avg=%dms (max=%dms), camera: avg=%dms, %smap=%dMB\n",
495  fileName.c_str(),
496  (int)ids.size(),
497  bestScale,
498  bestRMSE,
499  maxRMSE,
500  bestVoRMSE,
501  bestRMSEAng,
502  !outputKittiError?"":uFormat(", KITTI: t_err=%.2f%% r_err=%.2f deg/100m", kitti_t_err, kitti_r_err*100).c_str(),
503  (int)uMean(slamTime), (int)uMax(slamTime),
504  (int)loopClosureLinks.size(),
505  (int)uMean(odomTime), (int)uMax(odomTime),
506  (int)uMean(cameraTime),
507  maxOdomRAM!=-1.0f?uFormat("RAM odom=%dMB ", (int)maxOdomRAM).c_str():"",
508  (int)maxMapRAM);
509 
510  if(outputLatex)
511  {
512  std::vector<float> stats;
513  stats.push_back(ids.size());
514  stats.push_back(bestRMSE);
515  stats.push_back(maxRMSE);
516  stats.push_back(bestRMSEAng);
517  stats.push_back(uMean(odomTime));
518  stats.push_back(uMean(slamTime));
519  stats.push_back(uMax(slamTime));
520  stats.push_back(maxOdomRAM);
521  stats.push_back(maxMapRAM);
522  outputLatexStatisticsMap.insert(std::make_pair(filePath, stats));
523 
524  if(maxOdomRAM != -1.0f)
525  {
526  odomRAMSet = true;
527  }
528  }
529  }
530  driver->closeConnection();
531  delete driver;
532  }
533  else if(uSplit(fileName, '.').size() == 1)
534  {
535  //sub directory
536  subDirs.push_front(currentPath + UDirectory::separator() + fileName);
537  }
538  currentPathIsDatabase = false;
539  }
540 
541  for(std::list<std::string>::iterator iter=subDirs.begin(); iter!=subDirs.end(); ++iter)
542  {
543  paths.push_front(*iter);
544  }
545 
546  if(outputLatexStatisticsMap.size() && paths.empty())
547  {
548  outputLatexStatistics.push_back(outputLatexStatisticsMap);
549  outputLatexStatisticsMap.clear();
550  }
551  }
552 
553  if(outputLatex && outputLatexStatistics.size())
554  {
555  printf("\nLaTeX output:\n----------------\n");
556  printf("\\begin{table*}[!t]\n");
557  printf("\\caption{$t_{end}$ is the absolute translational RMSE value at the end "
558  "of the experiment as $ATE_{max}$ is the maximum during the experiment. "
559  "$r_{end}$ is rotational RMSE value at the end of the experiment. "
560  "$o_{avg}$ and $m_{avg}$ are the average computational time "
561  "for odometry (front-end) and map update (back-end). "
562  "$m_{avg}$ is the maximum computational time for map update. "
563  "$O_{end}$ and $M_{end}$ are the RAM usage at the end of the experiment "
564  "for odometry and map management respectively.}\n");
565  printf("\\label{}\n");
566  printf("\\centering\n");
567  if(odomRAMSet)
568  {
569  printf("\\begin{tabular}{l|c|c|c|c|c|c|c|c|c}\n");
570  printf("\\cline{2-10}\n");
571  printf(" & Size & $t_{end}$ & $t_{max}$ & $r_{end}$ & $o_{avg}$ & $m_{avg}$ & $m_{max}$ & $O_{end}$ & $M_{end}$ \\\\\n");
572  printf(" & (nodes) & (m) & (m) & (deg) & (ms) & (ms) & (ms) & (MB) & (MB) \\\\\n");
573  }
574  else
575  {
576  printf("\\begin{tabular}{l|c|c|c|c|c|c|c|c}\n");
577  printf("\\cline{2-9}\n");
578  printf(" & Size & $t_{end}$ & $t_{max}$ & $r_{end}$ & $o_{avg}$ & $m_{avg}$ & $m_{max}$ & $M_{end}$ \\\\\n");
579  printf(" & (nodes) & (m) & (m) & (deg) & (ms) & (ms) & (ms) & (MB) \\\\\n");
580  }
581 
582  printf("\\hline\n");
583 
584  for(unsigned int j=0; j<outputLatexStatistics.size(); ++j)
585  {
586  if(outputLatexStatistics[j].size())
587  {
588  std::vector<int> lowestIndex;
589  if(outputLatexStatistics[j].size() > 1)
590  {
591  std::vector<float> lowestValue(outputLatexStatistics[j].begin()->second.size(),-1);
592  lowestIndex = std::vector<int>(lowestValue.size(),0);
593  int index = 0;
594  for(std::map<std::string, std::vector<float> >::iterator iter=outputLatexStatistics[j].begin(); iter!=outputLatexStatistics[j].end(); ++iter)
595  {
596  UASSERT(lowestValue.size() == iter->second.size());
597  for(unsigned int i=0; i<iter->second.size(); ++i)
598  {
599  if(lowestValue[i] == -1 || (iter->second[i]>0.0f && lowestValue[i]>iter->second[i]))
600  {
601  lowestValue[i] = iter->second[i];
602  lowestIndex[i] = index;
603  }
604  }
605  ++index;
606  }
607  }
608 
609  int index = 0;
610  for(std::map<std::string, std::vector<float> >::iterator iter=outputLatexStatistics[j].begin(); iter!=outputLatexStatistics[j].end(); ++iter)
611  {
612  UASSERT(iter->second.size() == 9);
613  printf("%s & ", uReplaceChar(iter->first.c_str(), '_', '-').c_str());
614  printf("%d & ", (int)iter->second[0]);
615  printf("%s%.3f%s & ", lowestIndex.size()&&lowestIndex[1]==index?"\\textbf{":"", iter->second[1], lowestIndex.size()&&lowestIndex[1]==index?"}":"");
616  printf("%s%.3f%s & ", lowestIndex.size()&&lowestIndex[2]==index?"\\textbf{":"", iter->second[2], lowestIndex.size()&&lowestIndex[2]==index?"}":"");
617  printf("%s%.2f%s & ", lowestIndex.size()&&lowestIndex[3]==index?"\\textbf{":"", iter->second[3], lowestIndex.size()&&lowestIndex[3]==index?"}":"");
618  printf("%s%d%s & ", lowestIndex.size()&&lowestIndex[4]==index?"\\textbf{":"", (int)iter->second[4], lowestIndex.size()&&lowestIndex[4]==index?"}":"");
619  printf("%s%d%s & ", lowestIndex.size()&&lowestIndex[5]==index?"\\textbf{":"", (int)iter->second[5], lowestIndex.size()&&lowestIndex[5]==index?"}":"");
620  printf("%s%d%s & ", lowestIndex.size()&&lowestIndex[6]==index?"\\textbf{":"", (int)iter->second[6], lowestIndex.size()&&lowestIndex[6]==index?"}":"");
621  if(odomRAMSet)
622  {
623  printf("%s%d%s & ", lowestIndex.size()&&lowestIndex[7]==index?"\\textbf{":"", (int)iter->second[7], lowestIndex.size()&&lowestIndex[7]==index?"}":"");
624  }
625  printf("%s%d%s ", lowestIndex.size()&&lowestIndex[8]==index?"\\textbf{":"", (int)iter->second[8], lowestIndex.size()&&lowestIndex[8]==index?"}":"");
626  printf("\\\\\n");
627  ++index;
628  }
629  printf("\\hline\n");
630  }
631  }
632 
633  printf("\\end{tabular}\n");
634  printf("\\end{table*}\n----------------\n");
635  }
636 
637  if(figures.size())
638  {
639  for(std::map<std::string, UPlot*>::iterator iter=figures.begin(); iter!=figures.end(); ++iter)
640  {
641  iter->second->show();
642  }
643  return app.exec();
644  }
645  return 0;
646 }
static std::string homeDir()
Definition: UDirectory.cpp:355
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), bool g2oRobust=false)
Definition: Graph.cpp:53
T uMean(const T *v, unsigned int size)
Definition: UMath.h:401
std::string getName()
Definition: UFile.h:135
bool isValid()
Definition: UDirectory.cpp:216
f
const std::list< std::string > & getFileNames() const
Definition: UDirectory.h:129
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
Definition: DBDriver.cpp:813
static std::string getDir(const std::string &filePath)
Definition: UDirectory.cpp:273
static Transform getIdentity()
Definition: Transform.cpp:364
static std::string separator()
Definition: UDirectory.cpp:391
void getAllLinks(std::multimap< int, Link > &links, bool ignoreNullLinks=true) const
Definition: DBDriver.cpp:852
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
Basic mathematics functions.
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps) const
Definition: DBDriver.cpp:727
std::string getExtension()
Definition: UFile.h:140
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
std::multimap< int, Link > RTABMAP_EXP filterDuplicateLinks(const std::multimap< int, Link > &links)
Definition: Graph.cpp:952
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
Definition: UPlot.h:483
void showUsage()
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::map< int, Transform > optimizeIncremental(int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints, std::list< std::map< int, Transform > > *intermediateGraphes=0, double *finalError=0, int *iterationsDone=0)
Definition: Optimizer.cpp:266
bool isNull() const
Definition: Transform.cpp:107
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
std::map< int, Transform > optimize(int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints, std::list< std::map< int, Transform > > *intermediateGraphes=0, double *finalError=0, int *iterationsDone=0)
Definition: Optimizer.cpp:331
std::map< int, std::pair< std::map< std::string, float >, double > > getAllStatistics() const
Definition: DBDriver.cpp:257
Transform RTABMAP_EXP calcRMSE(const std::map< int, Transform > &groundTruth, const std::map< int, Transform > &poses, float &translational_rmse, float &translational_mean, float &translational_median, float &translational_std, float &translational_min, float &translational_max, float &rotational_rmse, float &rotational_mean, float &rotational_median, float &rotational_std, float &rotational_min, float &rotational_max)
Definition: Graph.cpp:684
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:32
static RTABMapApp app
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:409
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
T uMax(const T *v, unsigned int size, unsigned int &index)
Definition: UMath.h:94
std::vector< V > uValues(const std::multimap< K, V > &mm)
Definition: UStl.h:100
std::string getNextFileName()
Definition: UDirectory.cpp:221
std::multimap< int, Link >::iterator RTABMAP_EXP findLink(std::multimap< int, Link > &links, int from, int to, bool checkBothWays=true)
Definition: Graph.cpp:825
#define UERROR(...)
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
ULogger class and convenient macros.
#define UWARN(...)
int main(int argc, char *argv[])
static void getConnectedGraph(int fromId, const std::map< int, Transform > &posesIn, const std::multimap< int, Link > &linksIn, std::map< int, Transform > &posesOut, std::multimap< int, Link > &linksOut, int depth=0)
Definition: Optimizer.cpp:157
Transform clone() const
Definition: Transform.cpp:102
std::string UTILITE_EXP uFormat(const char *fmt,...)
static Optimizer * create(const ParametersMap &parameters)
Definition: Optimizer.cpp:67
void RTABMAP_EXP calcKittiSequenceErrors(const std::vector< Transform > &poses_gt, const std::vector< Transform > &poses_result, float &t_err, float &r_err)
Definition: Graph.cpp:616


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31