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"
31 #include "rtabmap/core/Graph.h"
34 #include "rtabmap/core/Memory.h"
38 #include "rtabmap/utilite/UFile.h"
39 #include "rtabmap/utilite/UMath.h"
40 #include "rtabmap/utilite/UStl.h"
42 #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];
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
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  SensorCaptureThread cameraThread(new
205  pathRgbImages,
206  pathDepthImages,
207  depthFactor,
208  0.0f), parameters);
209  ((CameraRGBDImages*)cameraThread.camera())->setTimestamps(true, "", false);
210  if(!pathGt.empty())
211  {
212  ((CameraRGBDImages*)cameraThread.camera())->setGroundTruthPath(pathGt, 1);
213  }
214 
215  bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
216  float detectionRate = Parameters::defaultRtabmapDetectionRate();
217  int odomStrategy = Parameters::defaultOdomStrategy();
218  Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
219  Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
220  Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
221  std::string databasePath = output+"/"+outputName+".db";
222  UFile::erase(databasePath);
223  if(cameraThread.camera()->init(path, outputName+"_calib"))
224  {
225  int totalImages = (int)((CameraRGBDImages*)cameraThread.camera())->filenames().size();
226 
227  if(skipFrames>0)
228  {
229  totalImages /= skipFrames+1;
230  }
231 
232  printf("Processing %d images...\n", totalImages);
233 
234  ParametersMap odomParameters = parameters;
235  odomParameters.erase(Parameters::kRtabmapPublishRAMUsage()); // as odometry is in the same process than rtabmap, don't get RAM usage in odometry.
236  Odometry * odom = Odometry::create(odomParameters);
238  rtabmap.init(parameters, databasePath);
239 
240  UTimer totalTime;
241  UTimer timer;
242  SensorCaptureInfo cameraInfo;
243  SensorData data = cameraThread.camera()->takeData(&cameraInfo);
244  int iteration = 0;
245 
247  // Processing dataset begin
249  int odomKeyFrames = 0;
250  double previousStamp = 0.0;
251  int skipCount = 0;
252  while(data.isValid() && g_forever)
253  {
254  if(skipCount < skipFrames)
255  {
256  ++skipCount;
257 
258  cameraInfo = SensorCaptureInfo();
259  timer.restart();
260  data = cameraThread.camera()->takeData(&cameraInfo);
261  continue;
262  }
263  skipCount = 0;
264 
265  cameraThread.postUpdate(&data, &cameraInfo);
266  cameraInfo.timeTotal = timer.ticks();
267 
268  OdometryInfo odomInfo;
269  Transform pose = odom->process(data, &odomInfo);
270 
271  if(odomStrategy == 2)
272  {
273  //special case for FOVIS, set covariance 1 if 9999 is detected
274  if(!odomInfo.reg.covariance.empty() && odomInfo.reg.covariance.at<double>(0,0) >= 9999)
275  {
276  odomInfo.reg.covariance = cv::Mat::eye(6,6,CV_64FC1);
277  }
278  }
279 
280  if(iteration!=0 && !odomInfo.reg.covariance.empty() && odomInfo.reg.covariance.at<double>(0,0)>=9999)
281  {
282  UWARN("Odometry is reset (high variance (%f >=9999 detected). Increment map id!", odomInfo.reg.covariance.at<double>(0,0));
283  rtabmap.triggerNewMap();
284  }
285 
286  if(odomInfo.keyFrameAdded)
287  {
288  ++odomKeyFrames;
289  }
290 
291  bool processData = true;
292  if(detectionRate>0.0f &&
293  previousStamp>0.0 &&
294  data.stamp()>previousStamp && data.stamp() - previousStamp < 1.0/detectionRate)
295  {
296  processData = false;
297  }
298 
299  if(processData)
300  {
301  previousStamp = data.stamp();
302  }
303 
304  if(!processData)
305  {
306  // set negative id so rtabmap will detect it as an intermediate node
307  data.setId(-1);
308  data.setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());// remove features
309  processData = intermediateNodes;
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/HistogramEqualization/ms", cameraInfo.timeHistogramEqualization*1000.0f));
323  externalStats.insert(std::make_pair("Camera/ExposureCompensation/ms", cameraInfo.timeStereoExposureCompensation*1000.0f));
324  externalStats.insert(std::make_pair("Camera/ScanFromDepth/ms", cameraInfo.timeScanFromDepth*1000.0f));
325  externalStats.insert(std::make_pair("Camera/TotalTime/ms", cameraInfo.timeTotal*1000.0f));
326  externalStats.insert(std::make_pair("Camera/UndistortDepth/ms", cameraInfo.timeUndistortDepth*1000.0f));
327  // save odometry statistics to database
328  externalStats.insert(std::make_pair("Odometry/LocalBundle/ms", odomInfo.localBundleTime*1000.0f));
329  externalStats.insert(std::make_pair("Odometry/LocalBundleConstraints/", odomInfo.localBundleConstraints));
330  externalStats.insert(std::make_pair("Odometry/LocalBundleOutliers/", odomInfo.localBundleOutliers));
331  externalStats.insert(std::make_pair("Odometry/TotalTime/ms", odomInfo.timeEstimation*1000.0f));
332  externalStats.insert(std::make_pair("Odometry/Registration/ms", odomInfo.reg.totalTime*1000.0f));
333  externalStats.insert(std::make_pair("Odometry/Inliers/", odomInfo.reg.inliers));
334  externalStats.insert(std::make_pair("Odometry/Features/", odomInfo.features));
335  externalStats.insert(std::make_pair("Odometry/DistanceTravelled/m", odomInfo.distanceTravelled));
336  externalStats.insert(std::make_pair("Odometry/KeyFrameAdded/", odomInfo.keyFrameAdded));
337  externalStats.insert(std::make_pair("Odometry/LocalKeyFrames/", odomInfo.localKeyFrames));
338  externalStats.insert(std::make_pair("Odometry/LocalMapSize/", odomInfo.localMapSize));
339  externalStats.insert(std::make_pair("Odometry/LocalScanMapSize/", odomInfo.localScanMapSize));
340 
341  OdometryEvent e(SensorData(), Transform(), odomInfo);
342  rtabmap.process(data, pose, odomInfo.reg.covariance, e.velocity(), externalStats);
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",
359  iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse);
360  }
361  else
362  {
363  printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
364  iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f));
365  }
366  if(processData && rtabmap.getLoopClosureId()>0)
367  {
368  printf(" *");
369  }
370  printf("\n");
371  }
372  else if(iteration % (totalImages/10) == 0)
373  {
374  printf(".");
375  fflush(stdout);
376  }
377 
378  cameraInfo = SensorCaptureInfo();
379  timer.restart();
380  data = cameraThread.camera()->takeData(&cameraInfo);
381  }
382  delete odom;
383  printf("Total time=%fs\n", totalTime.ticks());
385  // Processing dataset end
387 
388  // Save trajectory
389  printf("Saving trajectory...\n");
390  std::map<int, Transform> poses;
391  std::multimap<int, Link> links;
392  std::map<int, Signature> signatures;
393  std::map<int, double> stamps;
394  rtabmap.getGraph(poses, links, true, true, &signatures);
395  for(std::map<int, Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
396  {
397  stamps.insert(std::make_pair(iter->first, iter->second.getStamp()));
398  }
399  std::string pathTrajectory = output+"/"+outputName+"_poses.txt";
400  if(poses.size() && graph::exportPoses(pathTrajectory, 1, poses, links, stamps))
401  {
402  printf("Saving %s... done!\n", pathTrajectory.c_str());
403  }
404  else
405  {
406  printf("Saving %s... failed!\n", pathTrajectory.c_str());
407  }
408 
409  if(!pathGt.empty())
410  {
411  // Log ground truth statistics
412  std::map<int, Transform> groundTruth;
413 
414  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
415  {
416  Transform o, gtPose;
417  int m,w;
418  std::string l;
419  double s;
420  std::vector<float> v;
421  GPS gps;
422  EnvSensors sensors;
423  rtabmap.getMemory()->getNodeInfo(iter->first, o, m, w, l, s, gtPose, v, gps, sensors, true);
424  if(!gtPose.isNull())
425  {
426  groundTruth.insert(std::make_pair(iter->first, gtPose));
427  }
428  }
429 
430 
431  // compute RMSE statistics
432  float translational_rmse = 0.0f;
433  float translational_mean = 0.0f;
434  float translational_median = 0.0f;
435  float translational_std = 0.0f;
436  float translational_min = 0.0f;
437  float translational_max = 0.0f;
438  float rotational_rmse = 0.0f;
439  float rotational_mean = 0.0f;
440  float rotational_median = 0.0f;
441  float rotational_std = 0.0f;
442  float rotational_min = 0.0f;
443  float rotational_max = 0.0f;
445  groundTruth,
446  poses,
447  translational_rmse,
448  translational_mean,
449  translational_median,
450  translational_std,
451  translational_min,
452  translational_max,
453  rotational_rmse,
454  rotational_mean,
455  rotational_median,
456  rotational_std,
457  rotational_min,
458  rotational_max);
459 
460  printf(" translational_rmse= %f m\n", translational_rmse);
461  printf(" rotational_rmse= %f deg\n", rotational_rmse);
462 
463  FILE * pFile = 0;
464  std::string pathErrors = output+"/"+outputName+"_rmse.txt";
465  pFile = fopen(pathErrors.c_str(),"w");
466  if(!pFile)
467  {
468  UERROR("could not save RMSE results to \"%s\"", pathErrors.c_str());
469  }
470  fprintf(pFile, "Ground truth comparison:\n");
471  fprintf(pFile, " translational_rmse= %f\n", translational_rmse);
472  fprintf(pFile, " translational_mean= %f\n", translational_mean);
473  fprintf(pFile, " translational_median= %f\n", translational_median);
474  fprintf(pFile, " translational_std= %f\n", translational_std);
475  fprintf(pFile, " translational_min= %f\n", translational_min);
476  fprintf(pFile, " translational_max= %f\n", translational_max);
477  fprintf(pFile, " rotational_rmse= %f\n", rotational_rmse);
478  fprintf(pFile, " rotational_mean= %f\n", rotational_mean);
479  fprintf(pFile, " rotational_median= %f\n", rotational_median);
480  fprintf(pFile, " rotational_std= %f\n", rotational_std);
481  fprintf(pFile, " rotational_min= %f\n", rotational_min);
482  fprintf(pFile, " rotational_max= %f\n", rotational_max);
483  fclose(pFile);
484  }
485  }
486  else
487  {
488  UERROR("Camera init failed!");
489  }
490 
491  printf("Saving rtabmap database (with all statistics) to \"%s\"\n", (output+"/"+outputName+".db").c_str());
492  printf("Do:\n"
493  " $ rtabmap-databaseViewer %s\n\n", (output+"/"+outputName+".db").c_str());
494 
495  return 0;
496 }
rtabmap::SensorData
Definition: SensorData.h:51
rtabmap::SensorCaptureThread
Definition: SensorCaptureThread.h:58
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
w
RowVector3d w
int
int
rtabmap::OdometryEvent
Definition: OdometryEvent.h:39
rtabmap::Odometry::create
static Odometry * create(const ParametersMap &parameters=ParametersMap())
Definition: Odometry.cpp:58
rtabmap::OdometryInfo::localMapSize
int localMapSize
Definition: OdometryInfo.h:101
UFile::erase
static int erase(const std::string &filePath)
Definition: UFile.cpp:58
UFile
Definition: UFile.h:33
SensorCaptureThread.h
OdometryInfo.h
ULogger::kError
@ kError
Definition: ULogger.h:252
UDirectory::makeDir
static bool makeDir(const std::string &dirPath)
Definition: UDirectory.cpp:333
timer
s
RealScalar s
rtabmap::OdometryInfo::localBundleTime
float localBundleTime
Definition: OdometryInfo.h:106
rtabmap::Parameters::parseArguments
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
Definition: Parameters.cpp:599
UProcessInfo.h
rtabmap::OdometryInfo::keyFrameAdded
bool keyFrameAdded
Definition: OdometryInfo.h:109
rtabmap::OdometryInfo::timeEstimation
float timeEstimation
Definition: OdometryInfo.h:111
UDirectory.h
ULogger::kTypeConsole
@ kTypeConsole
Definition: ULogger.h:244
rtabmap::CameraModel
Definition: CameraModel.h:38
rtabmap::OdometryInfo::features
int features
Definition: OdometryInfo.h:100
rtabmap::graph::exportPoses
bool RTABMAP_CORE_EXPORT 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
ULogger::setLevel
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
rtabmap::GPS
Definition: GPS.h:35
CameraRGBD.h
UFile::getName
static std::string getName(const std::string &filePath)
Definition: UFile.cpp:69
timer::restart
void restart()
rtabmap::SensorCaptureInfo::timeHistogramEqualization
float timeHistogramEqualization
Definition: SensorCaptureInfo.h:69
rtabmap::SensorCaptureInfo::timeCapture
float timeCapture
Definition: SensorCaptureInfo.h:63
rtabmap::OdometryInfo::localKeyFrames
int localKeyFrames
Definition: OdometryInfo.h:103
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
stdout
stdout
rtabmap::graph::calcRMSE
Transform RTABMAP_CORE_EXPORT 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:759
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
UMath.h
Basic mathematics functions.
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:500
rtabmap::SensorCaptureInfo
Definition: SensorCaptureInfo.h:36
Odometry.h
UDirectory::homeDir
static std::string homeDir()
Definition: UDirectory.cpp:355
rtabmap::SensorCaptureThread::postUpdate
void postUpdate(SensorData *data, SensorCaptureInfo *info=0) const
Definition: SensorCaptureThread.cpp:573
rtabmap::SensorCapture::init
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
rtabmap::SensorCaptureInfo::timeScanFromDepth
float timeScanFromDepth
Definition: SensorCaptureInfo.h:70
seq
ArithmeticSequence< FirstTypeDerived, symbolic::AddExpr< symbolic::AddExpr< LastTypeDerived, symbolic::NegateExpr< FirstTypeDerived > >, symbolic::ValueExpr< internal::FixedInt< 1 > > > > seq(const symbolic::BaseExpr< FirstTypeDerived > &f, const symbolic::BaseExpr< LastTypeDerived > &l)
data
int data[]
sighandler
void sighandler(int sig)
Definition: tools/RgbdDataset/main.cpp:75
UConversion.h
Some conversion functions.
rtabmap::OdometryInfo::localBundleConstraints
int localBundleConstraints
Definition: OdometryInfo.h:105
rtabmap::OdometryInfo::localScanMapSize
int localScanMapSize
Definition: OdometryInfo.h:102
Rtabmap.h
rtabmap::Odometry::process
Transform process(SensorData &data, OdometryInfo *info=0)
Definition: Odometry.cpp:298
ULogger::kWarning
@ kWarning
Definition: ULogger.h:252
rtabmap::RegistrationInfo::covariance
cv::Mat covariance
Definition: RegistrationInfo.h:75
rtabmap::SensorCapture::takeData
SensorData takeData(SensorCaptureInfo *info=0)
Definition: SensorCapture.cpp:64
rtabmap::RegistrationInfo::inliers
int inliers
Definition: RegistrationInfo.h:80
UASSERT
#define UASSERT(condition)
rtabmap_netvlad.argv
argv
Definition: rtabmap_netvlad.py:15
m
Matrix3f m
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
rtabmap::SensorCaptureInfo::timeBilateralFiltering
float timeBilateralFiltering
Definition: SensorCaptureInfo.h:72
OdometryEvent.h
rtabmap::SensorCaptureInfo::timeTotal
float timeTotal
Definition: SensorCaptureInfo.h:73
rtabmap::SensorCaptureInfo::timeImageDecimation
float timeImageDecimation
Definition: SensorCaptureInfo.h:68
path
path
main
int main(int argc, char *argv[])
Definition: tools/RgbdDataset/main.cpp:81
UWARN
#define UWARN(...)
rtabmap::Parameters::showUsage
static const char * showUsage()
Definition: Parameters.cpp:572
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
uReplaceChar
std::string UTILITE_EXPORT uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:33
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
rtabmap::RegistrationInfo::totalTime
double totalTime
Definition: RegistrationInfo.h:77
rtabmap::Transform
Definition: Transform.h:41
Memory.h
UTimer::ticks
double ticks()
Definition: UTimer.cpp:117
g_forever
bool g_forever
Definition: tools/RgbdDataset/main.cpp:74
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:564
rtabmap::EnvSensors
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
rtabmap::OdometryInfo::distanceTravelled
float distanceTravelled
Definition: OdometryInfo.h:120
Graph.h
rtabmap::CameraRGBDImages
Definition: CameraRGBDImages.h:35
iter
iterator iter(handle obj)
rtabmap::SensorCaptureInfo::timeDisparity
float timeDisparity
Definition: SensorCaptureInfo.h:65
util3d_registration.h
c_str
const char * c_str(Args &&...args)
UStl.h
Wrappers of STL for convenient functions.
rtabmap::SensorCaptureInfo::timeStereoExposureCompensation
float timeStereoExposureCompensation
Definition: SensorCaptureInfo.h:67
rtabmap::SensorCaptureInfo::timeMirroring
float timeMirroring
Definition: SensorCaptureInfo.h:66
v
Array< int, Dynamic, 1 > v
rtabmap::Odometry
Definition: Odometry.h:42
rtabmap::OdometryInfo::reg
RegistrationInfo reg
Definition: OdometryInfo.h:99
UTimer
Definition: UTimer.h:46
rtabmap::OdometryInfo
Definition: OdometryInfo.h:40
rtabmap::Rtabmap
Definition: Rtabmap.h:54
rtabmap::SensorCaptureThread::camera
Camera * camera()
Definition: SensorCaptureThread.h:169
rtabmap::SensorCaptureInfo::timeUndistortDepth
float timeUndistortDepth
Definition: SensorCaptureInfo.h:71
UFile.h
rtabmap
Definition: CameraARCore.cpp:35
UFile::exists
bool exists()
Definition: UFile.h:104
UERROR
#define UERROR(...)
trace.model
model
Definition: trace.py:4
i
int i
rtabmap::OdometryInfo::localBundleOutliers
int localBundleOutliers
Definition: OdometryInfo.h:104
showUsage
void showUsage()
Definition: tools/RgbdDataset/main.cpp:49


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:12