mono_tum_vi.cc 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219
  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<iomanip>
  23. #include <unistd.h>
  24. #include<opencv2/core/core.hpp>
  25. #include"System.h"
  26. #include "Converter.h"
  27. using namespace std;
  28. void LoadImages(const string &strImagePath, const string &strPathTimes,
  29. vector<string> &vstrImages, vector<double> &vTimeStamps);
  30. double ttrack_tot = 0;
  31. int main(int argc, char **argv)
  32. {
  33. const int num_seq = (argc-3)/2;
  34. cout << "num_seq = " << num_seq << endl;
  35. bool bFileName= (((argc-3) % 2) == 1);
  36. string file_name;
  37. if (bFileName)
  38. {
  39. file_name = string(argv[argc-1]);
  40. cout << "file name: " << file_name << endl;
  41. }
  42. if(argc < 4)
  43. {
  44. cerr << endl << "Usage: ./mono_tum_vi path_to_vocabulary path_to_settings path_to_image_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;
  45. return 1;
  46. }
  47. // Load all sequences:
  48. int seq;
  49. vector< vector<string> > vstrImageFilenames;
  50. vector< vector<double> > vTimestampsCam;
  51. vector<int> nImages;
  52. vstrImageFilenames.resize(num_seq);
  53. vTimestampsCam.resize(num_seq);
  54. nImages.resize(num_seq);
  55. int tot_images = 0;
  56. for (seq = 0; seq<num_seq; seq++)
  57. {
  58. cout << "Loading images for sequence " << seq << "...";
  59. LoadImages(string(argv[(2*seq)+3]), string(argv[(2*seq)+4]), vstrImageFilenames[seq], vTimestampsCam[seq]);
  60. cout << "LOADED!" << endl;
  61. nImages[seq] = vstrImageFilenames[seq].size();
  62. tot_images += nImages[seq];
  63. if((nImages[seq]<=0))
  64. {
  65. cerr << "ERROR: Failed to load images for sequence" << seq << endl;
  66. return 1;
  67. }
  68. }
  69. // Vector for tracking time statistics
  70. vector<float> vTimesTrack;
  71. vTimesTrack.resize(tot_images);
  72. cout << endl << "-------" << endl;
  73. cout.precision(17);
  74. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  75. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true);
  76. int proccIm = 0;
  77. for (seq = 0; seq<num_seq; seq++)
  78. {
  79. // Main loop
  80. cv::Mat im;
  81. proccIm = 0;
  82. cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  83. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  84. {
  85. // Read image from file
  86. im = cv::imread(vstrImageFilenames[seq][ni],cv::IMREAD_UNCHANGED);
  87. // clahe
  88. clahe->apply(im,im);
  89. // cout << "mat type: " << im.type() << endl;
  90. double tframe = vTimestampsCam[seq][ni];
  91. if(im.empty())
  92. {
  93. cerr << endl << "Failed to load image at: "
  94. << vstrImageFilenames[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.TrackMonocular(im,tframe); // TODO change to monocular_inertial
  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. vTimesTrack[ni]=ttrack;
  112. // Wait to load the next frame
  113. double T=0;
  114. if(ni<nImages[seq]-1)
  115. T = vTimestampsCam[seq][ni+1]-tframe;
  116. else if(ni>0)
  117. T = tframe-vTimestampsCam[seq][ni-1];
  118. if(ttrack<T)
  119. usleep((T-ttrack)*1e6);
  120. }
  121. if(seq < num_seq - 1)
  122. {
  123. cout << "Changing the dataset" << endl;
  124. SLAM.ChangeDataset();
  125. }
  126. }
  127. // Stop all threads
  128. SLAM.Shutdown();
  129. // Save camera trajectory
  130. if (bFileName)
  131. {
  132. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  133. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  134. SLAM.SaveTrajectoryEuRoC(f_file);
  135. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  136. }
  137. else
  138. {
  139. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  140. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  141. }
  142. sort(vTimesTrack.begin(),vTimesTrack.end());
  143. float totaltime = 0;
  144. for(int ni=0; ni<nImages[0]; ni++)
  145. {
  146. totaltime+=vTimesTrack[ni];
  147. }
  148. cout << "-------" << endl << endl;
  149. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  150. cout << "mean tracking time: " << totaltime/proccIm << endl;
  151. return 0;
  152. }
  153. void LoadImages(const string &strImagePath, const string &strPathTimes,
  154. vector<string> &vstrImages, vector<double> &vTimeStamps)
  155. {
  156. ifstream fTimes;
  157. cout << strImagePath << endl;
  158. cout << strPathTimes << endl;
  159. fTimes.open(strPathTimes.c_str());
  160. vTimeStamps.reserve(5000);
  161. vstrImages.reserve(5000);
  162. while(!fTimes.eof())
  163. {
  164. string s;
  165. getline(fTimes,s);
  166. if(!s.empty())
  167. {
  168. stringstream ss;
  169. ss << s;
  170. vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
  171. double t;
  172. ss >> t;
  173. vTimeStamps.push_back(t/1e9);
  174. }
  175. }
  176. }