rgbd_tum.cc 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 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. // Vector for tracking time statistics
  55. vector<float> vTimesTrack;
  56. vTimesTrack.resize(nImages);
  57. cout << endl << "-------" << endl;
  58. cout << "Start processing sequence ..." << endl;
  59. cout << "Images in the sequence: " << nImages << endl << endl;
  60. // Main loop
  61. cv::Mat imRGB, imD;
  62. for(int ni=0; ni<nImages; ni++)
  63. {
  64. // Read image and depthmap from file
  65. imRGB = cv::imread(string(argv[3])+"/"+vstrImageFilenamesRGB[ni],cv::IMREAD_UNCHANGED);
  66. imD = cv::imread(string(argv[3])+"/"+vstrImageFilenamesD[ni],cv::IMREAD_UNCHANGED);
  67. double tframe = vTimestamps[ni];
  68. if(imRGB.empty())
  69. {
  70. cerr << endl << "Failed to load image at: "
  71. << string(argv[3]) << "/" << vstrImageFilenamesRGB[ni] << endl;
  72. return 1;
  73. }
  74. #ifdef COMPILEDWITHC11
  75. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  76. #else
  77. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  78. #endif
  79. // Pass the image to the SLAM system
  80. SLAM.TrackRGBD(imRGB,imD,tframe);
  81. #ifdef COMPILEDWITHC11
  82. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  83. #else
  84. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  85. #endif
  86. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  87. vTimesTrack[ni]=ttrack;
  88. // Wait to load the next frame
  89. double T=0;
  90. if(ni<nImages-1)
  91. T = vTimestamps[ni+1]-tframe;
  92. else if(ni>0)
  93. T = tframe-vTimestamps[ni-1];
  94. if(ttrack<T)
  95. usleep((T-ttrack)*1e6);
  96. }
  97. // Stop all threads
  98. SLAM.Shutdown();
  99. // Tracking time statistics
  100. sort(vTimesTrack.begin(),vTimesTrack.end());
  101. float totaltime = 0;
  102. for(int ni=0; ni<nImages; ni++)
  103. {
  104. totaltime+=vTimesTrack[ni];
  105. }
  106. cout << "-------" << endl << endl;
  107. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  108. cout << "mean tracking time: " << totaltime/nImages << endl;
  109. // Save camera trajectory
  110. SLAM.SaveTrajectoryTUM("CameraTrajectory.txt");
  111. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  112. return 0;
  113. }
  114. void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB,
  115. vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps)
  116. {
  117. ifstream fAssociation;
  118. fAssociation.open(strAssociationFilename.c_str());
  119. while(!fAssociation.eof())
  120. {
  121. string s;
  122. getline(fAssociation,s);
  123. if(!s.empty())
  124. {
  125. stringstream ss;
  126. ss << s;
  127. double t;
  128. string sRGB, sD;
  129. ss >> t;
  130. vTimestamps.push_back(t);
  131. ss >> sRGB;
  132. vstrImageFilenamesRGB.push_back(sRGB);
  133. ss >> t;
  134. ss >> sD;
  135. vstrImageFilenamesD.push_back(sD);
  136. }
  137. }
  138. }