mono_euroc.cc 7.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228
  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 &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. int fps = 20;
  66. float dT = 1.f/fps;
  67. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  68. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, false);
  69. float imageScale = SLAM.GetImageScale();
  70. double t_resize = 0.f;
  71. double t_track = 0.f;
  72. for (seq = 0; seq<num_seq; seq++)
  73. {
  74. // Main loop
  75. cv::Mat im;
  76. int proccIm = 0;
  77. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  78. {
  79. // Read image from file
  80. im = cv::imread(vstrImageFilenames[seq][ni],cv::IMREAD_UNCHANGED); //,CV_LOAD_IMAGE_UNCHANGED);
  81. double tframe = vTimestampsCam[seq][ni];
  82. if(im.empty())
  83. {
  84. cerr << endl << "Failed to load image at: "
  85. << vstrImageFilenames[seq][ni] << endl;
  86. return 1;
  87. }
  88. if(imageScale != 1.f)
  89. {
  90. #ifdef REGISTER_TIMES
  91. #ifdef COMPILEDWITHC14
  92. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  93. #else
  94. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  95. #endif
  96. #endif
  97. int width = im.cols * imageScale;
  98. int height = im.rows * imageScale;
  99. cv::resize(im, im, cv::Size(width, height));
  100. #ifdef REGISTER_TIMES
  101. #ifdef COMPILEDWITHC14
  102. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  103. #else
  104. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  105. #endif
  106. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  107. SLAM.InsertResizeTime(t_resize);
  108. #endif
  109. }
  110. #ifdef COMPILEDWITHC14
  111. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  112. #else
  113. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  114. #endif
  115. // Pass the image to the SLAM system
  116. // cout << "tframe = " << tframe << endl;
  117. SLAM.TrackMonocular(im,tframe); // TODO change to monocular_inertial
  118. #ifdef COMPILEDWITHC14
  119. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  120. #else
  121. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  122. #endif
  123. #ifdef REGISTER_TIMES
  124. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  125. SLAM.InsertTrackTime(t_track);
  126. #endif
  127. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  128. vTimesTrack[ni]=ttrack;
  129. // Wait to load the next frame
  130. double T=0;
  131. if(ni<nImages[seq]-1)
  132. T = vTimestampsCam[seq][ni+1]-tframe;
  133. else if(ni>0)
  134. T = tframe-vTimestampsCam[seq][ni-1];
  135. //std::cout << "T: " << T << std::endl;
  136. //std::cout << "ttrack: " << ttrack << std::endl;
  137. if(ttrack<T) {
  138. //std::cout << "usleep: " << (dT-ttrack) << std::endl;
  139. usleep((T-ttrack)*1e6); // 1e6
  140. }
  141. }
  142. if(seq < num_seq - 1)
  143. {
  144. string kf_file_submap = "./SubMaps/kf_SubMap_" + std::to_string(seq) + ".txt";
  145. string f_file_submap = "./SubMaps/f_SubMap_" + std::to_string(seq) + ".txt";
  146. SLAM.SaveTrajectoryEuRoC(f_file_submap);
  147. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file_submap);
  148. cout << "Changing the dataset" << endl;
  149. SLAM.ChangeDataset();
  150. }
  151. }
  152. // Stop all threads
  153. SLAM.Shutdown();
  154. // Save camera trajectory
  155. if (bFileName)
  156. {
  157. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  158. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  159. SLAM.SaveTrajectoryEuRoC(f_file);
  160. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  161. }
  162. else
  163. {
  164. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  165. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  166. }
  167. return 0;
  168. }
  169. void LoadImages(const string &strImagePath, const string &strPathTimes,
  170. vector<string> &vstrImages, vector<double> &vTimeStamps)
  171. {
  172. ifstream fTimes;
  173. fTimes.open(strPathTimes.c_str());
  174. vTimeStamps.reserve(5000);
  175. vstrImages.reserve(5000);
  176. while(!fTimes.eof())
  177. {
  178. string s;
  179. getline(fTimes,s);
  180. if(!s.empty())
  181. {
  182. stringstream ss;
  183. ss << s;
  184. vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
  185. double t;
  186. ss >> t;
  187. vTimeStamps.push_back(t*1e-9);
  188. }
  189. }
  190. }