tools/RgbdDataset/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 
29 #include "rtabmap/core/Rtabmap.h"
32 #include "rtabmap/core/Graph.h"
35 #include "rtabmap/core/Memory.h"
39 #include "rtabmap/utilite/UFile.h"
40 #include "rtabmap/utilite/UMath.h"
41 #include "rtabmap/utilite/UStl.h"
43 #include <pcl/common/common.h>
44 #include <stdio.h>
45 #include <signal.h>
46 
47 using namespace rtabmap;
48 
49 void showUsage()
50 {
51  printf("\nUsage:\n"
52  "rtabmap-rgbd_dataset [options] path\n"
53  " path Folder of the sequence (e.g., \"~/rgbd_dataset_freiburg3_long_office_household\")\n"
54  " containing least rgb_sync and depth_sync folders. These folders contain\n"
55  " synchronized images using associate.py tool (use tool version from\n"
56  " https://gist.github.com/matlabbe/484134a2d9da8ad425362c6669824798). If \n"
57  " \"groundtruth.txt\" is found in the sequence folder, they will be saved in the database.\n"
58  " --output Output directory. By default, results are saved in \"path\".\n"
59  " --output_name Output database name (default \"rtabmap\").\n"
60  " --quiet Don't show log messages and iteration updates.\n"
61  "%s\n"
62  "Example:\n\n"
63  " $ rtabmap-rgbd_dataset \\\n"
64  " --Rtabmap/PublishRAMUsage true\\\n"
65  " --Rtabmap/DetectionRate 2\\\n"
66  " --RGBD/LinearUpdate 0\\\n"
67  " --Mem/STMSize 30\\\n"
68  " ~/rgbd_dataset_freiburg3_long_office_household\n\n", rtabmap::Parameters::showUsage());
69  exit(1);
70 }
71 
72 // catch ctrl-c
73 bool g_forever = true;
74 void sighandler(int sig)
75 {
76  printf("\nSignal %d caught...\n", sig);
77  g_forever = false;
78 }
79 
80 int main(int argc, char * argv[])
81 {
82  signal(SIGABRT, &sighandler);
83  signal(SIGTERM, &sighandler);
84  signal(SIGINT, &sighandler);
85 
88 
89  ParametersMap parameters;
90  std::string path;
91  std::string output;
92  std::string outputName = "rtabmap";
93  bool quiet = false;
94  if(argc < 2)
95  {
96  showUsage();
97  }
98  else
99  {
100  for(int i=1; i<argc; ++i)
101  {
102  if(std::strcmp(argv[i], "--output") == 0)
103  {
104  output = argv[++i];
105  }
106  else if(std::strcmp(argv[i], "--output_name") == 0)
107  {
108  outputName = argv[++i];
109  }
110  else if(std::strcmp(argv[i], "--quiet") == 0)
111  {
112  quiet = true;
113  }
114  }
115  parameters = Parameters::parseArguments(argc, argv);
116  path = argv[argc-1];
117  path = uReplaceChar(path, '~', UDirectory::homeDir());
118  path = uReplaceChar(path, '\\', '/');
119  if(output.empty())
120  {
121  output = path;
122  }
123  else
124  {
125  output = uReplaceChar(output, '~', UDirectory::homeDir());
126  UDirectory::makeDir(output);
127  }
128  parameters.insert(ParametersPair(Parameters::kRtabmapWorkingDirectory(), output));
129  parameters.insert(ParametersPair(Parameters::kRtabmapPublishRAMUsage(), "true"));
130  }
131 
132  std::string seq = uSplit(path, '/').back();
133  std::string pathRgbImages = path+"/rgb_sync";
134  std::string pathDepthImages = path+"/depth_sync";
135  std::string pathGt = path+"/groundtruth.txt";
136  if(!UFile::exists(pathGt))
137  {
138  UWARN("Ground truth file path doesn't exist: \"%s\", benchmark values won't be computed.", pathGt.c_str());
139  pathGt.clear();
140  }
141 
142  if(quiet)
143  {
145  }
146 
147  printf("Paths:\n"
148  " Dataset name: %s\n"
149  " Dataset path: %s\n"
150  " RGB path: %s\n"
151  " Depth path: %s\n"
152  " Output: %s\n"
153  " Output name: %s\n",
154  seq.c_str(),
155  path.c_str(),
156  pathRgbImages.c_str(),
157  pathDepthImages.c_str(),
158  output.c_str(),
159  outputName.c_str());
160  if(!pathGt.empty())
161  {
162  printf(" groundtruth.txt: %s\n", pathGt.c_str());
163  }
164  if(!parameters.empty())
165  {
166  printf("Parameters:\n");
167  for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
168  {
169  printf(" %s=%s\n", iter->first.c_str(), iter->second.c_str());
170  }
171  }
172  printf("RTAB-Map version: %s\n", RTABMAP_VERSION);
173 
174  // setup calibration file
175  CameraModel model;
176  std::string sequenceName = UFile(path).getName();
177  Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
178  float depthFactor = 5.0f;
179  if(sequenceName.find("freiburg1") != std::string::npos)
180  {
181  model = CameraModel(outputName+"_calib", 517.3, 516.5, 318.6, 255.3, opticalRotation, 0, cv::Size(640,480));
182  }
183  else if(sequenceName.find("freiburg2") != std::string::npos)
184  {
185  model = CameraModel(outputName+"_calib", 520.9, 521.0, 325.1, 249.7, opticalRotation, 0, cv::Size(640,480));
186  }
187  else //if(sequenceName.find("freiburg3") != std::string::npos)
188  {
189  model = CameraModel(outputName+"_calib", 535.4, 539.2, 320.1, 247.6, opticalRotation, 0, cv::Size(640,480));
190  }
191  //parameters.insert(ParametersPair(Parameters::kg2oBaseline(), uNumber2Str(40.0f/model.fx())));
192  model.save(path);
193 
194  CameraThread cameraThread(new
196  pathRgbImages,
197  pathDepthImages,
198  depthFactor,
199  0.0f,
200  opticalRotation), parameters);
201  ((CameraRGBDImages*)cameraThread.camera())->setTimestamps(true, "", false);
202  if(!pathGt.empty())
203  {
204  ((CameraRGBDImages*)cameraThread.camera())->setGroundTruthPath(pathGt, 1);
205  }
206 
207  bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
208  float detectionRate = Parameters::defaultRtabmapDetectionRate();
209  int odomStrategy = Parameters::defaultOdomStrategy();
210  Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
211  Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
212  Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
213  std::string databasePath = output+"/"+outputName+".db";
214  UFile::erase(databasePath);
215  if(cameraThread.camera()->init(path, outputName+"_calib"))
216  {
217  int totalImages = (int)((CameraRGBDImages*)cameraThread.camera())->filenames().size();
218 
219  printf("Processing %d images...\n", totalImages);
220 
221  ParametersMap odomParameters = parameters;
222  odomParameters.erase(Parameters::kRtabmapPublishRAMUsage()); // as odometry is in the same process than rtabmap, don't get RAM usage in odometry.
223  Odometry * odom = Odometry::create(odomParameters);
225  rtabmap.init(parameters, databasePath);
226 
227  UTimer totalTime;
228  UTimer timer;
229  CameraInfo cameraInfo;
230  SensorData data = cameraThread.camera()->takeImage(&cameraInfo);
231  int iteration = 0;
232 
234  // Processing dataset begin
236  cv::Mat covariance;
237  int odomKeyFrames = 0;
238  double previousStamp = 0.0;
239  while(data.isValid() && g_forever)
240  {
241  cameraThread.postUpdate(&data, &cameraInfo);
242  cameraInfo.timeTotal = timer.ticks();
243 
244  OdometryInfo odomInfo;
245  Transform pose = odom->process(data, &odomInfo);
246 
247  if(odomStrategy == 2)
248  {
249  //special case for FOVIS, set covariance 1 if 9999 is detected
250  if(!odomInfo.reg.covariance.empty() && odomInfo.reg.covariance.at<double>(0,0) >= 9999)
251  {
252  odomInfo.reg.covariance = cv::Mat::eye(6,6,CV_64FC1);
253  }
254  }
255 
256  if(odomInfo.keyFrameAdded)
257  {
258  ++odomKeyFrames;
259  }
260 
261  bool processData = true;
262  if(detectionRate>0.0f &&
263  previousStamp>0.0 &&
264  data.stamp()>previousStamp && data.stamp() - previousStamp < 1.0/detectionRate)
265  {
266  processData = false;
267  }
268 
269  if(processData)
270  {
271  previousStamp = data.stamp();
272  }
273 
274  if(!processData)
275  {
276  // set negative id so rtabmap will detect it as an intermediate node
277  data.setId(-1);
278  data.setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());// remove features
279  processData = intermediateNodes;
280  }
281  if(covariance.empty() || odomInfo.reg.covariance.at<double>(0,0) > covariance.at<double>(0,0))
282  {
283  covariance = odomInfo.reg.covariance;
284  }
285 
286  timer.restart();
287  if(processData)
288  {
289  std::map<std::string, float> externalStats;
290  // save camera statistics to database
291  externalStats.insert(std::make_pair("Camera/BilateralFiltering/ms", cameraInfo.timeBilateralFiltering*1000.0f));
292  externalStats.insert(std::make_pair("Camera/Capture/ms", cameraInfo.timeCapture*1000.0f));
293  externalStats.insert(std::make_pair("Camera/Disparity/ms", cameraInfo.timeDisparity*1000.0f));
294  externalStats.insert(std::make_pair("Camera/ImageDecimation/ms", cameraInfo.timeImageDecimation*1000.0f));
295  externalStats.insert(std::make_pair("Camera/Mirroring/ms", cameraInfo.timeMirroring*1000.0f));
296  externalStats.insert(std::make_pair("Camera/ExposureCompensation/ms", cameraInfo.timeStereoExposureCompensation*1000.0f));
297  externalStats.insert(std::make_pair("Camera/ScanFromDepth/ms", cameraInfo.timeScanFromDepth*1000.0f));
298  externalStats.insert(std::make_pair("Camera/TotalTime/ms", cameraInfo.timeTotal*1000.0f));
299  externalStats.insert(std::make_pair("Camera/UndistortDepth/ms", cameraInfo.timeUndistortDepth*1000.0f));
300  // save odometry statistics to database
301  externalStats.insert(std::make_pair("Odometry/LocalBundle/ms", odomInfo.localBundleTime*1000.0f));
302  externalStats.insert(std::make_pair("Odometry/LocalBundleConstraints/", odomInfo.localBundleConstraints));
303  externalStats.insert(std::make_pair("Odometry/LocalBundleOutliers/", odomInfo.localBundleOutliers));
304  externalStats.insert(std::make_pair("Odometry/TotalTime/ms", odomInfo.timeEstimation*1000.0f));
305  externalStats.insert(std::make_pair("Odometry/Registration/ms", odomInfo.reg.totalTime*1000.0f));
306  externalStats.insert(std::make_pair("Odometry/Inliers/", odomInfo.reg.inliers));
307  externalStats.insert(std::make_pair("Odometry/Features/", odomInfo.features));
308  externalStats.insert(std::make_pair("Odometry/DistanceTravelled/m", odomInfo.distanceTravelled));
309  externalStats.insert(std::make_pair("Odometry/KeyFrameAdded/", odomInfo.keyFrameAdded));
310  externalStats.insert(std::make_pair("Odometry/LocalKeyFrames/", odomInfo.localKeyFrames));
311  externalStats.insert(std::make_pair("Odometry/LocalMapSize/", odomInfo.localMapSize));
312  externalStats.insert(std::make_pair("Odometry/LocalScanMapSize/", odomInfo.localScanMapSize));
313 
314  OdometryEvent e(SensorData(), Transform(), odomInfo);
315  rtabmap.process(data, pose, covariance, e.velocity(), externalStats);
316  covariance = cv::Mat();
317  }
318 
319  ++iteration;
320  if(!quiet || iteration == totalImages)
321  {
322  double slamTime = timer.ticks();
323 
324  float rmse = -1;
325  if(rtabmap.getStatistics().data().find(Statistics::kGtTranslational_rmse()) != rtabmap.getStatistics().data().end())
326  {
327  rmse = rtabmap.getStatistics().data().at(Statistics::kGtTranslational_rmse());
328  }
329 
330  if(rmse >= 0.0f)
331  {
332  //printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm, noise stddev=%fm %frad",
333  // iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse, sqrt(odomInfo.reg.covariance.at<double>(0,0)), sqrt(odomInfo.reg.covariance.at<double>(3,3)));
334  printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm",
335  iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse);
336  }
337  else
338  {
339  printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
340  iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f));
341  }
342  if(processData && rtabmap.getLoopClosureId()>0)
343  {
344  printf(" *");
345  }
346  printf("\n");
347  }
348  else if(iteration % (totalImages/10) == 0)
349  {
350  printf(".");
351  fflush(stdout);
352  }
353 
354  cameraInfo = CameraInfo();
355  timer.restart();
356  data = cameraThread.camera()->takeImage(&cameraInfo);
357  }
358  delete odom;
359  printf("Total time=%fs\n", totalTime.ticks());
361  // Processing dataset end
363 
364  // Save trajectory
365  printf("Saving trajectory...\n");
366  std::map<int, Transform> poses;
367  std::multimap<int, Link> links;
368  std::map<int, Signature> signatures;
369  std::map<int, double> stamps;
370  rtabmap.getGraph(poses, links, true, true, &signatures);
371  for(std::map<int, Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
372  {
373  stamps.insert(std::make_pair(iter->first, iter->second.getStamp()));
374  }
375  std::string pathTrajectory = output+"/"+outputName+"_poses.txt";
376  if(poses.size() && graph::exportPoses(pathTrajectory, 1, poses, links, stamps))
377  {
378  printf("Saving %s... done!\n", pathTrajectory.c_str());
379  }
380  else
381  {
382  printf("Saving %s... failed!\n", pathTrajectory.c_str());
383  }
384 
385  if(!pathGt.empty())
386  {
387  // Log ground truth statistics
388  std::map<int, Transform> groundTruth;
389 
390  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
391  {
392  Transform o, gtPose;
393  int m,w;
394  std::string l;
395  double s;
396  std::vector<float> v;
397  GPS gps;
398  rtabmap.getMemory()->getNodeInfo(iter->first, o, m, w, l, s, gtPose, v, gps, true);
399  if(!gtPose.isNull())
400  {
401  groundTruth.insert(std::make_pair(iter->first, gtPose));
402  }
403  }
404 
405 
406  // compute RMSE statistics
407  float translational_rmse = 0.0f;
408  float translational_mean = 0.0f;
409  float translational_median = 0.0f;
410  float translational_std = 0.0f;
411  float translational_min = 0.0f;
412  float translational_max = 0.0f;
413  float rotational_rmse = 0.0f;
414  float rotational_mean = 0.0f;
415  float rotational_median = 0.0f;
416  float rotational_std = 0.0f;
417  float rotational_min = 0.0f;
418  float rotational_max = 0.0f;
420  groundTruth,
421  poses,
422  translational_rmse,
423  translational_mean,
424  translational_median,
425  translational_std,
426  translational_min,
427  translational_max,
428  rotational_rmse,
429  rotational_mean,
430  rotational_median,
431  rotational_std,
432  rotational_min,
433  rotational_max);
434 
435  printf(" translational_rmse= %f m\n", translational_rmse);
436  printf(" rotational_rmse= %f deg\n", rotational_rmse);
437 
438  FILE * pFile = 0;
439  std::string pathErrors = output+"/"+outputName+"_rmse.txt";
440  pFile = fopen(pathErrors.c_str(),"w");
441  if(!pFile)
442  {
443  UERROR("could not save RMSE results to \"%s\"", pathErrors.c_str());
444  }
445  fprintf(pFile, "Ground truth comparison:\n");
446  fprintf(pFile, " translational_rmse= %f\n", translational_rmse);
447  fprintf(pFile, " translational_mean= %f\n", translational_mean);
448  fprintf(pFile, " translational_median= %f\n", translational_median);
449  fprintf(pFile, " translational_std= %f\n", translational_std);
450  fprintf(pFile, " translational_min= %f\n", translational_min);
451  fprintf(pFile, " translational_max= %f\n", translational_max);
452  fprintf(pFile, " rotational_rmse= %f\n", rotational_rmse);
453  fprintf(pFile, " rotational_mean= %f\n", rotational_mean);
454  fprintf(pFile, " rotational_median= %f\n", rotational_median);
455  fprintf(pFile, " rotational_std= %f\n", rotational_std);
456  fprintf(pFile, " rotational_min= %f\n", rotational_min);
457  fprintf(pFile, " rotational_max= %f\n", rotational_max);
458  fclose(pFile);
459  }
460  }
461  else
462  {
463  UERROR("Camera init failed!");
464  }
465 
466  printf("Saving rtabmap database (with all statistics) to \"%s\"\n", (output+"/"+outputName+".db").c_str());
467  printf("Do:\n"
468  " $ rtabmap-databaseViewer %s\n\n", (output+"/"+outputName+".db").c_str());
469 
470  return 0;
471 }
static std::string homeDir()
Definition: UDirectory.cpp:355
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
double restart()
Definition: UTimer.h:94
Definition: UTimer.h:46
void showUsage()
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
static bool makeDir(const std::string &dirPath)
Definition: UDirectory.cpp:333
bool g_forever
f
static const char * showUsage()
Definition: Parameters.cpp:518
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:42
static std::string getName(const std::string &filePath)
Definition: UFile.cpp:69
bool save(const std::string &directory) const
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
Definition: Parameters.cpp:543
static int erase(const std::string &filePath)
Definition: UFile.cpp:58
GLM_FUNC_DECL genType e()
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
Basic mathematics functions.
void setId(int id)
Definition: SensorData.h:153
Some conversion functions.
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0)
Definition: Rtabmap.cpp:3759
static rtabmap::Transform opticalRotation(1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f)
Transform process(SensorData &data, OdometryInfo *info=0)
Definition: Odometry.cpp:235
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
bool isValid() const
Definition: SensorData.h:134
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:67
Wrappers of STL for convenient functions.
const std::map< std::string, float > & data() const
Definition: Statistics.h:223
float timeStereoExposureCompensation
Definition: CameraInfo.h:62
bool isNull() const
Definition: Transform.cpp:107
int getLoopClosureId() const
Definition: Rtabmap.h:103
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
const Statistics & getStatistics() const
Definition: Rtabmap.cpp:631
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
bool process(const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
Main loop of rtabmap.
Definition: Rtabmap.cpp:897
static Odometry * create(const ParametersMap &parameters)
Definition: Odometry.cpp:53
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:32
void init(const ParametersMap &parameters, const std::string &databasePath="")
Definition: Rtabmap.cpp:282
double stamp() const
Definition: SensorData.h:154
bool exists()
Definition: UFile.h:104
Definition: UFile.h:33
void postUpdate(SensorData *data, CameraInfo *info=0) const
bool getNodeInfo(int signatureId, Transform &odomPose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruth, std::vector< float > &velocity, GPS &gps, bool lookInDatabase=false) const
Definition: Memory.cpp:3402
#define UERROR(...)
void sighandler(int sig)
int main(int argc, char *argv[])
#define UWARN(...)
const Memory * getMemory() const
Definition: Rtabmap.h:124
float timeImageDecimation
Definition: CameraInfo.h:63
double ticks()
Definition: UTimer.cpp:110
RegistrationInfo reg
Definition: OdometryInfo.h:91
std::vector< float > velocity() const
Definition: OdometryEvent.h:73
float timeBilateralFiltering
Definition: CameraInfo.h:66
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
Definition: SensorData.cpp:828
float timeUndistortDepth
Definition: CameraInfo.h:65


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