00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <rtabmap/core/OdometryF2M.h>
00029 #include "rtabmap/core/Rtabmap.h"
00030 #include "rtabmap/core/CameraStereo.h"
00031 #include "rtabmap/core/CameraThread.h"
00032 #include "rtabmap/core/Graph.h"
00033 #include "rtabmap/core/OdometryInfo.h"
00034 #include "rtabmap/core/OdometryEvent.h"
00035 #include "rtabmap/core/Memory.h"
00036 #include "rtabmap/core/util3d_registration.h"
00037 #include "rtabmap/utilite/UConversion.h"
00038 #include "rtabmap/utilite/UDirectory.h"
00039 #include "rtabmap/utilite/UFile.h"
00040 #include "rtabmap/utilite/UMath.h"
00041 #include "rtabmap/utilite/UStl.h"
00042 #include "rtabmap/utilite/UProcessInfo.h"
00043 #include <pcl/common/common.h>
00044 #include <stdio.h>
00045 #include <signal.h>
00046
00047 using namespace rtabmap;
00048
00049 void showUsage()
00050 {
00051 printf("\nUsage:\n"
00052 "rtabmap-kitti_dataset [options] path\n"
00053 " path Folder of the sequence (e.g., \"~/KITTI/dataset/sequences/07\")\n"
00054 " containing least calib.txt, times.txt, image_0 and image_1 folders.\n"
00055 " Optional image_2, image_3 and velodyne folders.\n"
00056 " --output Output directory. By default, results are saved in \"path\".\n"
00057 " --output_name Output database name (default \"rtabmap\").\n"
00058 " --gt \"path\" Ground truth path (e.g., ~/KITTI/devkit/cpp/data/odometry/poses/07.txt)\n"
00059 " --quiet Don't show log messages and iteration updates.\n"
00060 " --color Use color images for stereo (image_2 and image_3 folders).\n"
00061 " --height Add car's height to camera local transform (1.67m).\n"
00062 " --disp Generate full disparity.\n"
00063 " --exposure_comp Do exposure compensation between left and right images.\n"
00064 " --scan Include velodyne scan in node's data.\n"
00065 " --scan_step # Scan downsample step (default=1).\n"
00066 " --scan_voxel #.# Scan voxel size (default 0.5 m).\n"
00067 " --scan_k Scan normal K (default 0).\n"
00068 " --scan_radius Scan normal radius (default 0).\n\n"
00069 "%s\n"
00070 "Example:\n\n"
00071 " $ rtabmap-kitti_dataset \\\n"
00072 " --Rtabmap/PublishRAMUsage true\\\n"
00073 " --Rtabmap/DetectionRate 2\\\n"
00074 " --Rtabmap/CreateIntermediateNodes true\\\n"
00075 " --RGBD/LinearUpdate 0\\\n"
00076 " --GFTT/QualityLevel 0.01\\\n"
00077 " --GFTT/MinDistance 7\\\n"
00078 " --OdomF2M/MaxSize 3000\\\n"
00079 " --Mem/STMSize 30\\\n"
00080 " --Kp/MaxFeatures 750\\\n"
00081 " --Vis/MaxFeatures 1500\\\n"
00082 " --gt \"~/KITTI/devkit/cpp/data/odometry/poses/07.txt\"\\\n"
00083 " ~/KITTI/dataset/sequences/07\n\n", rtabmap::Parameters::showUsage());
00084 exit(1);
00085 }
00086
00087
00088 bool g_forever = true;
00089 void sighandler(int sig)
00090 {
00091 printf("\nSignal %d caught...\n", sig);
00092 g_forever = false;
00093 }
00094
00095 int main(int argc, char * argv[])
00096 {
00097 signal(SIGABRT, &sighandler);
00098 signal(SIGTERM, &sighandler);
00099 signal(SIGINT, &sighandler);
00100
00101 ULogger::setType(ULogger::kTypeConsole);
00102 ULogger::setLevel(ULogger::kWarning);
00103
00104 ParametersMap parameters;
00105 std::string path;
00106 std::string output;
00107 std::string outputName = "rtabmap";
00108 std::string seq;
00109 bool color = false;
00110 bool height = false;
00111 bool scan = false;
00112 bool disp = false;
00113 bool exposureCompensation = false;
00114 int scanStep = 1;
00115 float scanVoxel = 0.5f;
00116 int scanNormalK = 0;
00117 float scanNormalRadius = 0.0f;
00118 std::string gtPath;
00119 bool quiet = false;
00120 if(argc < 2)
00121 {
00122 showUsage();
00123 }
00124 else
00125 {
00126 for(int i=1; i<argc; ++i)
00127 {
00128 if(std::strcmp(argv[i], "--output") == 0)
00129 {
00130 output = argv[++i];
00131 }
00132 else if(std::strcmp(argv[i], "--output_name") == 0)
00133 {
00134 outputName = argv[++i];
00135 }
00136 else if(std::strcmp(argv[i], "--quiet") == 0)
00137 {
00138 quiet = true;
00139 }
00140 else if(std::strcmp(argv[i], "--scan_step") == 0)
00141 {
00142 scanStep = atoi(argv[++i]);
00143 if(scanStep <= 0)
00144 {
00145 printf("scan_step should be > 0\n");
00146 showUsage();
00147 }
00148 }
00149 else if(std::strcmp(argv[i], "--scan_voxel") == 0)
00150 {
00151 scanVoxel = atof(argv[++i]);
00152 if(scanVoxel < 0.0f)
00153 {
00154 printf("scan_voxel should be >= 0.0\n");
00155 showUsage();
00156 }
00157 }
00158 else if(std::strcmp(argv[i], "--scan_k") == 0)
00159 {
00160 scanNormalK = atoi(argv[++i]);
00161 if(scanNormalK < 0)
00162 {
00163 printf("scanNormalK should be >= 0\n");
00164 showUsage();
00165 }
00166 }
00167 else if(std::strcmp(argv[i], "--scan_radius") == 0)
00168 {
00169 scanNormalRadius = atof(argv[++i]);
00170 if(scanNormalRadius < 0.0f)
00171 {
00172 printf("scanNormalRadius should be >= 0\n");
00173 showUsage();
00174 }
00175 }
00176 else if(std::strcmp(argv[i], "--gt") == 0)
00177 {
00178 gtPath = argv[++i];
00179 }
00180 else if(std::strcmp(argv[i], "--color") == 0)
00181 {
00182 color = true;
00183 }
00184 else if(std::strcmp(argv[i], "--height") == 0)
00185 {
00186 height = true;
00187 }
00188 else if(std::strcmp(argv[i], "--scan") == 0)
00189 {
00190 scan = true;
00191 }
00192 else if(std::strcmp(argv[i], "--disp") == 0)
00193 {
00194 disp = true;
00195 }
00196 else if(std::strcmp(argv[i], "--exposure_comp") == 0)
00197 {
00198 exposureCompensation = true;
00199 }
00200 }
00201 parameters = Parameters::parseArguments(argc, argv);
00202 path = argv[argc-1];
00203 path = uReplaceChar(path, '~', UDirectory::homeDir());
00204 path = uReplaceChar(path, '\\', '/');
00205 if(output.empty())
00206 {
00207 output = path;
00208 }
00209 else
00210 {
00211 output = uReplaceChar(output, '~', UDirectory::homeDir());
00212 UDirectory::makeDir(output);
00213 }
00214 parameters.insert(ParametersPair(Parameters::kRtabmapWorkingDirectory(), output));
00215 parameters.insert(ParametersPair(Parameters::kRtabmapPublishRAMUsage(), "true"));
00216 }
00217
00218 seq = uSplit(path, '/').back();
00219 if(seq.empty() || !(uStr2Int(seq)>=0 && uStr2Int(seq)<=21))
00220 {
00221 UWARN("Sequence number \"%s\" should be between 0 and 21 (official KITTI datasets).", seq.c_str());
00222 seq.clear();
00223 }
00224 std::string pathLeftImages = path+(color?"/image_2":"/image_0");
00225 std::string pathRightImages = path+(color?"/image_3":"/image_1");
00226 std::string pathCalib = path+"/calib.txt";
00227 std::string pathTimes = path+"/times.txt";
00228 std::string pathScan;
00229
00230 printf("Paths:\n"
00231 " Sequence number: %s\n"
00232 " Sequence path: %s\n"
00233 " Output: %s\n"
00234 " Output name: %s\n"
00235 " left images: %s\n"
00236 " right images: %s\n"
00237 " calib.txt: %s\n"
00238 " times.txt: %s\n",
00239 seq.c_str(),
00240 path.c_str(),
00241 output.c_str(),
00242 outputName.c_str(),
00243 pathLeftImages.c_str(),
00244 pathRightImages.c_str(),
00245 pathCalib.c_str(),
00246 pathTimes.c_str());
00247 if(!gtPath.empty())
00248 {
00249 gtPath = uReplaceChar(gtPath, '~', UDirectory::homeDir());
00250 gtPath = uReplaceChar(gtPath, '\\', '/');
00251 if(!UFile::exists(gtPath))
00252 {
00253 UWARN("Ground truth file path doesn't exist: \"%s\", benchmark values won't be computed.", gtPath.c_str());
00254 gtPath.clear();
00255 }
00256 else
00257 {
00258 printf(" Ground Truth: %s\n", gtPath.c_str());
00259 }
00260 }
00261 printf(" Exposure Compensation: %s\n", exposureCompensation?"true":"false");
00262 printf(" Disparity: %s\n", disp?"true":"false");
00263 if(scan)
00264 {
00265 pathScan = path+"/velodyne";
00266 printf(" Scan: %s\n", pathScan.c_str());
00267 printf(" Scan step: %d\n", scanStep);
00268 printf(" Scan voxel: %fm\n", scanVoxel);
00269 printf(" Scan normal k: %d\n", scanNormalK);
00270 printf(" Scan normal radius: %f\n", scanNormalRadius);
00271 }
00272
00273
00274 FILE * pFile = 0;
00275 pFile = fopen(pathCalib.c_str(),"r");
00276 if(!pFile)
00277 {
00278 UERROR("Cannot open calibration file \"%s\"", pathCalib.c_str());
00279 return -1;
00280 }
00281 cv::Mat_<double> P0(3,4);
00282 cv::Mat_<double> P1(3,4);
00283 cv::Mat_<double> P2(3,4);
00284 cv::Mat_<double> P3(3,4);
00285 if(fscanf (pFile, "%*s %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
00286 &P0(0, 0), &P0(0, 1), &P0(0, 2), &P0(0, 3),
00287 &P0(1, 0), &P0(1, 1), &P0(1, 2), &P0(1, 3),
00288 &P0(2, 0), &P0(2, 1), &P0(2, 2), &P0(2, 3)) != 12)
00289 {
00290 UERROR("Failed to parse calibration file \"%s\"", pathCalib.c_str());
00291 return -1;
00292 }
00293 if(fscanf (pFile, "%*s %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
00294 &P1(0, 0), &P1(0, 1), &P1(0, 2), &P1(0, 3),
00295 &P1(1, 0), &P1(1, 1), &P1(1, 2), &P1(1, 3),
00296 &P1(2, 0), &P1(2, 1), &P1(2, 2), &P1(2, 3)) != 12)
00297 {
00298 UERROR("Failed to parse calibration file \"%s\"", pathCalib.c_str());
00299 return -1;
00300 }
00301 if(fscanf (pFile, "%*s %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
00302 &P2(0, 0), &P2(0, 1), &P2(0, 2), &P2(0, 3),
00303 &P2(1, 0), &P2(1, 1), &P2(1, 2), &P2(1, 3),
00304 &P2(2, 0), &P2(2, 1), &P2(2, 2), &P2(2, 3)) != 12)
00305 {
00306 UERROR("Failed to parse calibration file \"%s\"", pathCalib.c_str());
00307 return -1;
00308 }
00309 if(fscanf (pFile, "%*s %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf",
00310 &P3(0, 0), &P3(0, 1), &P3(0, 2), &P3(0, 3),
00311 &P3(1, 0), &P3(1, 1), &P3(1, 2), &P3(1, 3),
00312 &P3(2, 0), &P3(2, 1), &P3(2, 2), &P3(2, 3)) != 12)
00313 {
00314 UERROR("Failed to parse calibration file \"%s\"", pathCalib.c_str());
00315 return -1;
00316 }
00317 fclose (pFile);
00318
00319 UDirectory dir(pathLeftImages);
00320 std::string firstImage = dir.getNextFileName();
00321 cv::Mat image = cv::imread(dir.getNextFilePath());
00322 if(image.empty())
00323 {
00324 UERROR("Failed to read first image of \"%s\"", firstImage.c_str());
00325 return -1;
00326 }
00327
00328 StereoCameraModel model(outputName+"_calib",
00329 image.size(), P0.colRange(0,3), cv::Mat(), cv::Mat(), P0,
00330 image.size(), P1.colRange(0,3), cv::Mat(), cv::Mat(), P1,
00331 cv::Mat(), cv::Mat(), cv::Mat(), cv::Mat());
00332 if(!model.save(output, true))
00333 {
00334 UERROR("Could not save calibration!");
00335 return -1;
00336 }
00337 printf("Saved calibration \"%s\" to \"%s\"\n", (outputName+"_calib").c_str(), output.c_str());
00338
00339 if(!parameters.empty())
00340 {
00341 printf("Parameters:\n");
00342 for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00343 {
00344 printf(" %s=%s\n", iter->first.c_str(), iter->second.c_str());
00345 }
00346 }
00347
00348 printf("RTAB-Map version: %s\n", RTABMAP_VERSION);
00349
00350 if(quiet)
00351 {
00352 ULogger::setLevel(ULogger::kError);
00353 }
00354
00355
00356 Transform opticalRotation(0,0,1,0, -1,0,0,color?-0.06:0, 0,-1,0,height?1.67:0.0);
00357 CameraThread cameraThread(new
00358 CameraStereoImages(
00359 pathLeftImages,
00360 pathRightImages,
00361 false,
00362 0.0f,
00363 opticalRotation), parameters);
00364 ((CameraStereoImages*)cameraThread.camera())->setTimestamps(false, pathTimes, false);
00365 if(exposureCompensation)
00366 {
00367 cameraThread.setStereoExposureCompensation(true);
00368 }
00369 if(disp)
00370 {
00371 cameraThread.setStereoToDepth(true);
00372 }
00373 if(!gtPath.empty())
00374 {
00375 ((CameraStereoImages*)cameraThread.camera())->setGroundTruthPath(gtPath, 2);
00376 }
00377 if(!pathScan.empty())
00378 {
00379 ((CameraStereoImages*)cameraThread.camera())->setScanPath(
00380 pathScan,
00381 130000,
00382 scanStep,
00383 scanVoxel,
00384 scanNormalK,
00385 scanNormalRadius,
00386 Transform(-0.27f, 0.0f, 0.08+(height?1.67f:0.0f), 0.0f, 0.0f, 0.0f),
00387 true);
00388 }
00389
00390 float detectionRate = Parameters::defaultRtabmapDetectionRate();
00391 bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
00392 int odomStrategy = Parameters::defaultOdomStrategy();
00393 Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
00394 Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
00395 Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
00396
00397
00398 int mapUpdate = detectionRate>0?10 / detectionRate:1;
00399 if(mapUpdate < 1)
00400 {
00401 mapUpdate = 1;
00402 }
00403
00404 std::string databasePath = output+"/"+outputName+".db";
00405 UFile::erase(databasePath);
00406 if(cameraThread.camera()->init(output, outputName+"_calib"))
00407 {
00408 int totalImages = (int)((CameraStereoImages*)cameraThread.camera())->filenames().size();
00409
00410 printf("Processing %d images...\n", totalImages);
00411
00412 ParametersMap odomParameters = parameters;
00413 odomParameters.erase(Parameters::kRtabmapPublishRAMUsage());
00414 Odometry * odom = Odometry::create(odomParameters);
00415 Rtabmap rtabmap;
00416 rtabmap.init(parameters, databasePath);
00417
00418 UTimer totalTime;
00419 UTimer timer;
00420 CameraInfo cameraInfo;
00421 SensorData data = cameraThread.camera()->takeImage(&cameraInfo);
00422 int iteration = 0;
00423
00425
00427 cv::Mat covariance;
00428 int odomKeyFrames = 0;
00429 while(data.isValid() && g_forever)
00430 {
00431 cameraThread.postUpdate(&data, &cameraInfo);
00432 cameraInfo.timeTotal = timer.ticks();
00433
00434
00435 OdometryInfo odomInfo;
00436 Transform pose = odom->process(data, &odomInfo);
00437 float speed = 0.0f;
00438 if(odomInfo.interval>0.0)
00439 speed = odomInfo.transform.x()/odomInfo.interval*3.6;
00440 if(odomInfo.keyFrameAdded)
00441 {
00442 ++odomKeyFrames;
00443 }
00444
00445 if(odomStrategy == 2)
00446 {
00447
00448 if(!odomInfo.reg.covariance.empty() && odomInfo.reg.covariance.at<double>(0,0) >= 9999)
00449 {
00450 odomInfo.reg.covariance = cv::Mat::eye(6,6,CV_64FC1);
00451 }
00452 }
00453
00454 bool processData = true;
00455 if(iteration % mapUpdate != 0)
00456 {
00457
00458 data.setId(-1);
00459 data.setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());
00460 processData = intermediateNodes;
00461 }
00462 if(covariance.empty() || odomInfo.reg.covariance.at<double>(0,0) > covariance.at<double>(0,0))
00463 {
00464 covariance = odomInfo.reg.covariance;
00465 }
00466
00467 timer.restart();
00468 if(processData)
00469 {
00470 std::map<std::string, float> externalStats;
00471
00472 externalStats.insert(std::make_pair("Camera/BilateralFiltering/ms", cameraInfo.timeBilateralFiltering*1000.0f));
00473 externalStats.insert(std::make_pair("Camera/Capture/ms", cameraInfo.timeCapture*1000.0f));
00474 externalStats.insert(std::make_pair("Camera/Disparity/ms", cameraInfo.timeDisparity*1000.0f));
00475 externalStats.insert(std::make_pair("Camera/ImageDecimation/ms", cameraInfo.timeImageDecimation*1000.0f));
00476 externalStats.insert(std::make_pair("Camera/Mirroring/ms", cameraInfo.timeMirroring*1000.0f));
00477 externalStats.insert(std::make_pair("Camera/ExposureCompensation/ms", cameraInfo.timeStereoExposureCompensation*1000.0f));
00478 externalStats.insert(std::make_pair("Camera/ScanFromDepth/ms", cameraInfo.timeScanFromDepth*1000.0f));
00479 externalStats.insert(std::make_pair("Camera/TotalTime/ms", cameraInfo.timeTotal*1000.0f));
00480 externalStats.insert(std::make_pair("Camera/UndistortDepth/ms", cameraInfo.timeUndistortDepth*1000.0f));
00481
00482 externalStats.insert(std::make_pair("Odometry/LocalBundle/ms", odomInfo.localBundleTime*1000.0f));
00483 externalStats.insert(std::make_pair("Odometry/LocalBundleConstraints/", odomInfo.localBundleConstraints));
00484 externalStats.insert(std::make_pair("Odometry/LocalBundleOutliers/", odomInfo.localBundleOutliers));
00485 externalStats.insert(std::make_pair("Odometry/TotalTime/ms", odomInfo.timeEstimation*1000.0f));
00486 externalStats.insert(std::make_pair("Odometry/Registration/ms", odomInfo.reg.totalTime*1000.0f));
00487 externalStats.insert(std::make_pair("Odometry/Speed/kph", speed));
00488 externalStats.insert(std::make_pair("Odometry/Inliers/", odomInfo.reg.inliers));
00489 externalStats.insert(std::make_pair("Odometry/Features/", odomInfo.features));
00490 externalStats.insert(std::make_pair("Odometry/DistanceTravelled/m", odomInfo.distanceTravelled));
00491 externalStats.insert(std::make_pair("Odometry/KeyFrameAdded/", odomInfo.keyFrameAdded));
00492 externalStats.insert(std::make_pair("Odometry/LocalKeyFrames/", odomInfo.localKeyFrames));
00493 externalStats.insert(std::make_pair("Odometry/LocalMapSize/", odomInfo.localMapSize));
00494 externalStats.insert(std::make_pair("Odometry/LocalScanMapSize/", odomInfo.localScanMapSize));
00495
00496 OdometryEvent e(SensorData(), Transform(), odomInfo);
00497 rtabmap.process(data, pose, covariance, e.velocity(), externalStats);
00498 covariance = cv::Mat();
00499 }
00500
00501 ++iteration;
00502 if(!quiet || iteration == totalImages)
00503 {
00504 double slamTime = timer.ticks();
00505
00506 float rmse = -1;
00507 if(rtabmap.getStatistics().data().find(Statistics::kGtTranslational_rmse()) != rtabmap.getStatistics().data().end())
00508 {
00509 rmse = rtabmap.getStatistics().data().at(Statistics::kGtTranslational_rmse());
00510 }
00511
00512 if(data.keypoints().size() == 0 && data.laserScanRaw().size())
00513 {
00514 if(rmse >= 0.0f)
00515 {
00516
00517
00518 printf("Iteration %d/%d: speed=%dkm/h camera=%dms, odom(quality=%f, kfs=%d)=%dms, slam=%dms, rmse=%fm",
00519 iteration, totalImages, int(speed), int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.icpInliersRatio, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse);
00520 }
00521 else
00522 {
00523 printf("Iteration %d/%d: speed=%dkm/h camera=%dms, odom(quality=%f, kfs=%d)=%dms, slam=%dms",
00524 iteration, totalImages, int(speed), int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.icpInliersRatio, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f));
00525 }
00526 }
00527 else
00528 {
00529 if(rmse >= 0.0f)
00530 {
00531
00532
00533 printf("Iteration %d/%d: speed=%dkm/h camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm",
00534 iteration, totalImages, int(speed), int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse);
00535 }
00536 else
00537 {
00538 printf("Iteration %d/%d: speed=%dkm/h camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
00539 iteration, totalImages, int(speed), int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f));
00540 }
00541 }
00542 if(processData && rtabmap.getLoopClosureId()>0)
00543 {
00544 printf(" *");
00545 }
00546 printf("\n");
00547 }
00548 else if(iteration % (totalImages/10) == 0)
00549 {
00550 printf(".");
00551 fflush(stdout);
00552 }
00553
00554 cameraInfo = CameraInfo();
00555 timer.restart();
00556 data = cameraThread.camera()->takeImage(&cameraInfo);
00557 }
00558 delete odom;
00559 printf("Total time=%fs\n", totalTime.ticks());
00561
00563
00564
00565 printf("Saving trajectory ...\n");
00566 std::map<int, Transform> poses;
00567 std::multimap<int, Link> links;
00568 rtabmap.getGraph(poses, links, true, true);
00569 std::string pathTrajectory = output+"/"+outputName+"_poses.txt";
00570 if(poses.size() && graph::exportPoses(pathTrajectory, 2, poses, links))
00571 {
00572 printf("Saving %s... done!\n", pathTrajectory.c_str());
00573 }
00574 else
00575 {
00576 printf("Saving %s... failed!\n", pathTrajectory.c_str());
00577 }
00578
00579 if(!gtPath.empty())
00580 {
00581
00582 std::map<int, Transform> groundTruth;
00583
00584 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00585 {
00586 Transform o, gtPose;
00587 int m,w;
00588 std::string l;
00589 double s;
00590 std::vector<float> v;
00591 GPS gps;
00592 rtabmap.getMemory()->getNodeInfo(iter->first, o, m, w, l, s, gtPose, v, gps, true);
00593 if(!gtPose.isNull())
00594 {
00595 groundTruth.insert(std::make_pair(iter->first, gtPose));
00596 }
00597 }
00598
00599
00600 float t_err = 0.0f;
00601 float r_err = 0.0f;
00602 graph::calcKittiSequenceErrors(uValues(groundTruth), uValues(poses), t_err, r_err);
00603 printf("Ground truth comparison:\n");
00604 printf(" KITTI t_err = %f %%\n", t_err);
00605 printf(" KITTI r_err = %f deg/m\n", r_err);
00606
00607
00608 float translational_rmse = 0.0f;
00609 float translational_mean = 0.0f;
00610 float translational_median = 0.0f;
00611 float translational_std = 0.0f;
00612 float translational_min = 0.0f;
00613 float translational_max = 0.0f;
00614 float rotational_rmse = 0.0f;
00615 float rotational_mean = 0.0f;
00616 float rotational_median = 0.0f;
00617 float rotational_std = 0.0f;
00618 float rotational_min = 0.0f;
00619 float rotational_max = 0.0f;
00620 graph::calcRMSE(
00621 groundTruth,
00622 poses,
00623 translational_rmse,
00624 translational_mean,
00625 translational_median,
00626 translational_std,
00627 translational_min,
00628 translational_max,
00629 rotational_rmse,
00630 rotational_mean,
00631 rotational_median,
00632 rotational_std,
00633 rotational_min,
00634 rotational_max);
00635
00636 printf(" translational_rmse= %f m\n", translational_rmse);
00637 printf(" rotational_rmse= %f deg\n", rotational_rmse);
00638
00639 pFile = 0;
00640 std::string pathErrors = output+"/"+outputName+"_rmse.txt";
00641 pFile = fopen(pathErrors.c_str(),"w");
00642 if(!pFile)
00643 {
00644 UERROR("could not save RMSE results to \"%s\"", pathErrors.c_str());
00645 }
00646 fprintf(pFile, "Ground truth comparison:\n");
00647 fprintf(pFile, " KITTI t_err = %f %%\n", t_err);
00648 fprintf(pFile, " KITTI r_err = %f deg/m\n", r_err);
00649 fprintf(pFile, " translational_rmse= %f\n", translational_rmse);
00650 fprintf(pFile, " translational_mean= %f\n", translational_mean);
00651 fprintf(pFile, " translational_median= %f\n", translational_median);
00652 fprintf(pFile, " translational_std= %f\n", translational_std);
00653 fprintf(pFile, " translational_min= %f\n", translational_min);
00654 fprintf(pFile, " translational_max= %f\n", translational_max);
00655 fprintf(pFile, " rotational_rmse= %f\n", rotational_rmse);
00656 fprintf(pFile, " rotational_mean= %f\n", rotational_mean);
00657 fprintf(pFile, " rotational_median= %f\n", rotational_median);
00658 fprintf(pFile, " rotational_std= %f\n", rotational_std);
00659 fprintf(pFile, " rotational_min= %f\n", rotational_min);
00660 fprintf(pFile, " rotational_max= %f\n", rotational_max);
00661 fclose(pFile);
00662 }
00663 }
00664 else
00665 {
00666 UERROR("Camera init failed!");
00667 }
00668
00669 printf("Saving rtabmap database (with all statistics) to \"%s\"\n", (output+"/"+outputName+".db").c_str());
00670 printf("Do:\n"
00671 " $ rtabmap-databaseViewer %s\n\n", (output+"/"+outputName+".db").c_str());
00672
00673 return 0;
00674 }