stereo_tum_vi.cc 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226
  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<iomanip>
  22. #include<chrono>
  23. #include <unistd.h>
  24. #include<opencv2/core/core.hpp>
  25. #include<System.h>
  26. using namespace std;
  27. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  28. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps);
  29. double ttrack_tot = 0;
  30. int main(int argc, char **argv)
  31. {
  32. const int num_seq = (argc-3)/3;
  33. cout << "num_seq = " << num_seq << endl;
  34. bool bFileName= (((argc-3) % 3) == 1);
  35. string file_name;
  36. if (bFileName)
  37. file_name = string(argv[argc-1]);
  38. if(argc < 6)
  39. {
  40. cerr << endl << "Usage: ./stereo_tum_vi path_to_vocabulary path_to_settings path_to_image_folder1_1 path_to_image_folder2_1 path_to_times_file_1 (path_to_image_folder1_2 path_to_image_folder2_2 path_to_times_file_2 ... path_to_image_folder1_N path_to_image_folder2_N path_to_times_file_N) (trajectory_file_name)" << endl;
  41. return 1;
  42. }
  43. // Load all sequences:
  44. int seq;
  45. vector< vector<string> > vstrImageLeftFilenames;
  46. vector< vector<string> > vstrImageRightFilenames;
  47. vector< vector<double> > vTimestampsCam;
  48. vector<int> nImages;
  49. vstrImageLeftFilenames.resize(num_seq);
  50. vstrImageRightFilenames.resize(num_seq);
  51. vTimestampsCam.resize(num_seq);
  52. nImages.resize(num_seq);
  53. int tot_images = 0;
  54. for (seq = 0; seq<num_seq; seq++)
  55. {
  56. cout << "Loading images for sequence " << seq << "...";
  57. LoadImages(string(argv[(3*seq)+3]), string(argv[(2*seq)+4]), string(argv[(2*seq)+5]), vstrImageLeftFilenames[seq], vstrImageRightFilenames[seq], vTimestampsCam[seq]);
  58. cout << "Total images: " << vstrImageLeftFilenames[seq].size() << endl;
  59. cout << "Total cam ts: " << vTimestampsCam[seq].size() << endl;
  60. cout << "first cam ts: " << vTimestampsCam[seq][0] << endl;
  61. cout << "LOADED!" << endl;
  62. nImages[seq] = vstrImageLeftFilenames[seq].size();
  63. tot_images += nImages[seq];
  64. if((nImages[seq]<=0))
  65. {
  66. cerr << "ERROR: Failed to load images for sequence" << seq << endl;
  67. return 1;
  68. }
  69. }
  70. // Vector for tracking time statistics
  71. vector<float> vTimesTrack;
  72. vTimesTrack.resize(tot_images);
  73. cout << endl << "-------" << endl;
  74. cout.precision(17);
  75. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  76. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO,true);
  77. cout << endl << "-------" << endl;
  78. cout.precision(17);
  79. cv::Mat imLeft, imRight;
  80. int proccIm = 0;
  81. for (seq = 0; seq<num_seq; seq++)
  82. {
  83. // Main loop
  84. proccIm = 0;
  85. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  86. {
  87. // Read image from file
  88. imLeft = cv::imread(vstrImageLeftFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  89. imRight = cv::imread(vstrImageRightFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  90. double tframe = vTimestampsCam[seq][ni];
  91. if(imLeft.empty() || imRight.empty())
  92. {
  93. cerr << endl << "Failed to load image at: "
  94. << vstrImageLeftFilenames[seq][ni] << endl;
  95. return 1;
  96. }
  97. #ifdef COMPILEDWITHC11
  98. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  99. #else
  100. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  101. #endif
  102. // Pass the image to the SLAM system
  103. SLAM.TrackStereo(imLeft,imRight,tframe);
  104. #ifdef COMPILEDWITHC11
  105. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  106. #else
  107. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  108. #endif
  109. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  110. ttrack_tot += ttrack;
  111. // std::cout << "ttrack: " << ttrack << std::endl;
  112. vTimesTrack[ni]=ttrack;
  113. // Wait to load the next frame
  114. double T=0;
  115. if(ni<nImages[seq]-1)
  116. T = vTimestampsCam[seq][ni+1]-tframe;
  117. else if(ni>0)
  118. T = tframe-vTimestampsCam[seq][ni-1];
  119. if(ttrack<T)
  120. usleep((T-ttrack)*1e6); // 1e6
  121. }
  122. if(seq < num_seq - 1)
  123. {
  124. cout << "Changing the dataset" << endl;
  125. SLAM.ChangeDataset();
  126. }
  127. }
  128. // Stop all threads
  129. SLAM.Shutdown();
  130. // Tracking time statistics
  131. // Save camera trajectory
  132. std::chrono::system_clock::time_point scNow = std::chrono::system_clock::now();
  133. std::time_t now = std::chrono::system_clock::to_time_t(scNow);
  134. std::stringstream ss;
  135. ss << now;
  136. if (bFileName)
  137. {
  138. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  139. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  140. SLAM.SaveTrajectoryEuRoC(f_file);
  141. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  142. }
  143. else
  144. {
  145. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  146. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  147. }
  148. sort(vTimesTrack.begin(),vTimesTrack.end());
  149. float totaltime = 0;
  150. for(int ni=0; ni<nImages[0]; ni++)
  151. {
  152. totaltime+=vTimesTrack[ni];
  153. }
  154. cout << "-------" << endl << endl;
  155. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  156. cout << "mean tracking time: " << totaltime/proccIm << endl;
  157. return 0;
  158. }
  159. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  160. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  161. {
  162. ifstream fTimes;
  163. cout << strPathLeft << endl;
  164. cout << strPathRight << endl;
  165. cout << strPathTimes << endl;
  166. fTimes.open(strPathTimes.c_str());
  167. vTimeStamps.reserve(5000);
  168. vstrImageLeft.reserve(5000);
  169. vstrImageRight.reserve(5000);
  170. while(!fTimes.eof())
  171. {
  172. string s;
  173. getline(fTimes,s);
  174. if(!s.empty())
  175. {
  176. stringstream ss;
  177. ss << s;
  178. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  179. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  180. double t;
  181. ss >> t;
  182. vTimeStamps.push_back(t/1e9);
  183. }
  184. }
  185. }