mono_euroc.cc 5.7 KB

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