mono_tum_vi.cc 7.8 KB

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