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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:59