stereo_kitti.cc 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194
  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<iomanip>
  22. #include<chrono>
  23. #include<opencv2/core/core.hpp>
  24. #include<System.h>
  25. using namespace std;
  26. void LoadImages(const string &strPathToSequence, vector<string> &vstrImageLeft,
  27. vector<string> &vstrImageRight, vector<double> &vTimestamps);
  28. int main(int argc, char **argv)
  29. {
  30. if(argc != 4)
  31. {
  32. cerr << endl << "Usage: ./stereo_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
  33. return 1;
  34. }
  35. // Retrieve paths to images
  36. vector<string> vstrImageLeft;
  37. vector<string> vstrImageRight;
  38. vector<double> vTimestamps;
  39. LoadImages(string(argv[3]), vstrImageLeft, vstrImageRight, vTimestamps);
  40. const int nImages = vstrImageLeft.size();
  41. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  42. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO,true);
  43. float imageScale = SLAM.GetImageScale();
  44. // Vector for tracking time statistics
  45. vector<float> vTimesTrack;
  46. vTimesTrack.resize(nImages);
  47. cout << endl << "-------" << endl;
  48. cout << "Start processing sequence ..." << endl;
  49. cout << "Images in the sequence: " << nImages << endl << endl;
  50. double t_track = 0.f;
  51. double t_resize = 0.f;
  52. // Main loop
  53. cv::Mat imLeft, imRight;
  54. for(int ni=0; ni<nImages; ni++)
  55. {
  56. // Read left and right images from file
  57. imLeft = cv::imread(vstrImageLeft[ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  58. imRight = cv::imread(vstrImageRight[ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  59. double tframe = vTimestamps[ni];
  60. if(imLeft.empty())
  61. {
  62. cerr << endl << "Failed to load image at: "
  63. << string(vstrImageLeft[ni]) << endl;
  64. return 1;
  65. }
  66. if(imageScale != 1.f)
  67. {
  68. #ifdef REGISTER_TIMES
  69. #ifdef COMPILEDWITHC14
  70. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  71. #else
  72. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  73. #endif
  74. #endif
  75. int width = imLeft.cols * imageScale;
  76. int height = imLeft.rows * imageScale;
  77. cv::resize(imLeft, imLeft, cv::Size(width, height));
  78. cv::resize(imRight, imRight, cv::Size(width, height));
  79. #ifdef REGISTER_TIMES
  80. #ifdef COMPILEDWITHC14
  81. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  82. #else
  83. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  84. #endif
  85. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  86. SLAM.InsertResizeTime(t_resize);
  87. #endif
  88. }
  89. #ifdef COMPILEDWITHC14
  90. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  91. #else
  92. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  93. #endif
  94. // Pass the images to the SLAM system
  95. SLAM.TrackStereo(imLeft,imRight,tframe);
  96. #ifdef COMPILEDWITHC14
  97. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  98. #else
  99. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  100. #endif
  101. #ifdef REGISTER_TIMES
  102. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  103. SLAM.InsertTrackTime(t_track);
  104. #endif
  105. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  106. vTimesTrack[ni]=ttrack;
  107. // Wait to load the next frame
  108. double T=0;
  109. if(ni<nImages-1)
  110. T = vTimestamps[ni+1]-tframe;
  111. else if(ni>0)
  112. T = tframe-vTimestamps[ni-1];
  113. if(ttrack<T)
  114. usleep((T-ttrack)*1e6);
  115. }
  116. // Stop all threads
  117. SLAM.Shutdown();
  118. // Tracking time statistics
  119. sort(vTimesTrack.begin(),vTimesTrack.end());
  120. float totaltime = 0;
  121. for(int ni=0; ni<nImages; ni++)
  122. {
  123. totaltime+=vTimesTrack[ni];
  124. }
  125. cout << "-------" << endl << endl;
  126. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  127. cout << "mean tracking time: " << totaltime/nImages << endl;
  128. // Save camera trajectory
  129. SLAM.SaveTrajectoryKITTI("CameraTrajectory.txt");
  130. return 0;
  131. }
  132. void LoadImages(const string &strPathToSequence, vector<string> &vstrImageLeft,
  133. vector<string> &vstrImageRight, vector<double> &vTimestamps)
  134. {
  135. ifstream fTimes;
  136. string strPathTimeFile = strPathToSequence + "/times.txt";
  137. fTimes.open(strPathTimeFile.c_str());
  138. while(!fTimes.eof())
  139. {
  140. string s;
  141. getline(fTimes,s);
  142. if(!s.empty())
  143. {
  144. stringstream ss;
  145. ss << s;
  146. double t;
  147. ss >> t;
  148. vTimestamps.push_back(t);
  149. }
  150. }
  151. string strPrefixLeft = strPathToSequence + "/image_0/";
  152. string strPrefixRight = strPathToSequence + "/image_1/";
  153. const int nTimes = vTimestamps.size();
  154. vstrImageLeft.resize(nTimes);
  155. vstrImageRight.resize(nTimes);
  156. for(int i=0; i<nTimes; i++)
  157. {
  158. stringstream ss;
  159. ss << setfill('0') << setw(6) << i;
  160. vstrImageLeft[i] = strPrefixLeft + ss.str() + ".png";
  161. vstrImageRight[i] = strPrefixRight + ss.str() + ".png";
  162. }
  163. }