Go to the documentation of this file.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/Rtabmap.h"
00029 #include "rtabmap/core/Camera.h"
00030 #include <opencv2/core/core.hpp>
00031 #include "rtabmap/utilite/UFile.h"
00032 #include <stdio.h>
00033
00034 void showUsage()
00035 {
00036 printf("\nUsage:\n"
00037 "rtabmap-bow_mapping [options] \"path\"\n"
00038 " path Path to a directory of images\n "
00039 " Options:"
00040 " -l localization mode: use already built RTAB-Map database to localize\n ");
00041 exit(1);
00042 }
00043
00044 int main(int argc, char * argv[])
00045 {
00046
00047
00048
00049 std::string path;
00050 bool localizationMode = false;
00051
00052 if(argc < 2)
00053 {
00054 showUsage();
00055 }
00056
00057 for(int i=1; i<argc-1; ++i)
00058 {
00059 if(strcmp(argv[i], "-l") == 0)
00060 {
00061 localizationMode = true;
00062 }
00063 else
00064 {
00065 printf("Unrecognized option \"%s\"\n", argv[i]);
00066 showUsage();
00067 }
00068 }
00069
00070 path = argv[argc-1];
00071
00072
00073 rtabmap::CameraImages camera(path);
00074 if(!camera.init())
00075 {
00076 printf("Camera init failed, using path \"%s\"\n", path.c_str());
00077 exit(1);
00078 }
00079
00080
00081 rtabmap::Rtabmap rtabmap;
00082
00083
00084 rtabmap.setTimeThreshold(700.0f);
00085
00086
00087
00088
00089 rtabmap::ParametersMap parameters;
00090 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRtabmapLoopThr(), "0.11"));
00091
00092
00093
00094
00095
00096
00097
00098 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDEnabled(), "false"));
00099
00100 std::string databasePath = rtabmap::Parameters::defaultRtabmapWorkingDirectory()+"/"+rtabmap::Parameters::getDefaultDatabaseName();
00101 if(localizationMode)
00102 {
00103 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemIncrementalMemory(), "false"));
00104 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kKpIncrementalDictionary(), "false"));
00105 parameters.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemSTMSize(), "1"));
00106 }
00107 else
00108 {
00109
00110 UFile::erase(databasePath);
00111 }
00112
00113
00114 rtabmap.init(parameters, databasePath);
00115
00116
00117 printf("\nProcessing images... from directory \"%s\"\n", path.c_str());
00118
00119 int countLoopDetected=0;
00120 int i=0;
00121 cv::Mat img = camera.takeImage();
00122 int nextIndex = rtabmap.getLastLocationId()+1;
00123 while(!img.empty())
00124 {
00125
00126 rtabmap.process(img, nextIndex);
00127
00128
00129 if(rtabmap.getLoopClosureId())
00130 {
00131 ++countLoopDetected;
00132 }
00133 ++i;
00134 if(rtabmap.getLoopClosureId())
00135 {
00136 printf(" #%d ptime(%fs) STM(%d) WM(%d) hyp(%d) value(%.2f) *LOOP %d->%d*\n",
00137 i,
00138 rtabmap.getLastProcessTime(),
00139 (int)rtabmap.getSTM().size(),
00140 (int)rtabmap.getWM().size(),
00141 rtabmap.getLoopClosureId(),
00142 rtabmap.getLoopClosureValue(),
00143 nextIndex,
00144 rtabmap.getLoopClosureId());
00145 }
00146 else
00147 {
00148 printf(" #%d ptime(%fs) STM(%d) WM(%d) hyp(%d) value(%.2f)\n",
00149 i,
00150 rtabmap.getLastProcessTime(),
00151 (int)rtabmap.getSTM().size(),
00152 (int)rtabmap.getWM().size(),
00153 rtabmap.getHighestHypothesisId(),
00154 rtabmap.getLoopClosureValue());
00155 }
00156
00157 ++nextIndex;
00158
00159
00160 img = camera.takeImage();
00161 }
00162
00163 printf("Processing images completed. Loop closures found = %d\n", countLoopDetected);
00164
00165
00166 rtabmap.generateDOTGraph("Graph.dot");
00167 printf("Generated graph \"Graph.dot\", viewable with Graphiz using \"neato -Tpdf Graph.dot -o out.pdf\"\n");
00168
00169
00170 printf("Saving Long-Term Memory to \"rtabmap.db\"...\n");
00171 rtabmap.close();
00172
00173 return 0;
00174 }