42 #include <pcl/common/common.h>
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"
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"
77 printf(
"\nSignal %d caught...\n", sig);
93 std::string outputName =
"rtabmap";
102 for(
int i=1;
i<argc; ++
i)
104 if(std::strcmp(
argv[
i],
"--output") == 0)
108 else if(std::strcmp(
argv[
i],
"--output_name") == 0)
110 outputName =
argv[++
i];
112 else if(std::strcmp(
argv[
i],
"--skip") == 0)
114 skipFrames = atoi(
argv[++
i]);
117 else if(std::strcmp(
argv[
i],
"--quiet") == 0)
135 parameters.insert(
ParametersPair(Parameters::kRtabmapWorkingDirectory(), output));
136 parameters.insert(
ParametersPair(Parameters::kRtabmapPublishRAMUsage(),
"true"));
140 std::string pathRgbImages =
path+
"/rgb_sync";
141 std::string pathDepthImages =
path+
"/depth_sync";
142 std::string pathGt =
path+
"/groundtruth.txt";
145 UWARN(
"Ground truth file path doesn't exist: \"%s\", benchmark values won't be computed.", pathGt.c_str());
155 " Dataset name: %s\n"
156 " Dataset path: %s\n"
161 " Skip frames: %d\n",
164 pathRgbImages.c_str(),
165 pathDepthImages.c_str(),
171 printf(
" groundtruth.txt: %s\n", pathGt.c_str());
173 if(!parameters.empty())
175 printf(
"Parameters:\n");
176 for(ParametersMap::iterator
iter=parameters.begin();
iter!=parameters.end(); ++
iter)
178 printf(
" %s=%s\n",
iter->first.c_str(),
iter->second.c_str());
181 printf(
"RTAB-Map version: %s\n", RTABMAP_VERSION);
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)
190 model =
CameraModel(outputName+
"_calib", 517.3, 516.5, 318.6, 255.3, opticalRotation, 0, cv::Size(640,480));
192 else if(sequenceName.find(
"freiburg2") != std::string::npos)
194 model =
CameraModel(outputName+
"_calib", 520.9, 521.0, 325.1, 249.7, opticalRotation, 0, cv::Size(640,480));
198 model =
CameraModel(outputName+
"_calib", 535.4, 539.2, 320.1, 247.6, opticalRotation, 0, cv::Size(640,480));
215 bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
216 float detectionRate = Parameters::defaultRtabmapDetectionRate();
217 int odomStrategy = Parameters::defaultOdomStrategy();
218 Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
220 Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
221 std::string databasePath = output+
"/"+outputName+
".db";
229 totalImages /= skipFrames+1;
232 printf(
"Processing %d images...\n", totalImages);
235 odomParameters.erase(Parameters::kRtabmapPublishRAMUsage());
238 rtabmap.init(parameters, databasePath);
249 int odomKeyFrames = 0;
250 double previousStamp = 0.0;
254 if(skipCount < skipFrames)
271 if(odomStrategy == 2)
282 UWARN(
"Odometry is reset (high variance (%f >=9999 detected). Increment map id!", odomInfo.
reg.
covariance.at<
double>(0,0));
291 bool processData =
true;
292 if(detectionRate>0.0
f &&
294 data.stamp()>previousStamp &&
data.stamp() - previousStamp < 1.0/detectionRate)
301 previousStamp =
data.stamp();
308 data.setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());
309 processData = intermediateNodes;
315 std::map<std::string, float> externalStats;
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));
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));
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));
346 if(!quiet || iteration == totalImages)
348 double slamTime =
timer.ticks();
351 if(
rtabmap.getStatistics().data().find(Statistics::kGtTranslational_rmse()) !=
rtabmap.getStatistics().data().end())
353 rmse =
rtabmap.getStatistics().data().at(Statistics::kGtTranslational_rmse());
358 printf(
"Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm",
363 printf(
"Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
366 if(processData &&
rtabmap.getLoopClosureId()>0)
372 else if(iteration % (totalImages/10) == 0)
383 printf(
"Total time=%fs\n", totalTime.
ticks());
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)
397 stamps.insert(std::make_pair(
iter->first,
iter->second.getStamp()));
399 std::string pathTrajectory = output+
"/"+outputName+
"_poses.txt";
402 printf(
"Saving %s... done!\n", pathTrajectory.c_str());
406 printf(
"Saving %s... failed!\n", pathTrajectory.c_str());
412 std::map<int, Transform> groundTruth;
414 for(std::map<int, Transform>::const_iterator
iter=poses.begin();
iter!=poses.end(); ++
iter)
420 std::vector<float>
v;
423 rtabmap.getMemory()->getNodeInfo(
iter->first, o,
m,
w, l,
s, gtPose,
v, gps, sensors,
true);
426 groundTruth.insert(std::make_pair(
iter->first, gtPose));
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;
449 translational_median,
460 printf(
" translational_rmse= %f m\n", translational_rmse);
461 printf(
" rotational_rmse= %f deg\n", rotational_rmse);
464 std::string pathErrors = output+
"/"+outputName+
"_rmse.txt";
465 pFile = fopen(pathErrors.c_str(),
"w");
468 UERROR(
"could not save RMSE results to \"%s\"", pathErrors.c_str());
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);
488 UERROR(
"Camera init failed!");
491 printf(
"Saving rtabmap database (with all statistics) to \"%s\"\n", (output+
"/"+outputName+
".db").
c_str());
493 " $ rtabmap-databaseViewer %s\n\n", (output+
"/"+outputName+
".db").
c_str());