mono_tum.cc 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184
  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 &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. float imageScale = SLAM.GetImageScale();
  43. // Vector for tracking time statistics
  44. vector<float> vTimesTrack;
  45. vTimesTrack.resize(nImages);
  46. cout << endl << "-------" << endl;
  47. cout << "Start processing sequence ..." << endl;
  48. cout << "Images in the sequence: " << nImages << endl << endl;
  49. double t_resize = 0.f;
  50. double t_track = 0.f;
  51. // Main loop
  52. cv::Mat im;
  53. for(int ni=0; ni<nImages; ni++)
  54. {
  55. // Read image from file
  56. im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  57. double tframe = vTimestamps[ni];
  58. if(im.empty())
  59. {
  60. cerr << endl << "Failed to load image at: "
  61. << string(argv[3]) << "/" << vstrImageFilenames[ni] << endl;
  62. return 1;
  63. }
  64. if(imageScale != 1.f)
  65. {
  66. #ifdef REGISTER_TIMES
  67. #ifdef COMPILEDWITHC14
  68. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  69. #else
  70. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  71. #endif
  72. #endif
  73. int width = im.cols * imageScale;
  74. int height = im.rows * imageScale;
  75. cv::resize(im, im, cv::Size(width, height));
  76. #ifdef REGISTER_TIMES
  77. #ifdef COMPILEDWITHC14
  78. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  79. #else
  80. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  81. #endif
  82. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  83. SLAM.InsertResizeTime(t_resize);
  84. #endif
  85. }
  86. #ifdef COMPILEDWITHC14
  87. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  88. #else
  89. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  90. #endif
  91. // Pass the image to the SLAM system
  92. SLAM.TrackMonocular(im,tframe);
  93. #ifdef COMPILEDWITHC14
  94. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  95. #else
  96. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  97. #endif
  98. #ifdef REGISTER_TIMES
  99. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  100. SLAM.InsertTrackTime(t_track);
  101. #endif
  102. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  103. vTimesTrack[ni]=ttrack;
  104. // Wait to load the next frame
  105. double T=0;
  106. if(ni<nImages-1)
  107. T = vTimestamps[ni+1]-tframe;
  108. else if(ni>0)
  109. T = tframe-vTimestamps[ni-1];
  110. if(ttrack<T)
  111. usleep((T-ttrack)*1e6);
  112. }
  113. // Stop all threads
  114. SLAM.Shutdown();
  115. // Tracking time statistics
  116. sort(vTimesTrack.begin(),vTimesTrack.end());
  117. float totaltime = 0;
  118. for(int ni=0; ni<nImages; ni++)
  119. {
  120. totaltime+=vTimesTrack[ni];
  121. }
  122. cout << "-------" << endl << endl;
  123. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  124. cout << "mean tracking time: " << totaltime/nImages << endl;
  125. // Save camera trajectory
  126. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  127. return 0;
  128. }
  129. void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
  130. {
  131. ifstream f;
  132. f.open(strFile.c_str());
  133. // skip first three lines
  134. string s0;
  135. getline(f,s0);
  136. getline(f,s0);
  137. getline(f,s0);
  138. while(!f.eof())
  139. {
  140. string s;
  141. getline(f,s);
  142. if(!s.empty())
  143. {
  144. stringstream ss;
  145. ss << s;
  146. double t;
  147. string sRGB;
  148. ss >> t;
  149. vTimestamps.push_back(t);
  150. ss >> sRGB;
  151. vstrImageFilenames.push_back(sRGB);
  152. }
  153. }
  154. }