rgbd_tum.cc 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include<iostream>
  19. #include<algorithm>
  20. #include<fstream>
  21. #include<chrono>
  22. #include<opencv2/core/core.hpp>
  23. #include<System.h>
  24. using namespace std;
  25. void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB,
  26. vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps);
  27. int main(int argc, char **argv)
  28. {
  29. if(argc != 5)
  30. {
  31. cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association" << endl;
  32. return 1;
  33. }
  34. // Retrieve paths to images
  35. vector<string> vstrImageFilenamesRGB;
  36. vector<string> vstrImageFilenamesD;
  37. vector<double> vTimestamps;
  38. string strAssociationFilename = string(argv[4]);
  39. LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps);
  40. // Check consistency in the number of images and depthmaps
  41. int nImages = vstrImageFilenamesRGB.size();
  42. if(vstrImageFilenamesRGB.empty())
  43. {
  44. cerr << endl << "No images found in provided path." << endl;
  45. return 1;
  46. }
  47. else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size())
  48. {
  49. cerr << endl << "Different number of images for rgb and depth." << endl;
  50. return 1;
  51. }
  52. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  53. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::RGBD,true);
  54. float imageScale = SLAM.GetImageScale();
  55. // Vector for tracking time statistics
  56. vector<float> vTimesTrack;
  57. vTimesTrack.resize(nImages);
  58. cout << endl << "-------" << endl;
  59. cout << "Start processing sequence ..." << endl;
  60. cout << "Images in the sequence: " << nImages << endl << endl;
  61. // Main loop
  62. cv::Mat imRGB, imD;
  63. for(int ni=0; ni<nImages; ni++)
  64. {
  65. // Read image and depthmap from file
  66. imRGB = cv::imread(string(argv[3])+"/"+vstrImageFilenamesRGB[ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  67. imD = cv::imread(string(argv[3])+"/"+vstrImageFilenamesD[ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  68. double tframe = vTimestamps[ni];
  69. if(imRGB.empty())
  70. {
  71. cerr << endl << "Failed to load image at: "
  72. << string(argv[3]) << "/" << vstrImageFilenamesRGB[ni] << endl;
  73. return 1;
  74. }
  75. if(imageScale != 1.f)
  76. {
  77. int width = imRGB.cols * imageScale;
  78. int height = imRGB.rows * imageScale;
  79. cv::resize(imRGB, imRGB, cv::Size(width, height));
  80. cv::resize(imD, imD, cv::Size(width, height));
  81. }
  82. #ifdef COMPILEDWITHC14
  83. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  84. #else
  85. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  86. #endif
  87. // Pass the image to the SLAM system
  88. SLAM.TrackRGBD(imRGB,imD,tframe);
  89. #ifdef COMPILEDWITHC14
  90. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  91. #else
  92. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  93. #endif
  94. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  95. vTimesTrack[ni]=ttrack;
  96. // Wait to load the next frame
  97. double T=0;
  98. if(ni<nImages-1)
  99. T = vTimestamps[ni+1]-tframe;
  100. else if(ni>0)
  101. T = tframe-vTimestamps[ni-1];
  102. if(ttrack<T)
  103. usleep((T-ttrack)*1e6);
  104. }
  105. // Stop all threads
  106. SLAM.Shutdown();
  107. // Tracking time statistics
  108. sort(vTimesTrack.begin(),vTimesTrack.end());
  109. float totaltime = 0;
  110. for(int ni=0; ni<nImages; ni++)
  111. {
  112. totaltime+=vTimesTrack[ni];
  113. }
  114. cout << "-------" << endl << endl;
  115. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  116. cout << "mean tracking time: " << totaltime/nImages << endl;
  117. // Save camera trajectory
  118. SLAM.SaveTrajectoryTUM("CameraTrajectory.txt");
  119. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  120. return 0;
  121. }
  122. void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB,
  123. vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps)
  124. {
  125. ifstream fAssociation;
  126. fAssociation.open(strAssociationFilename.c_str());
  127. while(!fAssociation.eof())
  128. {
  129. string s;
  130. getline(fAssociation,s);
  131. if(!s.empty())
  132. {
  133. stringstream ss;
  134. ss << s;
  135. double t;
  136. string sRGB, sD;
  137. ss >> t;
  138. vTimestamps.push_back(t);
  139. ss >> sRGB;
  140. vstrImageFilenamesRGB.push_back(sRGB);
  141. ss >> t;
  142. ss >> sD;
  143. vstrImageFilenamesD.push_back(sD);
  144. }
  145. }
  146. }