43 #include <pcl/common/common.h> 52 "rtabmap-rgbd_dataset [options] path\n" 53 " path Folder of the sequence (e.g., \"~/rgbd_dataset_freiburg3_long_office_household\")\n" 54 " containing least rgb_sync and depth_sync folders. These folders contain\n" 55 " synchronized images using associate.py tool (use tool version from\n" 56 " https://gist.github.com/matlabbe/484134a2d9da8ad425362c6669824798). If \n" 57 " \"groundtruth.txt\" is found in the sequence folder, they will be saved in the database.\n" 58 " --output Output directory. By default, results are saved in \"path\".\n" 59 " --output_name Output database name (default \"rtabmap\").\n" 60 " --skip # Skip X frames.\n" 61 " --quiet Don't show log messages and iteration updates.\n" 64 " $ rtabmap-rgbd_dataset \\\n" 65 " --Rtabmap/PublishRAMUsage true\\\n" 66 " --Rtabmap/DetectionRate 2\\\n" 67 " --RGBD/LinearUpdate 0\\\n" 68 " --Mem/STMSize 30\\\n" 77 printf(
"\nSignal %d caught...\n", sig);
93 std::string outputName =
"rtabmap";
102 for(
int i=1; i<argc; ++i)
104 if(std::strcmp(argv[i],
"--output") == 0)
108 else if(std::strcmp(argv[i],
"--output_name") == 0)
110 outputName = argv[++i];
112 else if(std::strcmp(argv[i],
"--skip") == 0)
114 skipFrames = atoi(argv[++i]);
117 else if(std::strcmp(argv[i],
"--quiet") == 0)
135 parameters.insert(
ParametersPair(Parameters::kRtabmapWorkingDirectory(), output));
136 parameters.insert(
ParametersPair(Parameters::kRtabmapPublishRAMUsage(),
"true"));
139 std::string seq =
uSplit(path,
'/').back();
140 std::string pathRgbImages = path+
"/rgb_sync";
141 std::string pathDepthImages = path+
"/depth_sync";
142 std::string pathGt = path+
"/groundtruth.txt";
145 UWARN(
"Ground truth file path doesn't exist: \"%s\", benchmark values won't be computed.", pathGt.c_str());
155 " Dataset name: %s\n" 156 " Dataset path: %s\n" 161 " Skip frames: %d\n",
164 pathRgbImages.c_str(),
165 pathDepthImages.c_str(),
171 printf(
" groundtruth.txt: %s\n", pathGt.c_str());
173 if(!parameters.empty())
175 printf(
"Parameters:\n");
176 for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
178 printf(
" %s=%s\n", iter->first.c_str(), iter->second.c_str());
181 printf(
"RTAB-Map version: %s\n", RTABMAP_VERSION);
186 Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
187 float depthFactor = 5.0f;
188 if(sequenceName.find(
"freiburg1") != std::string::npos)
190 model =
CameraModel(outputName+
"_calib", 517.3, 516.5, 318.6, 255.3, opticalRotation, 0, cv::Size(640,480));
192 else if(sequenceName.find(
"freiburg2") != std::string::npos)
194 model =
CameraModel(outputName+
"_calib", 520.9, 521.0, 325.1, 249.7, opticalRotation, 0, cv::Size(640,480));
198 model =
CameraModel(outputName+
"_calib", 535.4, 539.2, 320.1, 247.6, opticalRotation, 0, cv::Size(640,480));
209 opticalRotation), parameters);
216 bool intermediateNodes = Parameters::defaultRtabmapCreateIntermediateNodes();
217 float detectionRate = Parameters::defaultRtabmapDetectionRate();
218 int odomStrategy = Parameters::defaultOdomStrategy();
219 Parameters::parse(parameters, Parameters::kRtabmapCreateIntermediateNodes(), intermediateNodes);
221 Parameters::parse(parameters, Parameters::kRtabmapDetectionRate(), detectionRate);
222 std::string databasePath = output+
"/"+outputName+
".db";
224 if(cameraThread.
camera()->
init(path, outputName+
"_calib"))
230 totalImages /= skipFrames+1;
233 printf(
"Processing %d images...\n", totalImages);
236 odomParameters.erase(Parameters::kRtabmapPublishRAMUsage());
239 rtabmap.
init(parameters, databasePath);
251 int odomKeyFrames = 0;
252 double previousStamp = 0.0;
256 if(skipCount < skipFrames)
273 if(odomStrategy == 2)
287 bool processData =
true;
288 if(detectionRate>0.0
f &&
290 data.
stamp()>previousStamp && data.
stamp() - previousStamp < 1.0/detectionRate)
297 previousStamp = data.
stamp();
304 data.
setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());
305 processData = intermediateNodes;
307 if(covariance.empty() || odomInfo.
reg.
covariance.at<
double>(0,0) > covariance.at<
double>(0,0))
315 std::map<std::string, float> externalStats;
317 externalStats.insert(std::make_pair(
"Camera/BilateralFiltering/ms", cameraInfo.
timeBilateralFiltering*1000.0f));
318 externalStats.insert(std::make_pair(
"Camera/Capture/ms", cameraInfo.
timeCapture*1000.0f));
319 externalStats.insert(std::make_pair(
"Camera/Disparity/ms", cameraInfo.
timeDisparity*1000.0f));
320 externalStats.insert(std::make_pair(
"Camera/ImageDecimation/ms", cameraInfo.
timeImageDecimation*1000.0f));
321 externalStats.insert(std::make_pair(
"Camera/Mirroring/ms", cameraInfo.
timeMirroring*1000.0f));
323 externalStats.insert(std::make_pair(
"Camera/ScanFromDepth/ms", cameraInfo.
timeScanFromDepth*1000.0f));
324 externalStats.insert(std::make_pair(
"Camera/TotalTime/ms", cameraInfo.
timeTotal*1000.0f));
325 externalStats.insert(std::make_pair(
"Camera/UndistortDepth/ms", cameraInfo.
timeUndistortDepth*1000.0f));
327 externalStats.insert(std::make_pair(
"Odometry/LocalBundle/ms", odomInfo.
localBundleTime*1000.0f));
328 externalStats.insert(std::make_pair(
"Odometry/LocalBundleConstraints/", odomInfo.
localBundleConstraints));
329 externalStats.insert(std::make_pair(
"Odometry/LocalBundleOutliers/", odomInfo.
localBundleOutliers));
330 externalStats.insert(std::make_pair(
"Odometry/TotalTime/ms", odomInfo.
timeEstimation*1000.0f));
331 externalStats.insert(std::make_pair(
"Odometry/Registration/ms", odomInfo.
reg.
totalTime*1000.0f));
332 externalStats.insert(std::make_pair(
"Odometry/Inliers/", odomInfo.
reg.
inliers));
333 externalStats.insert(std::make_pair(
"Odometry/Features/", odomInfo.
features));
334 externalStats.insert(std::make_pair(
"Odometry/DistanceTravelled/m", odomInfo.
distanceTravelled));
335 externalStats.insert(std::make_pair(
"Odometry/KeyFrameAdded/", odomInfo.
keyFrameAdded));
336 externalStats.insert(std::make_pair(
"Odometry/LocalKeyFrames/", odomInfo.
localKeyFrames));
337 externalStats.insert(std::make_pair(
"Odometry/LocalMapSize/", odomInfo.
localMapSize));
338 externalStats.insert(std::make_pair(
"Odometry/LocalScanMapSize/", odomInfo.
localScanMapSize));
342 covariance = cv::Mat();
346 if(!quiet || iteration == totalImages)
348 double slamTime = timer.
ticks();
360 printf(
"Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms, rmse=%fm",
365 printf(
"Iteration %d/%d: camera=%dms, odom(quality=%d/%d, kfs=%d)=%dms, slam=%dms",
374 else if(iteration % (totalImages/10) == 0)
385 printf(
"Total time=%fs\n", totalTime.
ticks());
391 printf(
"Saving trajectory...\n");
392 std::map<int, Transform> poses;
393 std::multimap<int, Link> links;
394 std::map<int, Signature> signatures;
395 std::map<int, double> stamps;
396 rtabmap.
getGraph(poses, links,
true,
true, &signatures);
397 for(std::map<int, Signature>::iterator iter=signatures.begin(); iter!=signatures.end(); ++iter)
399 stamps.insert(std::make_pair(iter->first, iter->second.getStamp()));
401 std::string pathTrajectory = output+
"/"+outputName+
"_poses.txt";
404 printf(
"Saving %s... done!\n", pathTrajectory.c_str());
408 printf(
"Saving %s... failed!\n", pathTrajectory.c_str());
414 std::map<int, Transform> groundTruth;
416 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
422 std::vector<float> v;
425 rtabmap.
getMemory()->
getNodeInfo(iter->first, o, m, w, l, s, gtPose, v, gps, sensors,
true);
428 groundTruth.insert(std::make_pair(iter->first, gtPose));
434 float translational_rmse = 0.0f;
435 float translational_mean = 0.0f;
436 float translational_median = 0.0f;
437 float translational_std = 0.0f;
438 float translational_min = 0.0f;
439 float translational_max = 0.0f;
440 float rotational_rmse = 0.0f;
441 float rotational_mean = 0.0f;
442 float rotational_median = 0.0f;
443 float rotational_std = 0.0f;
444 float rotational_min = 0.0f;
445 float rotational_max = 0.0f;
451 translational_median,
462 printf(
" translational_rmse= %f m\n", translational_rmse);
463 printf(
" rotational_rmse= %f deg\n", rotational_rmse);
466 std::string pathErrors = output+
"/"+outputName+
"_rmse.txt";
467 pFile = fopen(pathErrors.c_str(),
"w");
470 UERROR(
"could not save RMSE results to \"%s\"", pathErrors.c_str());
472 fprintf(pFile,
"Ground truth comparison:\n");
473 fprintf(pFile,
" translational_rmse= %f\n", translational_rmse);
474 fprintf(pFile,
" translational_mean= %f\n", translational_mean);
475 fprintf(pFile,
" translational_median= %f\n", translational_median);
476 fprintf(pFile,
" translational_std= %f\n", translational_std);
477 fprintf(pFile,
" translational_min= %f\n", translational_min);
478 fprintf(pFile,
" translational_max= %f\n", translational_max);
479 fprintf(pFile,
" rotational_rmse= %f\n", rotational_rmse);
480 fprintf(pFile,
" rotational_mean= %f\n", rotational_mean);
481 fprintf(pFile,
" rotational_median= %f\n", rotational_median);
482 fprintf(pFile,
" rotational_std= %f\n", rotational_std);
483 fprintf(pFile,
" rotational_min= %f\n", rotational_min);
484 fprintf(pFile,
" rotational_max= %f\n", rotational_max);
490 UERROR(
"Camera init failed!");
493 printf(
"Saving rtabmap database (with all statistics) to \"%s\"\n", (output+
"/"+outputName+
".db").c_str());
495 " $ rtabmap-databaseViewer %s\n\n", (output+
"/"+outputName+
".db").c_str());
static std::string homeDir()
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
static bool makeDir(const std::string &dirPath)
static const char * showUsage()
std::pair< std::string, std::string > ParametersPair
static std::string getName(const std::string &filePath)
bool save(const std::string &directory) const
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
static int erase(const std::string &filePath)
GLM_FUNC_DECL genType e()
std::map< std::string, std::string > ParametersMap
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
Basic mathematics functions.
Some conversion functions.
int localBundleConstraints
static void setLevel(ULogger::Level level)
Transform process(SensorData &data, OdometryInfo *info=0)
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
#define UASSERT(condition)
SensorData takeImage(CameraInfo *info=0)
Wrappers of STL for convenient functions.
const std::map< std::string, float > & data() const
float timeStereoExposureCompensation
static Odometry * create(const ParametersMap ¶meters=ParametersMap())
bool getNodeInfo(int signatureId, Transform &odomPose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruth, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors, bool lookInDatabase=false) const
int getLoopClosureId() const
Transform RTABMAP_EXP calcRMSE(const std::map< int, Transform > &groundTruth, const std::map< int, Transform > &poses, float &translational_rmse, float &translational_mean, float &translational_median, float &translational_std, float &translational_min, float &translational_max, float &rotational_rmse, float &rotational_mean, float &rotational_median, float &rotational_std, float &rotational_min, float &rotational_max)
const Statistics & getStatistics() const
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
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)
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), const ParametersMap ¶meters=ParametersMap())
void postUpdate(SensorData *data, CameraInfo *info=0) const
int main(int argc, char *argv[])
const Memory * getMemory() const
float timeImageDecimation
std::vector< float > velocity() const
std::map< EnvSensor::Type, EnvSensor > EnvSensors
float timeBilateralFiltering
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)