main.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <rtabmap/core/OdometryF2M.h>
00029 #include "rtabmap/core/Rtabmap.h"
00030 #include "rtabmap/core/CameraRGBD.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-rgbd_dataset [options] path\n"
00053                         "  path               Folder of the sequence (e.g., \"~/rgbd_dataset_freiburg3_long_office_household\")\n"
00054                         "                        containing least rgb_sync and depth_sync folders. These folders contain\n"
00055                         "                        synchronized images using associate.py tool (use tool version from\n"
00056                         "                        https://gist.github.com/matlabbe/484134a2d9da8ad425362c6669824798). If \n"
00057                         "                        \"groundtruth.txt\" is found in the sequence folder, they will be saved in the database.\n"
00058                         "  --output           Output directory. By default, results are saved in \"path\".\n"
00059                         "  --output_name      Output database name (default \"rtabmap\").\n"
00060                         "  --quiet            Don't show log messages and iteration updates.\n"
00061                         "%s\n"
00062                         "Example:\n\n"
00063                         "   $ rtabmap-rgbd_dataset \\\n"
00064                         "       --Rtabmap/PublishRAMUsage true\\\n"
00065                         "       --Rtabmap/DetectionRate 2\\\n"
00066                         "       --RGBD/LinearUpdate 0\\\n"
00067                         "       --Mem/STMSize 30\\\n"
00068                         "       ~/rgbd_dataset_freiburg3_long_office_household\n\n", rtabmap::Parameters::showUsage());
00069         exit(1);
00070 }
00071 
00072 // catch ctrl-c
00073 bool g_forever = true;
00074 void sighandler(int sig)
00075 {
00076         printf("\nSignal %d caught...\n", sig);
00077         g_forever = false;
00078 }
00079 
00080 int main(int argc, char * argv[])
00081 {
00082         signal(SIGABRT, &sighandler);
00083         signal(SIGTERM, &sighandler);
00084         signal(SIGINT, &sighandler);
00085 
00086         ULogger::setType(ULogger::kTypeConsole);
00087         ULogger::setLevel(ULogger::kWarning);
00088 
00089         ParametersMap parameters;
00090         std::string path;
00091         std::string output;
00092         std::string outputName = "rtabmap";
00093         bool quiet = false;
00094         if(argc < 2)
00095         {
00096                 showUsage();
00097         }
00098         else
00099         {
00100                 for(int i=1; i<argc; ++i)
00101                 {
00102                         if(std::strcmp(argv[i], "--output") == 0)
00103                         {
00104                                 output = argv[++i];
00105                         }
00106                         else if(std::strcmp(argv[i], "--output_name") == 0)
00107                         {
00108                                 outputName = argv[++i];
00109                         }
00110                         else if(std::strcmp(argv[i], "--quiet") == 0)
00111                         {
00112                                 quiet = true;
00113                         }
00114                 }
00115                 parameters = Parameters::parseArguments(argc, argv);
00116                 path = argv[argc-1];
00117                 path = uReplaceChar(path, '~', UDirectory::homeDir());
00118                 path = uReplaceChar(path, '\\', '/');
00119                 if(output.empty())
00120                 {
00121                         output = path;
00122                 }
00123                 else
00124                 {
00125                         output = uReplaceChar(output, '~', UDirectory::homeDir());
00126                         UDirectory::makeDir(output);
00127                 }
00128                 parameters.insert(ParametersPair(Parameters::kRtabmapWorkingDirectory(), output));
00129                 parameters.insert(ParametersPair(Parameters::kRtabmapPublishRAMUsage(), "true"));
00130         }
00131 
00132         std::string seq = uSplit(path, '/').back();
00133         std::string pathRgbImages  = path+"/rgb_sync";
00134         std::string pathDepthImages = path+"/depth_sync";
00135         std::string pathGt = path+"/groundtruth.txt";
00136         if(!UFile::exists(pathGt))
00137         {
00138                 UWARN("Ground truth file path doesn't exist: \"%s\", benchmark values won't be computed.", pathGt.c_str());
00139                 pathGt.clear();
00140         }
00141 
00142         if(quiet)
00143         {
00144                 ULogger::setLevel(ULogger::kError);
00145         }
00146 
00147         printf("Paths:\n"
00148                         "   Dataset name:    %s\n"
00149                         "   Dataset path:    %s\n"
00150                         "   RGB path:        %s\n"
00151                         "   Depth path:      %s\n"
00152                         "   Output:          %s\n"
00153                         "   Output name:     %s\n",
00154                         seq.c_str(),
00155                         path.c_str(),
00156                         pathRgbImages.c_str(),
00157                         pathDepthImages.c_str(),
00158                         output.c_str(),
00159                         outputName.c_str());
00160         if(!pathGt.empty())
00161         {
00162                 printf("   groundtruth.txt: %s\n", pathGt.c_str());
00163         }
00164         if(!parameters.empty())
00165         {
00166                 printf("Parameters:\n");
00167                 for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
00168                 {
00169                         printf("   %s=%s\n", iter->first.c_str(), iter->second.c_str());
00170                 }
00171         }
00172         printf("RTAB-Map version: %s\n", RTABMAP_VERSION);
00173 
00174         // setup calibration file
00175         CameraModel model;
00176         std::string sequenceName = UFile(path).getName();
00177         Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
00178         float depthFactor = 5.0f;
00179         if(sequenceName.find("freiburg1") != std::string::npos)
00180         {
00181                 model = CameraModel(outputName+"_calib", 517.3, 516.5, 318.6, 255.3, opticalRotation, 0, cv::Size(640,480));
00182         }
00183         else if(sequenceName.find("freiburg2") != std::string::npos)
00184         {
00185                 model = CameraModel(outputName+"_calib", 520.9, 521.0, 325.1, 249.7, opticalRotation, 0, cv::Size(640,480));
00186         }
00187         else //if(sequenceName.find("freiburg3") != std::string::npos)
00188         {
00189                 model = CameraModel(outputName+"_calib", 535.4, 539.2, 320.1, 247.6, opticalRotation, 0, cv::Size(640,480));
00190         }
00191         //parameters.insert(ParametersPair(Parameters::kg2oBaseline(), uNumber2Str(40.0f/model.fx())));
00192         model.save(path);
00193 
00194         CameraThread cameraThread(new
00195                 CameraRGBDImages(
00196                                 pathRgbImages,
00197                                 pathDepthImages,
00198                                 depthFactor,
00199                                 0.0f,
00200                                 opticalRotation), parameters);
00201         ((CameraRGBDImages*)cameraThread.camera())->setTimestamps(true, "", false);
00202         if(!pathGt.empty())
00203         {
00204                 ((CameraRGBDImages*)cameraThread.camera())->setGroundTruthPath(pathGt, 1);
00205         }
00206 
00207         bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
00208         float detectionRate = Parameters::defaultRtabmapDetectionRate();
00209         int odomStrategy = Parameters::defaultOdomStrategy();
00210         Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
00211         Parameters::parse(parameters, Parameters::kOdomStrategy(), odomStrategy);
00212         Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
00213         std::string databasePath = output+"/"+outputName+".db";
00214         UFile::erase(databasePath);
00215         if(cameraThread.camera()->init(path, outputName+"_calib"))
00216         {
00217                 int totalImages = (int)((CameraRGBDImages*)cameraThread.camera())->filenames().size();
00218 
00219                 printf("Processing %d images...\n", totalImages);
00220 
00221                 ParametersMap odomParameters = parameters;
00222                 odomParameters.erase(Parameters::kRtabmapPublishRAMUsage()); // as odometry is in the same process than rtabmap, don't get RAM usage in odometry.
00223                 Odometry * odom = Odometry::create(odomParameters);
00224                 Rtabmap rtabmap;
00225                 rtabmap.init(parameters, databasePath);
00226 
00227                 UTimer totalTime;
00228                 UTimer timer;
00229                 CameraInfo cameraInfo;
00230                 SensorData data = cameraThread.camera()->takeImage(&cameraInfo);
00231                 int iteration = 0;
00232 
00234                 // Processing dataset begin
00236                 cv::Mat covariance;
00237                 int odomKeyFrames = 0;
00238                 double previousStamp = 0.0;
00239                 while(data.isValid() && g_forever)
00240                 {
00241                         cameraThread.postUpdate(&data, &cameraInfo);
00242                         cameraInfo.timeTotal = timer.ticks();
00243 
00244                         OdometryInfo odomInfo;
00245                         Transform pose = odom->process(data, &odomInfo);
00246 
00247                         if(odomStrategy == 2)
00248                         {
00249                                 //special case for FOVIS, set covariance 1 if 9999 is detected
00250                                 if(!odomInfo.reg.covariance.empty() && odomInfo.reg.covariance.at<double>(0,0) >= 9999)
00251                                 {
00252                                         odomInfo.reg.covariance = cv::Mat::eye(6,6,CV_64FC1);
00253                                 }
00254                         }
00255 
00256                         if(odomInfo.keyFrameAdded)
00257                         {
00258                                 ++odomKeyFrames;
00259                         }
00260 
00261                         bool processData = true;
00262                         if(detectionRate>0.0f &&
00263                                 previousStamp>0.0 &&
00264                                 data.stamp()>previousStamp && data.stamp() - previousStamp < 1.0/detectionRate)
00265                         {
00266                                 processData = false;
00267                         }
00268 
00269                         if(processData)
00270                         {
00271                                 previousStamp = data.stamp();
00272                         }
00273 
00274                         if(!processData)
00275                         {
00276                                 // set negative id so rtabmap will detect it as an intermediate node
00277                                 data.setId(-1);
00278                                 data.setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());// remove features
00279                                 processData = intermediateNodes;
00280                         }
00281                         if(covariance.empty() || odomInfo.reg.covariance.at<double>(0,0) > covariance.at<double>(0,0))
00282                         {
00283                                 covariance = odomInfo.reg.covariance;
00284                         }
00285 
00286                         timer.restart();
00287                         if(processData)
00288                         {
00289                                 std::map<std::string, float> externalStats;
00290                                 // save camera statistics to database
00291                                 externalStats.insert(std::make_pair("Camera/BilateralFiltering/ms", cameraInfo.timeBilateralFiltering*1000.0f));
00292                                 externalStats.insert(std::make_pair("Camera/Capture/ms", cameraInfo.timeCapture*1000.0f));
00293                                 externalStats.insert(std::make_pair("Camera/Disparity/ms", cameraInfo.timeDisparity*1000.0f));
00294                                 externalStats.insert(std::make_pair("Camera/ImageDecimation/ms", cameraInfo.timeImageDecimation*1000.0f));
00295                                 externalStats.insert(std::make_pair("Camera/Mirroring/ms", cameraInfo.timeMirroring*1000.0f));
00296                                 externalStats.insert(std::make_pair("Camera/ExposureCompensation/ms", cameraInfo.timeStereoExposureCompensation*1000.0f));
00297                                 externalStats.insert(std::make_pair("Camera/ScanFromDepth/ms", cameraInfo.timeScanFromDepth*1000.0f));
00298                                 externalStats.insert(std::make_pair("Camera/TotalTime/ms", cameraInfo.timeTotal*1000.0f));
00299                                 externalStats.insert(std::make_pair("Camera/UndistortDepth/ms", cameraInfo.timeUndistortDepth*1000.0f));
00300                                 // save odometry statistics to database
00301                                 externalStats.insert(std::make_pair("Odometry/LocalBundle/ms", odomInfo.localBundleTime*1000.0f));
00302                                 externalStats.insert(std::make_pair("Odometry/LocalBundleConstraints/", odomInfo.localBundleConstraints));
00303                                 externalStats.insert(std::make_pair("Odometry/LocalBundleOutliers/", odomInfo.localBundleOutliers));
00304                                 externalStats.insert(std::make_pair("Odometry/TotalTime/ms", odomInfo.timeEstimation*1000.0f));
00305                                 externalStats.insert(std::make_pair("Odometry/Registration/ms", odomInfo.reg.totalTime*1000.0f));
00306                                 externalStats.insert(std::make_pair("Odometry/Inliers/", odomInfo.reg.inliers));
00307                                 externalStats.insert(std::make_pair("Odometry/Features/", odomInfo.features));
00308                                 externalStats.insert(std::make_pair("Odometry/DistanceTravelled/m", odomInfo.distanceTravelled));
00309                                 externalStats.insert(std::make_pair("Odometry/KeyFrameAdded/", odomInfo.keyFrameAdded));
00310                                 externalStats.insert(std::make_pair("Odometry/LocalKeyFrames/", odomInfo.localKeyFrames));
00311                                 externalStats.insert(std::make_pair("Odometry/LocalMapSize/", odomInfo.localMapSize));
00312                                 externalStats.insert(std::make_pair("Odometry/LocalScanMapSize/", odomInfo.localScanMapSize));
00313 
00314                                 OdometryEvent e(SensorData(), Transform(), odomInfo);
00315                                 rtabmap.process(data, pose, covariance, e.velocity(), externalStats);
00316                                 covariance = cv::Mat();
00317                         }
00318 
00319                         ++iteration;
00320                         if(!quiet || iteration == totalImages)
00321                         {
00322                                 double slamTime = timer.ticks();
00323 
00324                                 float rmse = -1;
00325                                 if(rtabmap.getStatistics().data().find(Statistics::kGtTranslational_rmse()) != rtabmap.getStatistics().data().end())
00326                                 {
00327                                         rmse = rtabmap.getStatistics().data().at(Statistics::kGtTranslational_rmse());
00328                                 }
00329 
00330                                 if(rmse >= 0.0f)
00331                                 {
00332                                         //printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm, noise stddev=%fm %frad",
00333                                         //              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)));
00334                                         printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm",
00335                                                         iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f), rmse);
00336                                 }
00337                                 else
00338                                 {
00339                                         printf("Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
00340                                                         iteration, totalImages, int(cameraInfo.timeTotal*1000.0f), odomInfo.reg.inliers, odomInfo.features, odomKeyFrames, int(odomInfo.timeEstimation*1000.0f), int(slamTime*1000.0f));
00341                                 }
00342                                 if(processData && rtabmap.getLoopClosureId()>0)
00343                                 {
00344                                         printf(" *");
00345                                 }
00346                                 printf("\n");
00347                         }
00348                         else if(iteration % (totalImages/10) == 0)
00349                         {
00350                                 printf(".");
00351                                 fflush(stdout);
00352                         }
00353 
00354                         cameraInfo = CameraInfo();
00355                         timer.restart();
00356                         data = cameraThread.camera()->takeImage(&cameraInfo);
00357                 }
00358                 delete odom;
00359                 printf("Total time=%fs\n", totalTime.ticks());
00361                 // Processing dataset end
00363 
00364                 // Save trajectory
00365                 printf("Saving trajectory...\n");
00366                 std::map<int, Transform> poses;
00367                 std::multimap<int, Link> links;
00368                 std::map<int, Signature> signatures;
00369                 std::map<int, double> stamps;
00370                 rtabmap.getGraph(poses, links, true, true, &signatures);
00371                 for(std::map<int, Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
00372                 {
00373                         stamps.insert(std::make_pair(iter->first, iter->second.getStamp()));
00374                 }
00375                 std::string pathTrajectory = output+"/"+outputName+"_poses.txt";
00376                 if(poses.size() && graph::exportPoses(pathTrajectory, 1, poses, links, stamps))
00377                 {
00378                         printf("Saving %s... done!\n", pathTrajectory.c_str());
00379                 }
00380                 else
00381                 {
00382                         printf("Saving %s... failed!\n", pathTrajectory.c_str());
00383                 }
00384 
00385                 if(!pathGt.empty())
00386                 {
00387                         // Log ground truth statistics
00388                         std::map<int, Transform> groundTruth;
00389 
00390                         for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00391                         {
00392                                 Transform o, gtPose;
00393                                 int m,w;
00394                                 std::string l;
00395                                 double s;
00396                                 std::vector<float> v;
00397                                 GPS gps;
00398                                 rtabmap.getMemory()->getNodeInfo(iter->first, o, m, w, l, s, gtPose, v, gps, true);
00399                                 if(!gtPose.isNull())
00400                                 {
00401                                         groundTruth.insert(std::make_pair(iter->first, gtPose));
00402                                 }
00403                         }
00404 
00405 
00406                         // compute RMSE statistics
00407                         float translational_rmse = 0.0f;
00408                         float translational_mean = 0.0f;
00409                         float translational_median = 0.0f;
00410                         float translational_std = 0.0f;
00411                         float translational_min = 0.0f;
00412                         float translational_max = 0.0f;
00413                         float rotational_rmse = 0.0f;
00414                         float rotational_mean = 0.0f;
00415                         float rotational_median = 0.0f;
00416                         float rotational_std = 0.0f;
00417                         float rotational_min = 0.0f;
00418                         float rotational_max = 0.0f;
00419                         graph::calcRMSE(
00420                                         groundTruth,
00421                                         poses,
00422                                         translational_rmse,
00423                                         translational_mean,
00424                                         translational_median,
00425                                         translational_std,
00426                                         translational_min,
00427                                         translational_max,
00428                                         rotational_rmse,
00429                                         rotational_mean,
00430                                         rotational_median,
00431                                         rotational_std,
00432                                         rotational_min,
00433                                         rotational_max);
00434 
00435                         printf("   translational_rmse=   %f m\n", translational_rmse);
00436                         printf("   rotational_rmse=      %f deg\n", rotational_rmse);
00437 
00438                         FILE * pFile = 0;
00439                         std::string pathErrors = output+"/"+outputName+"_rmse.txt";
00440                         pFile = fopen(pathErrors.c_str(),"w");
00441                         if(!pFile)
00442                         {
00443                                 UERROR("could not save RMSE results to \"%s\"", pathErrors.c_str());
00444                         }
00445                         fprintf(pFile, "Ground truth comparison:\n");
00446                         fprintf(pFile, "  translational_rmse=   %f\n", translational_rmse);
00447                         fprintf(pFile, "  translational_mean=   %f\n", translational_mean);
00448                         fprintf(pFile, "  translational_median= %f\n", translational_median);
00449                         fprintf(pFile, "  translational_std=    %f\n", translational_std);
00450                         fprintf(pFile, "  translational_min=    %f\n", translational_min);
00451                         fprintf(pFile, "  translational_max=    %f\n", translational_max);
00452                         fprintf(pFile, "  rotational_rmse=      %f\n", rotational_rmse);
00453                         fprintf(pFile, "  rotational_mean=      %f\n", rotational_mean);
00454                         fprintf(pFile, "  rotational_median=    %f\n", rotational_median);
00455                         fprintf(pFile, "  rotational_std=       %f\n", rotational_std);
00456                         fprintf(pFile, "  rotational_min=       %f\n", rotational_min);
00457                         fprintf(pFile, "  rotational_max=       %f\n", rotational_max);
00458                         fclose(pFile);
00459                 }
00460         }
00461         else
00462         {
00463                 UERROR("Camera init failed!");
00464         }
00465 
00466         printf("Saving rtabmap database (with all statistics) to \"%s\"\n", (output+"/"+outputName+".db").c_str());
00467         printf("Do:\n"
00468                         " $ rtabmap-databaseViewer %s\n\n", (output+"/"+outputName+".db").c_str());
00469 
00470         return 0;
00471 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20