stereo_inertial_euroc.cc 9.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303
  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 <ctime>
  24. #include <sstream>
  25. #include <opencv2/core/core.hpp>
  26. #include<System.h>
  27. #include "ImuTypes.h"
  28. #include "Optimizer.h"
  29. using namespace std;
  30. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  31. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps);
  32. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro);
  33. int main(int argc, char **argv)
  34. {
  35. if(argc < 5)
  36. {
  37. cerr << endl << "Usage: ./stereo_inertial_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) " << endl;
  38. return 1;
  39. }
  40. const int num_seq = (argc-3)/2;
  41. cout << "num_seq = " << num_seq << endl;
  42. bool bFileName= (((argc-3) % 2) == 1);
  43. string file_name;
  44. if (bFileName)
  45. {
  46. file_name = string(argv[argc-1]);
  47. cout << "file name: " << file_name << endl;
  48. }
  49. // Load all sequences:
  50. int seq;
  51. vector< vector<string> > vstrImageLeft;
  52. vector< vector<string> > vstrImageRight;
  53. vector< vector<double> > vTimestampsCam;
  54. vector< vector<cv::Point3f> > vAcc, vGyro;
  55. vector< vector<double> > vTimestampsImu;
  56. vector<int> nImages;
  57. vector<int> nImu;
  58. vector<int> first_imu(num_seq,0);
  59. vstrImageLeft.resize(num_seq);
  60. vstrImageRight.resize(num_seq);
  61. vTimestampsCam.resize(num_seq);
  62. vAcc.resize(num_seq);
  63. vGyro.resize(num_seq);
  64. vTimestampsImu.resize(num_seq);
  65. nImages.resize(num_seq);
  66. nImu.resize(num_seq);
  67. int tot_images = 0;
  68. for (seq = 0; seq<num_seq; seq++)
  69. {
  70. cout << "Loading images for sequence " << seq << "...";
  71. string pathSeq(argv[(2*seq) + 3]);
  72. string pathTimeStamps(argv[(2*seq) + 4]);
  73. string pathCam0 = pathSeq + "/mav0/cam0/data";
  74. string pathCam1 = pathSeq + "/mav0/cam1/data";
  75. string pathImu = pathSeq + "/mav0/imu0/data.csv";
  76. LoadImages(pathCam0, pathCam1, pathTimeStamps, vstrImageLeft[seq], vstrImageRight[seq], vTimestampsCam[seq]);
  77. cout << "LOADED!" << endl;
  78. cout << "Loading IMU for sequence " << seq << "...";
  79. LoadIMU(pathImu, vTimestampsImu[seq], vAcc[seq], vGyro[seq]);
  80. cout << "LOADED!" << endl;
  81. nImages[seq] = vstrImageLeft[seq].size();
  82. tot_images += nImages[seq];
  83. nImu[seq] = vTimestampsImu[seq].size();
  84. if((nImages[seq]<=0)||(nImu[seq]<=0))
  85. {
  86. cerr << "ERROR: Failed to load images or IMU for sequence" << seq << endl;
  87. return 1;
  88. }
  89. // Find first imu to be considered, supposing imu measurements start first
  90. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][0])
  91. first_imu[seq]++;
  92. first_imu[seq]--; // first imu measurement to be considered
  93. }
  94. // Read rectification parameters
  95. cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ);
  96. if(!fsSettings.isOpened())
  97. {
  98. cerr << "ERROR: Wrong path to settings" << endl;
  99. return -1;
  100. }
  101. // Vector for tracking time statistics
  102. vector<float> vTimesTrack;
  103. vTimesTrack.resize(tot_images);
  104. cout << endl << "-------" << endl;
  105. cout.precision(17);
  106. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  107. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, false);
  108. cv::Mat imLeft, imRight;
  109. for (seq = 0; seq<num_seq; seq++)
  110. {
  111. // Seq loop
  112. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  113. double t_rect = 0.f;
  114. double t_resize = 0.f;
  115. double t_track = 0.f;
  116. int num_rect = 0;
  117. int proccIm = 0;
  118. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  119. {
  120. // Read left and right images from file
  121. imLeft = cv::imread(vstrImageLeft[seq][ni],cv::IMREAD_UNCHANGED);
  122. imRight = cv::imread(vstrImageRight[seq][ni],cv::IMREAD_UNCHANGED);
  123. if(imLeft.empty())
  124. {
  125. cerr << endl << "Failed to load image at: "
  126. << string(vstrImageLeft[seq][ni]) << endl;
  127. return 1;
  128. }
  129. if(imRight.empty())
  130. {
  131. cerr << endl << "Failed to load image at: "
  132. << string(vstrImageRight[seq][ni]) << endl;
  133. return 1;
  134. }
  135. double tframe = vTimestampsCam[seq][ni];
  136. // Load imu measurements from previous frame
  137. vImuMeas.clear();
  138. if(ni>0)
  139. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni]) // while(vTimestampsImu[first_imu]<=vTimestampsCam[ni])
  140. {
  141. vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[seq][first_imu[seq]].x,vAcc[seq][first_imu[seq]].y,vAcc[seq][first_imu[seq]].z,
  142. vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
  143. vTimestampsImu[seq][first_imu[seq]]));
  144. first_imu[seq]++;
  145. }
  146. #ifdef COMPILEDWITHC14
  147. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  148. #else
  149. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  150. #endif
  151. // Pass the images to the SLAM system
  152. SLAM.TrackStereo(imLeft,imRight,tframe,vImuMeas);
  153. #ifdef COMPILEDWITHC14
  154. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  155. #else
  156. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  157. #endif
  158. #ifdef REGISTER_TIMES
  159. t_track = t_rect + t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  160. SLAM.InsertTrackTime(t_track);
  161. #endif
  162. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  163. vTimesTrack[ni]=ttrack;
  164. // Wait to load the next frame
  165. double T=0;
  166. if(ni<nImages[seq]-1)
  167. T = vTimestampsCam[seq][ni+1]-tframe;
  168. else if(ni>0)
  169. T = tframe-vTimestampsCam[seq][ni-1];
  170. if(ttrack<T)
  171. usleep((T-ttrack)*1e6); // 1e6
  172. }
  173. if(seq < num_seq - 1)
  174. {
  175. cout << "Changing the dataset" << endl;
  176. SLAM.ChangeDataset();
  177. }
  178. }
  179. // Stop all threads
  180. SLAM.Shutdown();
  181. // Save camera trajectory
  182. if (bFileName)
  183. {
  184. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  185. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  186. SLAM.SaveTrajectoryEuRoC(f_file);
  187. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  188. }
  189. else
  190. {
  191. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  192. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  193. }
  194. return 0;
  195. }
  196. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  197. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  198. {
  199. ifstream fTimes;
  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 LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro)
  221. {
  222. ifstream fImu;
  223. fImu.open(strImuPath.c_str());
  224. vTimeStamps.reserve(5000);
  225. vAcc.reserve(5000);
  226. vGyro.reserve(5000);
  227. while(!fImu.eof())
  228. {
  229. string s;
  230. getline(fImu,s);
  231. if (s[0] == '#')
  232. continue;
  233. if(!s.empty())
  234. {
  235. string item;
  236. size_t pos = 0;
  237. double data[7];
  238. int count = 0;
  239. while ((pos = s.find(',')) != string::npos) {
  240. item = s.substr(0, pos);
  241. data[count++] = stod(item);
  242. s.erase(0, pos + 1);
  243. }
  244. item = s.substr(0, pos);
  245. data[6] = stod(item);
  246. vTimeStamps.push_back(data[0]/1e9);
  247. vAcc.push_back(cv::Point3f(data[4],data[5],data[6]));
  248. vGyro.push_back(cv::Point3f(data[1],data[2],data[3]));
  249. }
  250. }
  251. }