tools/Reprocess/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/Rtabmap.h>
29 #include <rtabmap/core/DBDriver.h>
30 #include <rtabmap/core/DBReader.h>
31 #ifdef RTABMAP_OCTOMAP
32 #include <rtabmap/core/OctoMap.h>
33 #endif
35 #include <rtabmap/utilite/UFile.h>
37 #include <rtabmap/utilite/UTimer.h>
38 #include <rtabmap/utilite/UStl.h>
39 #include <stdio.h>
40 #include <string.h>
41 #include <stdlib.h>
42 #include <pcl/io/pcd_io.h>
43 #include <signal.h>
44 
45 using namespace rtabmap;
46 
47 void showUsage()
48 {
49  printf("\nUsage:\n"
50  "rtabmap-reprocess [options] \"input.db\" \"output.db\"\n"
51  " Options:\n"
52  " -r Use database stamps as input rate.\n"
53  " -g2 Assemble 2D occupancy grid map and save it to \"[output]_map.pgm\".\n"
54  " -g3 Assemble 3D cloud map and save it to \"[output]_map.pcd\".\n"
55  " -o2 Assemble OctoMap 2D projection and save it to \"[output]_octomap.pgm\".\n"
56  " -o3 Assemble OctoMap 3D cloud and save it to \"[output]_octomap.pcd\".\n"
57  "%s\n"
58  "\n", Parameters::showUsage());
59  exit(1);
60 }
61 
62 // catch ctrl-c
63 bool g_loopForever = true;
64 void sighandler(int sig)
65 {
66  printf("\nSignal %d caught...\n", sig);
67  g_loopForever = false;
68 }
69 
70 int main(int argc, char * argv[])
71 {
72  signal(SIGABRT, &sighandler);
73  signal(SIGTERM, &sighandler);
74  signal(SIGINT, &sighandler);
75 
78 
79  if(argc < 3)
80  {
81  showUsage();
82  }
83 
84  bool assemble2dMap = false;
85  bool assemble3dMap = false;
86  bool assemble2dOctoMap = false;
87  bool assemble3dOctoMap = false;
88  bool useDatabaseRate = false;
89  for(int i=1; i<argc-2; ++i)
90  {
91  if(strcmp(argv[i], "-r") == 0)
92  {
93  useDatabaseRate = true;
94  printf("Using database stamps as input rate.\n");
95  }
96  else if(strcmp(argv[i], "-g2") == 0)
97  {
98  assemble2dMap = true;
99  printf("2D occupancy grid will be assembled (-g2 option).\n");
100  }
101  else if(strcmp(argv[i], "-g3") == 0)
102  {
103  assemble3dMap = true;
104  printf("3D cloud map will be assembled (-g3 option).\n");
105  }
106  else if(strcmp(argv[i], "-o2") == 0)
107  {
108 #ifdef RTABMAP_OCTOMAP
109  assemble2dOctoMap = true;
110  printf("OctoMap will be assembled (-o2 option).\n");
111 #else
112  printf("RTAB-Map is not built with OctoMap support, cannot set -o2 option!\n");
113 #endif
114  }
115  else if(strcmp(argv[i], "-o3") == 0)
116  {
117 #ifdef RTABMAP_OCTOMAP
118  assemble3dOctoMap = true;
119  printf("OctoMap will be assembled (-o3 option).\n");
120 #else
121  printf("RTAB-Map is not built with OctoMap support, cannot set -o3 option!\n");
122 #endif
123  }
124  }
125 
126  ParametersMap customParameters = Parameters::parseArguments(argc, argv);
127 
128  std::string inputDatabasePath = uReplaceChar(argv[argc-2], '~', UDirectory::homeDir());
129  std::string outputDatabasePath = uReplaceChar(argv[argc-1], '~', UDirectory::homeDir());
130 
131  if(!UFile::exists(inputDatabasePath))
132  {
133  printf("Input database \"%s\" doesn't exist!\n", inputDatabasePath.c_str());
134  return -1;
135  }
136 
137  if(UFile::getExtension(inputDatabasePath).compare("db") != 0)
138  {
139  printf("File \"%s\" is not a database format (*.db)!\n", inputDatabasePath.c_str());
140  return -1;
141  }
142  if(UFile::getExtension(outputDatabasePath).compare("db") != 0)
143  {
144  printf("File \"%s\" is not a database format (*.db)!\n", outputDatabasePath.c_str());
145  return -1;
146  }
147 
148  if(UFile::exists(outputDatabasePath))
149  {
150  UFile::erase(outputDatabasePath);
151  }
152 
153  DBDriver * dbDriver = DBDriver::create();
154  if(!dbDriver->openConnection(inputDatabasePath, false))
155  {
156  printf("Failed opening input database!\n");
157  delete dbDriver;
158  return -1;
159  }
160 
161  ParametersMap parameters = dbDriver->getLastParameters();
162  if(parameters.empty())
163  {
164  printf("Failed getting parameters from database, reprocessing cannot be done. Database version may be too old.\n");
165  dbDriver->closeConnection(false);
166  delete dbDriver;
167  return -1;
168  }
169  if(customParameters.size())
170  {
171  printf("Custom parameters:\n");
172  for(ParametersMap::iterator iter=customParameters.begin(); iter!=customParameters.end(); ++iter)
173  {
174  printf(" %s\t= %s\n", iter->first.c_str(), iter->second.c_str());
175  }
176  }
177  uInsert(parameters, customParameters);
178  std::set<int> ids;
179  dbDriver->getAllNodeIds(ids);
180  if(ids.empty())
181  {
182  printf("Input database doesn't have any nodes saved in it.\n");
183  dbDriver->closeConnection(false);
184  delete dbDriver;
185  return -1;
186  }
187 
188  dbDriver->closeConnection(false);
189  delete dbDriver;
190 
192  rtabmap.init(parameters, outputDatabasePath);
193 
194  bool rgbdEnabled = Parameters::defaultRGBDEnabled();
195  Parameters::parse(parameters, Parameters::kRGBDEnabled(), rgbdEnabled);
196  bool odometryIgnored = !rgbdEnabled;
197  DBReader dbReader(inputDatabasePath, useDatabaseRate?-1:0, odometryIgnored);
198  dbReader.init();
199 
200  OccupancyGrid grid(parameters);
201  grid.setCloudAssembling(assemble3dMap);
202 #ifdef RTABMAP_OCTOMAP
203  OctoMap octomap(parameters);
204 #endif
205 
206  printf("Reprocessing data of \"%s\"...\n", inputDatabasePath.c_str());
207  std::map<std::string, float> globalMapStats;
208  int processed = 0;
209  CameraInfo info;
210  SensorData data = dbReader.takeImage(&info);
211  while(data.isValid() && g_loopForever)
212  {
213  UTimer iterationTime;
214  std::string status;
215  if(!odometryIgnored && info.odomPose.isNull())
216  {
217  printf("Skipping node %d as it doesn't have odometry pose set.\n", data.id());
218  }
219  else
220  {
221  if(!odometryIgnored && !info.odomCovariance.empty() && info.odomCovariance.at<double>(0,0)>=9999)
222  {
223  printf("High variance detected, triggering a new map...\n");
224  rtabmap.triggerNewMap();
225  }
226  UTimer t;
227  if(!rtabmap.process(data, info.odomPose, info.odomCovariance, info.odomVelocity, globalMapStats))
228  {
229  printf("Failed processing node %d.\n", data.id());
230  globalMapStats.clear();
231  }
232  else if(assemble2dMap || assemble3dMap || assemble2dOctoMap || assemble3dOctoMap)
233  {
234  globalMapStats.clear();
235  double timeRtabmap = t.ticks();
236  double timeUpdateInit = 0.0;
237  double timeUpdateGrid = 0.0;
238 #ifdef RTABMAP_OCTOMAP
239  double timeUpdateOctoMap = 0.0;
240 #endif
241  const rtabmap::Statistics & stats = rtabmap.getStatistics();
242  if(stats.poses().size() && stats.getSignatures().size())
243  {
244  int id = stats.poses().rbegin()->first;
245  if(stats.getSignatures().find(id)!=stats.getSignatures().end() &&
246  stats.getSignatures().find(id)->second.sensorData().gridCellSize() > 0.0f)
247  {
248  bool updateGridMap = false;
249  bool updateOctoMap = false;
250  if((assemble2dMap || assemble3dMap) && grid.addedNodes().find(id) == grid.addedNodes().end())
251  {
252  updateGridMap = true;
253  }
254 #ifdef RTABMAP_OCTOMAP
255  if((assemble2dOctoMap || assemble3dOctoMap) && octomap.addedNodes().find(id) == octomap.addedNodes().end())
256  {
257  updateOctoMap = true;
258  }
259 #endif
260  if(updateGridMap || updateOctoMap)
261  {
262  cv::Mat ground, obstacles, empty;
263  stats.getSignatures().find(id)->second.sensorData().uncompressDataConst(0, 0, 0, 0, &ground, &obstacles, &empty);
264 
265  timeUpdateInit = t.ticks();
266 
267  if(updateGridMap)
268  {
269  grid.addToCache(id, ground, obstacles, empty);
270  grid.update(stats.poses());
271  timeUpdateGrid = t.ticks() + timeUpdateInit;
272  }
273 #ifdef RTABMAP_OCTOMAP
274  if(updateOctoMap)
275  {
276  const cv::Point3f & viewpoint = stats.getSignatures().find(id)->second.sensorData().gridViewPoint();
277  octomap.addToCache(id, ground, obstacles, empty, viewpoint);
278  octomap.update(stats.poses());
279  timeUpdateOctoMap = t.ticks() + timeUpdateInit;
280  }
281 #endif
282  }
283  }
284  }
285 
286  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/GridUpdate/ms"), timeUpdateGrid*1000.0f));
287 #ifdef RTABMAP_OCTOMAP
288  //Simulate publishing
289  double timePub2dOctoMap = 0.0;
290  double timePub3dOctoMap = 0.0;
291  if(assemble2dOctoMap)
292  {
293  float xMin, yMin, size;
294  octomap.createProjectionMap(xMin, yMin, size);
295  timePub2dOctoMap = t.ticks();
296  }
297  if(assemble3dOctoMap)
298  {
299  octomap.createCloud();
300  timePub3dOctoMap = t.ticks();
301  }
302 
303  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/OctoMapUpdate/ms"), timeUpdateOctoMap*1000.0f));
304  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/OctoMapProjection/ms"), timePub2dOctoMap*1000.0f));
305  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/OctomapToCloud/ms"), timePub3dOctoMap*1000.0f));
306  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/TotalWithRtabmap/ms"), (timeUpdateGrid+timeUpdateOctoMap+timePub2dOctoMap+timePub3dOctoMap+timeRtabmap)*1000.0f));
307 #else
308  globalMapStats.insert(std::make_pair(std::string("GlobalGrid/TotalWithRtabmap/ms"), (timeUpdateGrid+timeRtabmap)*1000.0f));
309 #endif
310  }
311  }
312 
313  printf("Processed %d/%d nodes... %dms\n", ++processed, (int)ids.size(), int(iterationTime.ticks()*1000));
314 
315  data = dbReader.takeImage(&info);
316  }
317 
318  printf("Closing database \"%s\"...\n", outputDatabasePath.c_str());
319  rtabmap.close(true);
320  printf("Closing database \"%s\"... done!\n", outputDatabasePath.c_str());
321 
322  if(assemble2dMap)
323  {
324  std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_map.pgm";
325  float xMin,yMin;
326  cv::Mat map = grid.getMap(xMin, yMin);
327  if(!map.empty())
328  {
329  cv::Mat map8U(map.rows, map.cols, CV_8U);
330  //convert to gray scaled map
331  for (int i = 0; i < map.rows; ++i)
332  {
333  for (int j = 0; j < map.cols; ++j)
334  {
335  char v = map.at<char>(i, j);
336  unsigned char gray;
337  if(v == 0)
338  {
339  gray = 178;
340  }
341  else if(v == 100)
342  {
343  gray = 0;
344  }
345  else // -1
346  {
347  gray = 89;
348  }
349  map8U.at<unsigned char>(i, j) = gray;
350  }
351  }
352  if(cv::imwrite(outputPath, map8U))
353  {
354  printf("Saving occupancy grid \"%s\"... done!\n", outputPath.c_str());
355  }
356  else
357  {
358  printf("Saving occupancy grid \"%s\"... failed!\n", outputPath.c_str());
359  }
360  }
361  else
362  {
363  printf("2D map is empty! Cannot save it!\n");
364  }
365  }
366  if(assemble3dMap)
367  {
368  std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_obstacles.pcd";
369  if(pcl::io::savePCDFileBinary(outputPath, *grid.getMapObstacles()) == 0)
370  {
371  printf("Saving 3d obstacles \"%s\"... done!\n", outputPath.c_str());
372  }
373  else
374  {
375  printf("Saving 3d obstacles \"%s\"... failed!\n", outputPath.c_str());
376  }
377  if(grid.getMapGround()->size())
378  {
379  outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_ground.pcd";
380  if(pcl::io::savePCDFileBinary(outputPath, *grid.getMapGround()) == 0)
381  {
382  printf("Saving 3d ground \"%s\"... done!\n", outputPath.c_str());
383  }
384  else
385  {
386  printf("Saving 3d ground \"%s\"... failed!\n", outputPath.c_str());
387  }
388  }
389  if(grid.getMapEmptyCells()->size())
390  {
391  outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_empty.pcd";
392  if(pcl::io::savePCDFileBinary(outputPath, *grid.getMapEmptyCells()) == 0)
393  {
394  printf("Saving 3d empty cells \"%s\"... done!\n", outputPath.c_str());
395  }
396  else
397  {
398  printf("Saving 3d empty cells \"%s\"... failed!\n", outputPath.c_str());
399  }
400  }
401  }
402 #ifdef RTABMAP_OCTOMAP
403  if(assemble2dOctoMap)
404  {
405  std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_octomap.pgm";
406  float xMin,yMin,cellSize;
407  cv::Mat map = octomap.createProjectionMap(xMin, yMin, cellSize);
408  if(!map.empty())
409  {
410  cv::Mat map8U(map.rows, map.cols, CV_8U);
411  //convert to gray scaled map
412  for (int i = 0; i < map.rows; ++i)
413  {
414  for (int j = 0; j < map.cols; ++j)
415  {
416  char v = map.at<char>(i, j);
417  unsigned char gray;
418  if(v == 0)
419  {
420  gray = 178;
421  }
422  else if(v == 100)
423  {
424  gray = 0;
425  }
426  else // -1
427  {
428  gray = 89;
429  }
430  map8U.at<unsigned char>(i, j) = gray;
431  }
432  }
433  if(cv::imwrite(outputPath, map8U))
434  {
435  printf("Saving octomap 2D projection \"%s\"... done!\n", outputPath.c_str());
436  }
437  else
438  {
439  printf("Saving octomap 2D projection \"%s\"... failed!\n", outputPath.c_str());
440  }
441  }
442  else
443  {
444  printf("OctoMap 2D projection map is empty! Cannot save it!\n");
445  }
446  }
447  if(assemble3dOctoMap)
448  {
449  std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_octomap_occupied.pcd";
450  std::vector<int> obstacles, emptySpace, ground;
451  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = octomap.createCloud(0, &obstacles, &emptySpace, &ground);
452  if(pcl::io::savePCDFile(outputPath, *cloud, obstacles, true) == 0)
453  {
454  printf("Saving obstacles cloud \"%s\"... done!\n", outputPath.c_str());
455  }
456  else
457  {
458  printf("Saving obstacles cloud \"%s\"... failed!\n", outputPath.c_str());
459  }
460  if(ground.size())
461  {
462  outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_octomap_ground.pcd";
463  if(pcl::io::savePCDFile(outputPath, *cloud, ground, true) == 0)
464  {
465  printf("Saving empty space cloud \"%s\"... done!\n", outputPath.c_str());
466  }
467  else
468  {
469  printf("Saving empty space cloud \"%s\"... failed!\n", outputPath.c_str());
470  }
471  }
472  if(emptySpace.size())
473  {
474  outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) + "_octomap_empty.pcd";
475  if(pcl::io::savePCDFile(outputPath, *cloud, emptySpace, true) == 0)
476  {
477  printf("Saving empty space cloud \"%s\"... done!\n", outputPath.c_str());
478  }
479  else
480  {
481  printf("Saving empty space cloud \"%s\"... failed!\n", outputPath.c_str());
482  }
483  }
484  }
485 #endif
486 
487  return 0;
488 }
static std::string homeDir()
Definition: UDirectory.cpp:355
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapEmptyCells() const
cv::Mat odomCovariance
Definition: CameraInfo.h:69
Definition: UTimer.h:46
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
Definition: DBReader.cpp:100
f
static const char * showUsage()
Definition: Parameters.cpp:518
const std::map< int, Signature > & getSignatures() const
Definition: Statistics.h:207
void update(const std::map< int, Transform > &poses)
Definition: OctoMap.cpp:367
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
Definition: DBDriver.cpp:813
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
Definition: Parameters.cpp:543
static int erase(const std::string &filePath)
Definition: UFile.cpp:58
int main(int argc, char *argv[])
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
std::vector< float > odomVelocity
Definition: CameraInfo.h:70
void update(const std::map< int, Transform > &poses)
std::string getExtension()
Definition: UFile.h:140
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
int triggerNewMap()
Definition: Rtabmap.cpp:685
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
bool isValid() const
Definition: SensorData.h:134
SensorData takeImage(CameraInfo *info=0)
Definition: Camera.cpp:67
Wrappers of STL for convenient functions.
void addToCache(int nodeId, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &ground, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &obstacles, const pcl::PointXYZ &viewPoint)
Definition: OctoMap.cpp:343
const std::map< int, Transform > & addedNodes() const
Definition: OctoMap.h:177
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
Definition: Rtabmap.cpp:348
bool isNull() const
Definition: Transform.cpp:107
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
void addToCache(int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty)
const Statistics & getStatistics() const
Definition: Rtabmap.cpp:631
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
pcl::PointCloud< pcl::PointXYZRGB >::Ptr createCloud(unsigned int treeDepth=0, std::vector< int > *obstacleIndices=0, std::vector< int > *emptyIndices=0, std::vector< int > *groundIndices=0, bool originalRefPoints=true) const
Definition: OctoMap.cpp:920
bool process(const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
Main loop of rtabmap.
Definition: Rtabmap.cpp:897
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:32
int id() const
Definition: SensorData.h:152
void init(const ParametersMap &parameters, const std::string &databasePath="")
Definition: Rtabmap.cpp:282
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapGround() const
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
bool g_loopForever
const std::map< int, Transform > & poses() const
Definition: Statistics.h:209
void sighandler(int sig)
bool exists()
Definition: UFile.h:104
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
double ticks()
Definition: UTimer.cpp:110
cv::Mat createProjectionMap(float &xMin, float &yMin, float &gridCellSize, float minGridSize=0.0f, unsigned int treeDepth=0)
Definition: OctoMap.cpp:1043
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapObstacles() const
Transform odomPose
Definition: CameraInfo.h:68
void showUsage()
cv::Mat getMap(float &xMin, float &yMin) const
const std::map< int, Transform > & addedNodes() const
Definition: OccupancyGrid.h:65
void setCloudAssembling(bool enabled)
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:443


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31