39 "Clear empty space from local occupancy grids and laser scans based on the saved optimized global 2d grid map.\n" 41 " * If the map needs to be regenerated in the future (e.g., when \n" 42 " we re-use the map in SLAM mode), removed obstacles won't reappear.\n" 43 " * [--scan] The cropped laser scans will be also used for localization,\n" 44 " so if dynamic obstacles have been removed, localization won't try to\n" 45 " match them anymore.\n\n" 47 " * [--scan] Cropping the laser scans cannot be reverted, but grids can.\n" 49 "rtabmap-cleanupLocalGrids [options] database.db\n" 51 " --radius # Radius in cells around empty cell without obstacles to clear\n" 52 " underlying obstacles. Default is 1.\n" 53 " --scan Filter also scans, otherwise only local grids are filtered.\n" 70 bool filterScans =
false;
72 for(
int i=1; i<argc; ++i)
74 if(std::strcmp(argv[i],
"--help") == 0)
78 else if(std::strcmp(argv[i],
"--scan") == 0)
82 else if(std::strcmp(argv[i],
"--radius") == 0)
97 std::string dbPath = argv[argc-1];
101 UERROR(
"File \"%s\" doesn't exist!", dbPath.c_str());
110 float xMin, yMin, cellSize;
114 UERROR(
"Database %s doesn't have optimized 2d map saved in it!", dbPath.c_str());
118 printf(
"Options:\n");
119 printf(
" --radius: %d cell(s) (cell size=%.3fm)\n", cropRadius, cellSize);
120 printf(
" --scan: %s\n", filterScans?
"true":
"false");
123 if(poses.empty() || poses.lower_bound(1) == poses.end())
125 UERROR(
"Database %s doesn't have optimized poses saved in it!", dbPath.c_str());
130 printf(
"Cleaning grids...\n");
131 int modifiedCells = rtabmap.
cleanupLocalGrids(poses, map, xMin, yMin, cellSize, cropRadius, filterScans);
132 printf(
"Cleanup %d cells! (%fs)\n", modifiedCells, timer.
ticks());
int UTILITE_EXP uStr2Int(const std::string &str)
std::map< std::string, std::string > ParametersMap
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
static void setLevel(ULogger::Level level)
#define UASSERT(condition)
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
const Memory * getMemory() const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
const std::map< int, Transform > & getLocalOptimizedPoses() const
int cleanupLocalGrids(const std::map< int, Transform > &mapPoses, const cv::Mat &map, float xMin, float yMin, float cellSize, int cropRadius=1, bool filterScans=false)
cv::Mat load2DMap(float &xMin, float &yMin, float &cellSize) const
int main(int argc, char *argv[])