31 #ifdef RTABMAP_OCTOMAP 42 #include <pcl/io/pcd_io.h> 50 "rtabmap-reprocess [options] \"input.db\" \"output.db\"\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" 66 printf(
"\nSignal %d caught...\n", sig);
70 int main(
int argc,
char * argv[])
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)
91 if(strcmp(argv[i],
"-r") == 0)
93 useDatabaseRate =
true;
94 printf(
"Using database stamps as input rate.\n");
96 else if(strcmp(argv[i],
"-g2") == 0)
99 printf(
"2D occupancy grid will be assembled (-g2 option).\n");
101 else if(strcmp(argv[i],
"-g3") == 0)
103 assemble3dMap =
true;
104 printf(
"3D cloud map will be assembled (-g3 option).\n");
106 else if(strcmp(argv[i],
"-o2") == 0)
108 #ifdef RTABMAP_OCTOMAP 109 assemble2dOctoMap =
true;
110 printf(
"OctoMap will be assembled (-o2 option).\n");
112 printf(
"RTAB-Map is not built with OctoMap support, cannot set -o2 option!\n");
115 else if(strcmp(argv[i],
"-o3") == 0)
117 #ifdef RTABMAP_OCTOMAP 118 assemble3dOctoMap =
true;
119 printf(
"OctoMap will be assembled (-o3 option).\n");
121 printf(
"RTAB-Map is not built with OctoMap support, cannot set -o3 option!\n");
133 printf(
"Input database \"%s\" doesn't exist!\n", inputDatabasePath.c_str());
139 printf(
"File \"%s\" is not a database format (*.db)!\n", inputDatabasePath.c_str());
144 printf(
"File \"%s\" is not a database format (*.db)!\n", outputDatabasePath.c_str());
156 printf(
"Failed opening input database!\n");
162 if(parameters.empty())
164 printf(
"Failed getting parameters from database, reprocessing cannot be done. Database version may be too old.\n");
169 if(customParameters.size())
171 printf(
"Custom parameters:\n");
172 for(ParametersMap::iterator iter=customParameters.begin(); iter!=customParameters.end(); ++iter)
174 printf(
" %s\t= %s\n", iter->first.c_str(), iter->second.c_str());
177 uInsert(parameters, customParameters);
182 printf(
"Input database doesn't have any nodes saved in it.\n");
192 rtabmap.
init(parameters, outputDatabasePath);
194 bool rgbdEnabled = Parameters::defaultRGBDEnabled();
196 bool odometryIgnored = !rgbdEnabled;
197 DBReader dbReader(inputDatabasePath, useDatabaseRate?-1:0, odometryIgnored);
202 #ifdef RTABMAP_OCTOMAP 206 printf(
"Reprocessing data of \"%s\"...\n", inputDatabasePath.c_str());
207 std::map<std::string, float> globalMapStats;
217 printf(
"Skipping node %d as it doesn't have odometry pose set.\n", data.
id());
223 printf(
"High variance detected, triggering a new map...\n");
229 printf(
"Failed processing node %d.\n", data.
id());
230 globalMapStats.clear();
232 else if(assemble2dMap || assemble3dMap || assemble2dOctoMap || assemble3dOctoMap)
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;
244 int id = stats.
poses().rbegin()->first;
246 stats.
getSignatures().find(
id)->second.sensorData().gridCellSize() > 0.0f)
248 bool updateGridMap =
false;
249 bool updateOctoMap =
false;
252 updateGridMap =
true;
254 #ifdef RTABMAP_OCTOMAP 255 if((assemble2dOctoMap || assemble3dOctoMap) && octomap.
addedNodes().find(
id) == octomap.
addedNodes().end())
257 updateOctoMap =
true;
260 if(updateGridMap || updateOctoMap)
262 cv::Mat ground, obstacles, empty;
263 stats.
getSignatures().find(
id)->second.sensorData().uncompressDataConst(0, 0, 0, 0, &ground, &obstacles, &empty);
265 timeUpdateInit = t.
ticks();
269 grid.
addToCache(
id, ground, obstacles, empty);
271 timeUpdateGrid = t.
ticks() + timeUpdateInit;
273 #ifdef RTABMAP_OCTOMAP 276 const cv::Point3f & viewpoint = stats.
getSignatures().find(
id)->second.sensorData().gridViewPoint();
277 octomap.
addToCache(
id, ground, obstacles, empty, viewpoint);
279 timeUpdateOctoMap = t.
ticks() + timeUpdateInit;
286 globalMapStats.insert(std::make_pair(std::string(
"GlobalGrid/GridUpdate/ms"), timeUpdateGrid*1000.0
f));
287 #ifdef RTABMAP_OCTOMAP 289 double timePub2dOctoMap = 0.0;
290 double timePub3dOctoMap = 0.0;
291 if(assemble2dOctoMap)
293 float xMin, yMin, size;
295 timePub2dOctoMap = t.
ticks();
297 if(assemble3dOctoMap)
300 timePub3dOctoMap = t.
ticks();
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));
308 globalMapStats.insert(std::make_pair(std::string(
"GlobalGrid/TotalWithRtabmap/ms"), (timeUpdateGrid+timeRtabmap)*1000.0f));
313 printf(
"Processed %d/%d nodes... %dms\n", ++processed, (
int)ids.size(), int(iterationTime.
ticks()*1000));
318 printf(
"Closing database \"%s\"...\n", outputDatabasePath.c_str());
320 printf(
"Closing database \"%s\"... done!\n", outputDatabasePath.c_str());
324 std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_map.pgm";
326 cv::Mat map = grid.
getMap(xMin, yMin);
329 cv::Mat map8U(map.rows, map.cols, CV_8U);
331 for (
int i = 0; i < map.rows; ++i)
333 for (
int j = 0; j < map.cols; ++j)
335 char v = map.at<
char>(i, j);
349 map8U.at<
unsigned char>(i, j) = gray;
352 if(cv::imwrite(outputPath, map8U))
354 printf(
"Saving occupancy grid \"%s\"... done!\n", outputPath.c_str());
358 printf(
"Saving occupancy grid \"%s\"... failed!\n", outputPath.c_str());
363 printf(
"2D map is empty! Cannot save it!\n");
368 std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_obstacles.pcd";
369 if(pcl::io::savePCDFileBinary(outputPath, *grid.
getMapObstacles()) == 0)
371 printf(
"Saving 3d obstacles \"%s\"... done!\n", outputPath.c_str());
375 printf(
"Saving 3d obstacles \"%s\"... failed!\n", outputPath.c_str());
379 outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_ground.pcd";
380 if(pcl::io::savePCDFileBinary(outputPath, *grid.
getMapGround()) == 0)
382 printf(
"Saving 3d ground \"%s\"... done!\n", outputPath.c_str());
386 printf(
"Saving 3d ground \"%s\"... failed!\n", outputPath.c_str());
391 outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_empty.pcd";
394 printf(
"Saving 3d empty cells \"%s\"... done!\n", outputPath.c_str());
398 printf(
"Saving 3d empty cells \"%s\"... failed!\n", outputPath.c_str());
402 #ifdef RTABMAP_OCTOMAP 403 if(assemble2dOctoMap)
405 std::string outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_octomap.pgm";
406 float xMin,yMin,cellSize;
410 cv::Mat map8U(map.rows, map.cols, CV_8U);
412 for (
int i = 0; i < map.rows; ++i)
414 for (
int j = 0; j < map.cols; ++j)
416 char v = map.at<
char>(i, j);
430 map8U.at<
unsigned char>(i, j) = gray;
433 if(cv::imwrite(outputPath, map8U))
435 printf(
"Saving octomap 2D projection \"%s\"... done!\n", outputPath.c_str());
439 printf(
"Saving octomap 2D projection \"%s\"... failed!\n", outputPath.c_str());
444 printf(
"OctoMap 2D projection map is empty! Cannot save it!\n");
447 if(assemble3dOctoMap)
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)
454 printf(
"Saving obstacles cloud \"%s\"... done!\n", outputPath.c_str());
458 printf(
"Saving obstacles cloud \"%s\"... failed!\n", outputPath.c_str());
462 outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_octomap_ground.pcd";
463 if(pcl::io::savePCDFile(outputPath, *cloud, ground,
true) == 0)
465 printf(
"Saving empty space cloud \"%s\"... done!\n", outputPath.c_str());
469 printf(
"Saving empty space cloud \"%s\"... failed!\n", outputPath.c_str());
472 if(emptySpace.size())
474 outputPath = outputDatabasePath.substr(0, outputDatabasePath.size()-3) +
"_octomap_empty.pcd";
475 if(pcl::io::savePCDFile(outputPath, *cloud, emptySpace,
true) == 0)
477 printf(
"Saving empty space cloud \"%s\"... done!\n", outputPath.c_str());
481 printf(
"Saving empty space cloud \"%s\"... failed!\n", outputPath.c_str());
static std::string homeDir()
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapEmptyCells() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
static const char * showUsage()
const std::map< int, Signature > & getSignatures() const
void update(const std::map< int, Transform > &poses)
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
static int erase(const std::string &filePath)
int main(int argc, char *argv[])
std::map< std::string, std::string > ParametersMap
std::vector< float > odomVelocity
void update(const std::map< int, Transform > &poses)
std::string getExtension()
static void setLevel(ULogger::Level level)
bool openConnection(const std::string &url, bool overwritten=false)
SensorData takeImage(CameraInfo *info=0)
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)
const std::map< int, Transform > & addedNodes() const
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
void closeConnection(bool save=true, const std::string &outputUrl="")
void addToCache(int nodeId, const cv::Mat &ground, const cv::Mat &obstacles, const cv::Mat &empty)
const Statistics & getStatistics() const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
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
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.
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
void init(const ParametersMap ¶meters, const std::string &databasePath="")
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapGround() const
static DBDriver * create(const ParametersMap ¶meters=ParametersMap())
const std::map< int, Transform > & poses() const
ParametersMap getLastParameters() const
cv::Mat createProjectionMap(float &xMin, float &yMin, float &gridCellSize, float minGridSize=0.0f, unsigned int treeDepth=0)
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & getMapObstacles() const
cv::Mat getMap(float &xMin, float &yMin) const
const std::map< int, Transform > & addedNodes() const
void setCloudAssembling(bool enabled)
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)