stereo_tum_vi.cc 9.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296
  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 <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. float imageScale = SLAM.GetImageScale();
  78. cout << endl << "-------" << endl;
  79. cout.precision(17);
  80. cv::Mat imLeft, imRight;
  81. cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  82. double t_resize = 0.f;
  83. double t_track = 0.f;
  84. int proccIm = 0;
  85. for (seq = 0; seq<num_seq; seq++)
  86. {
  87. // Main loop
  88. proccIm = 0;
  89. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  90. {
  91. // Read image from file
  92. imLeft = cv::imread(vstrImageLeftFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  93. imRight = cv::imread(vstrImageRightFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  94. if(imageScale != 1.f)
  95. {
  96. #ifdef REGISTER_TIMES
  97. #ifdef COMPILEDWITHC14
  98. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  99. #else
  100. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  101. #endif
  102. #endif
  103. int width = imLeft.cols * imageScale;
  104. int height = imLeft.rows * imageScale;
  105. cv::resize(imLeft, imLeft, cv::Size(width, height));
  106. cv::resize(imRight, imRight, cv::Size(width, height));
  107. #ifdef REGISTER_TIMES
  108. #ifdef COMPILEDWITHC14
  109. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  110. #else
  111. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  112. #endif
  113. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  114. SLAM.InsertResizeTime(t_resize);
  115. #endif
  116. }
  117. // clahe
  118. clahe->apply(imLeft,imLeft);
  119. clahe->apply(imRight,imRight);
  120. double tframe = vTimestampsCam[seq][ni];
  121. if(imLeft.empty() || imRight.empty())
  122. {
  123. cerr << endl << "Failed to load image at: "
  124. << vstrImageLeftFilenames[seq][ni] << endl;
  125. return 1;
  126. }
  127. #ifdef COMPILEDWITHC14
  128. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  129. #else
  130. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  131. #endif
  132. // Pass the image to the SLAM system
  133. SLAM.TrackStereo(imLeft,imRight,tframe);
  134. #ifdef COMPILEDWITHC14
  135. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  136. #else
  137. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  138. #endif
  139. #ifdef REGISTER_TIMES
  140. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  141. SLAM.InsertTrackTime(t_track);
  142. #endif
  143. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  144. ttrack_tot += ttrack;
  145. // std::cout << "ttrack: " << ttrack << std::endl;
  146. vTimesTrack[ni]=ttrack;
  147. // Wait to load the next frame
  148. double T=0;
  149. if(ni<nImages[seq]-1)
  150. T = vTimestampsCam[seq][ni+1]-tframe;
  151. else if(ni>0)
  152. T = tframe-vTimestampsCam[seq][ni-1];
  153. if(ttrack<T)
  154. usleep((T-ttrack)*1e6); // 1e6
  155. }
  156. if(seq < num_seq - 1)
  157. {
  158. cout << "Changing the dataset" << endl;
  159. SLAM.ChangeDataset();
  160. }
  161. }
  162. // Stop all threads
  163. SLAM.Shutdown();
  164. // Tracking time statistics
  165. // Save camera trajectory
  166. std::chrono::system_clock::time_point scNow = std::chrono::system_clock::now();
  167. std::time_t now = std::chrono::system_clock::to_time_t(scNow);
  168. std::stringstream ss;
  169. ss << now;
  170. if (bFileName)
  171. {
  172. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  173. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  174. SLAM.SaveTrajectoryEuRoC(f_file);
  175. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  176. }
  177. else
  178. {
  179. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  180. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  181. }
  182. sort(vTimesTrack.begin(),vTimesTrack.end());
  183. float totaltime = 0;
  184. for(int ni=0; ni<nImages[0]; ni++)
  185. {
  186. totaltime+=vTimesTrack[ni];
  187. }
  188. cout << "-------" << endl << endl;
  189. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  190. cout << "mean tracking time: " << totaltime/proccIm << endl;
  191. return 0;
  192. }
  193. /*void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  194. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  195. {
  196. ifstream fTimes;
  197. cout << strPathLeft << endl;
  198. cout << strPathRight << endl;
  199. cout << strPathTimes << endl;
  200. fTimes.open(strPathTimes.c_str());
  201. vTimeStamps.reserve(5000);
  202. vstrImageLeft.reserve(5000);
  203. vstrImageRight.reserve(5000);
  204. while(!fTimes.eof())
  205. {
  206. string s;
  207. getline(fTimes,s);
  208. if(!s.empty())
  209. {
  210. stringstream ss;
  211. ss << s;
  212. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  213. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  214. double t;
  215. ss >> t;
  216. vTimeStamps.push_back(t/1e9);
  217. }
  218. }
  219. }*/
  220. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  221. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  222. {
  223. ifstream fTimes;
  224. cout << strPathLeft << endl;
  225. cout << strPathRight << endl;
  226. cout << strPathTimes << endl;
  227. fTimes.open(strPathTimes.c_str());
  228. vTimeStamps.reserve(5000);
  229. vstrImageLeft.reserve(5000);
  230. vstrImageRight.reserve(5000);
  231. while(!fTimes.eof())
  232. {
  233. string s;
  234. getline(fTimes,s);
  235. if(!s.empty())
  236. {
  237. if (s[0] == '#')
  238. continue;
  239. int pos = s.find(' ');
  240. string item = s.substr(0, pos);
  241. vstrImageLeft.push_back(strPathLeft + "/" + item + ".png");
  242. vstrImageRight.push_back(strPathRight + "/" + item + ".png");
  243. double t = stod(item);
  244. vTimeStamps.push_back(t/1e9);
  245. }
  246. }
  247. }