mono_tum.cc 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150
  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. // Main loop
  46. cv::Mat im;
  47. for(int ni=0; ni<nImages; ni++)
  48. {
  49. // Read image from file
  50. im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],cv::IMREAD_UNCHANGED);
  51. double tframe = vTimestamps[ni];
  52. if(im.empty())
  53. {
  54. cerr << endl << "Failed to load image at: "
  55. << string(argv[3]) << "/" << vstrImageFilenames[ni] << endl;
  56. return 1;
  57. }
  58. #ifdef COMPILEDWITHC11
  59. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  60. #else
  61. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  62. #endif
  63. // Pass the image to the SLAM system
  64. SLAM.TrackMonocular(im,tframe);
  65. #ifdef COMPILEDWITHC11
  66. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  67. #else
  68. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  69. #endif
  70. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  71. vTimesTrack[ni]=ttrack;
  72. // Wait to load the next frame
  73. double T=0;
  74. if(ni<nImages-1)
  75. T = vTimestamps[ni+1]-tframe;
  76. else if(ni>0)
  77. T = tframe-vTimestamps[ni-1];
  78. if(ttrack<T)
  79. usleep((T-ttrack)*1e6);
  80. }
  81. // Stop all threads
  82. SLAM.Shutdown();
  83. // Tracking time statistics
  84. sort(vTimesTrack.begin(),vTimesTrack.end());
  85. float totaltime = 0;
  86. for(int ni=0; ni<nImages; ni++)
  87. {
  88. totaltime+=vTimesTrack[ni];
  89. }
  90. cout << "-------" << endl << endl;
  91. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  92. cout << "mean tracking time: " << totaltime/nImages << endl;
  93. // Save camera trajectory
  94. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  95. return 0;
  96. }
  97. void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
  98. {
  99. ifstream f;
  100. f.open(strFile.c_str());
  101. // skip first three lines
  102. string s0;
  103. getline(f,s0);
  104. getline(f,s0);
  105. getline(f,s0);
  106. while(!f.eof())
  107. {
  108. string s;
  109. getline(f,s);
  110. if(!s.empty())
  111. {
  112. stringstream ss;
  113. ss << s;
  114. double t;
  115. string sRGB;
  116. ss >> t;
  117. vTimestamps.push_back(t);
  118. ss >> sRGB;
  119. vstrImageFilenames.push_back(sRGB);
  120. }
  121. }
  122. }