stereo_euroc.cc 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212
  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 &strPathLeft, const string &strPathRight, const string &strPathTimes,
  27. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps);
  28. int main(int argc, char **argv)
  29. {
  30. if(argc < 5)
  31. {
  32. cerr << endl << "Usage: ./stereo_euroc path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl;
  33. return 1;
  34. }
  35. const int num_seq = (argc-3)/2;
  36. cout << "num_seq = " << num_seq << endl;
  37. bool bFileName= (((argc-3) % 2) == 1);
  38. string file_name;
  39. if (bFileName)
  40. {
  41. file_name = string(argv[argc-1]);
  42. cout << "file name: " << file_name << endl;
  43. }
  44. // Load all sequences:
  45. int seq;
  46. vector< vector<string> > vstrImageLeft;
  47. vector< vector<string> > vstrImageRight;
  48. vector< vector<double> > vTimestampsCam;
  49. vector<int> nImages;
  50. vstrImageLeft.resize(num_seq);
  51. vstrImageRight.resize(num_seq);
  52. vTimestampsCam.resize(num_seq);
  53. nImages.resize(num_seq);
  54. int tot_images = 0;
  55. for (seq = 0; seq<num_seq; seq++)
  56. {
  57. cout << "Loading images for sequence " << seq << "...";
  58. string pathSeq(argv[(2*seq) + 3]);
  59. string pathTimeStamps(argv[(2*seq) + 4]);
  60. string pathCam0 = pathSeq + "/mav0/cam0/data";
  61. string pathCam1 = pathSeq + "/mav0/cam1/data";
  62. LoadImages(pathCam0, pathCam1, pathTimeStamps, vstrImageLeft[seq], vstrImageRight[seq], vTimestampsCam[seq]);
  63. cout << "LOADED!" << endl;
  64. nImages[seq] = vstrImageLeft[seq].size();
  65. tot_images += nImages[seq];
  66. }
  67. // Vector for tracking time statistics
  68. vector<float> vTimesTrack;
  69. vTimesTrack.resize(tot_images);
  70. cout << endl << "-------" << endl;
  71. cout.precision(17);
  72. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  73. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO, true);
  74. cv::Mat imLeft, imRight;
  75. for (seq = 0; seq<num_seq; seq++)
  76. {
  77. // Seq loop
  78. double t_resize = 0;
  79. double t_rect = 0;
  80. double t_track = 0;
  81. int num_rect = 0;
  82. int proccIm = 0;
  83. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  84. {
  85. // Read left and right images from file
  86. imLeft = cv::imread(vstrImageLeft[seq][ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  87. imRight = cv::imread(vstrImageRight[seq][ni],cv::IMREAD_UNCHANGED); //,cv::IMREAD_UNCHANGED);
  88. if(imLeft.empty())
  89. {
  90. cerr << endl << "Failed to load image at: "
  91. << string(vstrImageLeft[seq][ni]) << endl;
  92. return 1;
  93. }
  94. if(imRight.empty())
  95. {
  96. cerr << endl << "Failed to load image at: "
  97. << string(vstrImageRight[seq][ni]) << endl;
  98. return 1;
  99. }
  100. double tframe = vTimestampsCam[seq][ni];
  101. #ifdef COMPILEDWITHC14
  102. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  103. #else
  104. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  105. #endif
  106. // Pass the images to the SLAM system
  107. SLAM.TrackStereo(imLeft,imRight,tframe, vector<ORB_SLAM3::IMU::Point>(), vstrImageLeft[seq][ni]);
  108. #ifdef COMPILEDWITHC14
  109. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  110. #else
  111. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  112. #endif
  113. #ifdef REGISTER_TIMES
  114. t_track = t_resize + t_rect + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  115. SLAM.InsertTrackTime(t_track);
  116. #endif
  117. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  118. vTimesTrack[ni]=ttrack;
  119. // Wait to load the next frame
  120. double T=0;
  121. if(ni<nImages[seq]-1)
  122. T = vTimestampsCam[seq][ni+1]-tframe;
  123. else if(ni>0)
  124. T = tframe-vTimestampsCam[seq][ni-1];
  125. if(ttrack<T)
  126. usleep((T-ttrack)*1e6); // 1e6
  127. }
  128. if(seq < num_seq - 1)
  129. {
  130. cout << "Changing the dataset" << endl;
  131. SLAM.ChangeDataset();
  132. }
  133. }
  134. // Stop all threads
  135. SLAM.Shutdown();
  136. // Save camera trajectory
  137. if (bFileName)
  138. {
  139. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  140. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  141. SLAM.SaveTrajectoryEuRoC(f_file);
  142. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  143. }
  144. else
  145. {
  146. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  147. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  148. }
  149. return 0;
  150. }
  151. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  152. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  153. {
  154. ifstream fTimes;
  155. fTimes.open(strPathTimes.c_str());
  156. vTimeStamps.reserve(5000);
  157. vstrImageLeft.reserve(5000);
  158. vstrImageRight.reserve(5000);
  159. while(!fTimes.eof())
  160. {
  161. string s;
  162. getline(fTimes,s);
  163. if(!s.empty())
  164. {
  165. stringstream ss;
  166. ss << s;
  167. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  168. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  169. double t;
  170. ss >> t;
  171. vTimeStamps.push_back(t/1e9);
  172. }
  173. }
  174. }