stereo_euroc.cc 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261
  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<iomanip>
  22. #include<chrono>
  23. #include<opencv2/core/core.hpp>
  24. #include<System.h>
  25. using namespace std;
  26. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  27. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps);
  28. int main(int argc, char **argv)
  29. {
  30. if(argc < 5)
  31. {
  32. cerr << endl << "Usage: ./stereo_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;
  33. return 1;
  34. }
  35. const int num_seq = (argc-3)/2;
  36. cout << "num_seq = " << num_seq << endl;
  37. bool bFileName= (((argc-3) % 2) == 1);
  38. string file_name;
  39. if (bFileName)
  40. {
  41. file_name = string(argv[argc-1]);
  42. cout << "file name: " << file_name << endl;
  43. }
  44. // Load all sequences:
  45. int seq;
  46. vector< vector<string> > vstrImageLeft;
  47. vector< vector<string> > vstrImageRight;
  48. vector< vector<double> > vTimestampsCam;
  49. vector<int> nImages;
  50. vstrImageLeft.resize(num_seq);
  51. vstrImageRight.resize(num_seq);
  52. vTimestampsCam.resize(num_seq);
  53. nImages.resize(num_seq);
  54. int tot_images = 0;
  55. for (seq = 0; seq<num_seq; seq++)
  56. {
  57. cout << "Loading images for sequence " << seq << "...";
  58. string pathSeq(argv[(2*seq) + 3]);
  59. string pathTimeStamps(argv[(2*seq) + 4]);
  60. string pathCam0 = pathSeq + "/mav0/cam0/data";
  61. string pathCam1 = pathSeq + "/mav0/cam1/data";
  62. LoadImages(pathCam0, pathCam1, pathTimeStamps, vstrImageLeft[seq], vstrImageRight[seq], vTimestampsCam[seq]);
  63. cout << "LOADED!" << endl;
  64. nImages[seq] = vstrImageLeft[seq].size();
  65. tot_images += nImages[seq];
  66. }
  67. // Read rectification parameters
  68. cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ);
  69. if(!fsSettings.isOpened())
  70. {
  71. cerr << "ERROR: Wrong path to settings" << endl;
  72. return -1;
  73. }
  74. cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r;
  75. fsSettings["LEFT.K"] >> K_l;
  76. fsSettings["RIGHT.K"] >> K_r;
  77. fsSettings["LEFT.P"] >> P_l;
  78. fsSettings["RIGHT.P"] >> P_r;
  79. fsSettings["LEFT.R"] >> R_l;
  80. fsSettings["RIGHT.R"] >> R_r;
  81. fsSettings["LEFT.D"] >> D_l;
  82. fsSettings["RIGHT.D"] >> D_r;
  83. int rows_l = fsSettings["LEFT.height"];
  84. int cols_l = fsSettings["LEFT.width"];
  85. int rows_r = fsSettings["RIGHT.height"];
  86. int cols_r = fsSettings["RIGHT.width"];
  87. if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() ||
  88. rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0)
  89. {
  90. cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl;
  91. return -1;
  92. }
  93. cv::Mat M1l,M2l,M1r,M2r;
  94. cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,M1l,M2l);
  95. cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,M1r,M2r);
  96. // Vector for tracking time statistics
  97. vector<float> vTimesTrack;
  98. vTimesTrack.resize(tot_images);
  99. cout << endl << "-------" << endl;
  100. cout.precision(17);
  101. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  102. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::STEREO, true);
  103. cv::Mat imLeft, imRight, imLeftRect, imRightRect;
  104. for (seq = 0; seq<num_seq; seq++)
  105. {
  106. // Seq loop
  107. double t_rect = 0;
  108. int num_rect = 0;
  109. int proccIm = 0;
  110. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  111. {
  112. // Read left and right images from file
  113. imLeft = cv::imread(vstrImageLeft[seq][ni],cv::IMREAD_UNCHANGED);
  114. imRight = cv::imread(vstrImageRight[seq][ni],cv::IMREAD_UNCHANGED);
  115. if(imLeft.empty())
  116. {
  117. cerr << endl << "Failed to load image at: "
  118. << string(vstrImageLeft[seq][ni]) << endl;
  119. return 1;
  120. }
  121. if(imRight.empty())
  122. {
  123. cerr << endl << "Failed to load image at: "
  124. << string(vstrImageRight[seq][ni]) << endl;
  125. return 1;
  126. }
  127. #ifdef COMPILEDWITHC11
  128. std::chrono::steady_clock::time_point t_Start_Rect = std::chrono::steady_clock::now();
  129. #else
  130. std::chrono::monotonic_clock::time_point t_Start_Rect = std::chrono::monotonic_clock::now();
  131. #endif
  132. cv::remap(imLeft,imLeftRect,M1l,M2l,cv::INTER_LINEAR);
  133. cv::remap(imRight,imRightRect,M1r,M2r,cv::INTER_LINEAR);
  134. #ifdef COMPILEDWITHC11
  135. std::chrono::steady_clock::time_point t_End_Rect = std::chrono::steady_clock::now();
  136. #else
  137. std::chrono::monotonic_clock::time_point t_End_Rect = std::chrono::monotonic_clock::now();
  138. #endif
  139. t_rect = std::chrono::duration_cast<std::chrono::duration<double> >(t_End_Rect - t_Start_Rect).count();
  140. double tframe = vTimestampsCam[seq][ni];
  141. #ifdef COMPILEDWITHC11
  142. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  143. #else
  144. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  145. #endif
  146. // Pass the images to the SLAM system
  147. SLAM.TrackStereo(imLeftRect,imRightRect,tframe, vector<ORB_SLAM3::IMU::Point>(), vstrImageLeft[seq][ni]);
  148. #ifdef COMPILEDWITHC11
  149. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  150. #else
  151. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  152. #endif
  153. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  154. vTimesTrack[ni]=ttrack;
  155. // Wait to load the next frame
  156. double T=0;
  157. if(ni<nImages[seq]-1)
  158. T = vTimestampsCam[seq][ni+1]-tframe;
  159. else if(ni>0)
  160. T = tframe-vTimestampsCam[seq][ni-1];
  161. if(ttrack<T)
  162. usleep((T-ttrack)*1e6); // 1e6
  163. }
  164. if(seq < num_seq - 1)
  165. {
  166. cout << "Changing the dataset" << endl;
  167. SLAM.ChangeDataset();
  168. }
  169. }
  170. // Stop all threads
  171. SLAM.Shutdown();
  172. // Save camera trajectory
  173. if (bFileName)
  174. {
  175. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  176. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  177. SLAM.SaveTrajectoryEuRoC(f_file);
  178. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  179. }
  180. else
  181. {
  182. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  183. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  184. }
  185. return 0;
  186. }
  187. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  188. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  189. {
  190. ifstream fTimes;
  191. fTimes.open(strPathTimes.c_str());
  192. vTimeStamps.reserve(5000);
  193. vstrImageLeft.reserve(5000);
  194. vstrImageRight.reserve(5000);
  195. while(!fTimes.eof())
  196. {
  197. string s;
  198. getline(fTimes,s);
  199. if(!s.empty())
  200. {
  201. stringstream ss;
  202. ss << s;
  203. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  204. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  205. double t;
  206. ss >> t;
  207. vTimeStamps.push_back(t/1e9);
  208. }
  209. }
  210. }