mono_tum.cc 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  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 &strFile, vector<string> &vstrImageFilenames,
  26. vector<double> &vTimestamps);
  27. int main(int argc, char **argv)
  28. {
  29. if(argc != 4)
  30. {
  31. cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence" << endl;
  32. return 1;
  33. }
  34. // Retrieve paths to images
  35. vector<string> vstrImageFilenames;
  36. vector<double> vTimestamps;
  37. string strFile = string(argv[3])+"/rgb.txt";
  38. LoadImages(strFile, vstrImageFilenames, vTimestamps);
  39. int nImages = vstrImageFilenames.size();
  40. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  41. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true);
  42. // Vector for tracking time statistics
  43. vector<float> vTimesTrack;
  44. vTimesTrack.resize(nImages);
  45. cout << endl << "-------" << endl;
  46. cout << "Start processing sequence ..." << endl;
  47. cout << "Images in the sequence: " << nImages << endl << endl;
  48. // Main loop
  49. cv::Mat im;
  50. for(int ni=0; ni<nImages; ni++)
  51. {
  52. // Read image from file
  53. im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],cv::IMREAD_UNCHANGED);
  54. double tframe = vTimestamps[ni];
  55. if(im.empty())
  56. {
  57. cerr << endl << "Failed to load image at: "
  58. << string(argv[3]) << "/" << vstrImageFilenames[ni] << endl;
  59. return 1;
  60. }
  61. #ifdef COMPILEDWITHC11
  62. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  63. #else
  64. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  65. #endif
  66. // Pass the image to the SLAM system
  67. SLAM.TrackMonocular(im,tframe);
  68. #ifdef COMPILEDWITHC11
  69. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  70. #else
  71. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  72. #endif
  73. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  74. vTimesTrack[ni]=ttrack;
  75. // Wait to load the next frame
  76. double T=0;
  77. if(ni<nImages-1)
  78. T = vTimestamps[ni+1]-tframe;
  79. else if(ni>0)
  80. T = tframe-vTimestamps[ni-1];
  81. if(ttrack<T)
  82. usleep((T-ttrack)*1e6);
  83. }
  84. // Stop all threads
  85. SLAM.Shutdown();
  86. // Tracking time statistics
  87. sort(vTimesTrack.begin(),vTimesTrack.end());
  88. float totaltime = 0;
  89. for(int ni=0; ni<nImages; ni++)
  90. {
  91. totaltime+=vTimesTrack[ni];
  92. }
  93. cout << "-------" << endl << endl;
  94. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  95. cout << "mean tracking time: " << totaltime/nImages << endl;
  96. // Save camera trajectory
  97. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  98. return 0;
  99. }
  100. void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
  101. {
  102. ifstream f;
  103. f.open(strFile.c_str());
  104. // skip first three lines
  105. string s0;
  106. getline(f,s0);
  107. getline(f,s0);
  108. getline(f,s0);
  109. while(!f.eof())
  110. {
  111. string s;
  112. getline(f,s);
  113. if(!s.empty())
  114. {
  115. stringstream ss;
  116. ss << s;
  117. double t;
  118. string sRGB;
  119. ss >> t;
  120. vTimestamps.push_back(t);
  121. ss >> sRGB;
  122. vstrImageFilenames.push_back(sRGB);
  123. }
  124. }
  125. }