stereo_inertial_euroc.cc 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342
  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 <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. cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r;
  102. fsSettings["LEFT.K"] >> K_l;
  103. fsSettings["RIGHT.K"] >> K_r;
  104. fsSettings["LEFT.P"] >> P_l;
  105. fsSettings["RIGHT.P"] >> P_r;
  106. fsSettings["LEFT.R"] >> R_l;
  107. fsSettings["RIGHT.R"] >> R_r;
  108. fsSettings["LEFT.D"] >> D_l;
  109. fsSettings["RIGHT.D"] >> D_r;
  110. int rows_l = fsSettings["LEFT.height"];
  111. int cols_l = fsSettings["LEFT.width"];
  112. int rows_r = fsSettings["RIGHT.height"];
  113. int cols_r = fsSettings["RIGHT.width"];
  114. 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() ||
  115. rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0)
  116. {
  117. cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl;
  118. return -1;
  119. }
  120. cv::Mat M1l,M2l,M1r,M2r;
  121. 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);
  122. 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);
  123. // Vector for tracking time statistics
  124. vector<float> vTimesTrack;
  125. vTimesTrack.resize(tot_images);
  126. cout << endl << "-------" << endl;
  127. cout.precision(17);
  128. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  129. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, true);
  130. cv::Mat imLeft, imRight, imLeftRect, imRightRect;
  131. for (seq = 0; seq<num_seq; seq++)
  132. {
  133. // Seq loop
  134. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  135. double t_rect = 0;
  136. int num_rect = 0;
  137. int proccIm = 0;
  138. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  139. {
  140. // Read left and right images from file
  141. imLeft = cv::imread(vstrImageLeft[seq][ni],cv::IMREAD_UNCHANGED);
  142. imRight = cv::imread(vstrImageRight[seq][ni],cv::IMREAD_UNCHANGED);
  143. if(imLeft.empty())
  144. {
  145. cerr << endl << "Failed to load image at: "
  146. << string(vstrImageLeft[seq][ni]) << endl;
  147. return 1;
  148. }
  149. if(imRight.empty())
  150. {
  151. cerr << endl << "Failed to load image at: "
  152. << string(vstrImageRight[seq][ni]) << endl;
  153. return 1;
  154. }
  155. #ifdef COMPILEDWITHC11
  156. std::chrono::steady_clock::time_point t_Start_Rect = std::chrono::steady_clock::now();
  157. #else
  158. std::chrono::monotonic_clock::time_point t_Start_Rect = std::chrono::monotonic_clock::now();
  159. #endif
  160. cv::remap(imLeft,imLeftRect,M1l,M2l,cv::INTER_LINEAR);
  161. cv::remap(imRight,imRightRect,M1r,M2r,cv::INTER_LINEAR);
  162. #ifdef COMPILEDWITHC11
  163. std::chrono::steady_clock::time_point t_End_Rect = std::chrono::steady_clock::now();
  164. #else
  165. std::chrono::monotonic_clock::time_point t_End_Rect = std::chrono::monotonic_clock::now();
  166. #endif
  167. t_rect = std::chrono::duration_cast<std::chrono::duration<double> >(t_End_Rect - t_Start_Rect).count();
  168. double tframe = vTimestampsCam[seq][ni];
  169. // Load imu measurements from previous frame
  170. vImuMeas.clear();
  171. if(ni>0)
  172. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni]) // while(vTimestampsImu[first_imu]<=vTimestampsCam[ni])
  173. {
  174. 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,
  175. vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
  176. vTimestampsImu[seq][first_imu[seq]]));
  177. first_imu[seq]++;
  178. }
  179. #ifdef COMPILEDWITHC11
  180. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  181. #else
  182. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  183. #endif
  184. // Pass the images to the SLAM system
  185. SLAM.TrackStereo(imLeftRect,imRightRect,tframe,vImuMeas);
  186. #ifdef COMPILEDWITHC11
  187. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  188. #else
  189. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  190. #endif
  191. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  192. vTimesTrack[ni]=ttrack;
  193. // Wait to load the next frame
  194. double T=0;
  195. if(ni<nImages[seq]-1)
  196. T = vTimestampsCam[seq][ni+1]-tframe;
  197. else if(ni>0)
  198. T = tframe-vTimestampsCam[seq][ni-1];
  199. if(ttrack<T)
  200. usleep((T-ttrack)*1e6); // 1e6
  201. }
  202. if(seq < num_seq - 1)
  203. {
  204. cout << "Changing the dataset" << endl;
  205. SLAM.ChangeDataset();
  206. }
  207. }
  208. // Stop all threads
  209. SLAM.Shutdown();
  210. // Save camera trajectory
  211. if (bFileName)
  212. {
  213. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  214. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  215. SLAM.SaveTrajectoryEuRoC(f_file);
  216. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  217. }
  218. else
  219. {
  220. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  221. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  222. }
  223. return 0;
  224. }
  225. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  226. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  227. {
  228. ifstream fTimes;
  229. fTimes.open(strPathTimes.c_str());
  230. vTimeStamps.reserve(5000);
  231. vstrImageLeft.reserve(5000);
  232. vstrImageRight.reserve(5000);
  233. while(!fTimes.eof())
  234. {
  235. string s;
  236. getline(fTimes,s);
  237. if(!s.empty())
  238. {
  239. stringstream ss;
  240. ss << s;
  241. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  242. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  243. double t;
  244. ss >> t;
  245. vTimeStamps.push_back(t/1e9);
  246. }
  247. }
  248. }
  249. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro)
  250. {
  251. ifstream fImu;
  252. fImu.open(strImuPath.c_str());
  253. vTimeStamps.reserve(5000);
  254. vAcc.reserve(5000);
  255. vGyro.reserve(5000);
  256. while(!fImu.eof())
  257. {
  258. string s;
  259. getline(fImu,s);
  260. if (s[0] == '#')
  261. continue;
  262. if(!s.empty())
  263. {
  264. string item;
  265. size_t pos = 0;
  266. double data[7];
  267. int count = 0;
  268. while ((pos = s.find(',')) != string::npos) {
  269. item = s.substr(0, pos);
  270. data[count++] = stod(item);
  271. s.erase(0, pos + 1);
  272. }
  273. item = s.substr(0, pos);
  274. data[6] = stod(item);
  275. vTimeStamps.push_back(data[0]/1e9);
  276. vAcc.push_back(cv::Point3f(data[4],data[5],data[6]));
  277. vGyro.push_back(cv::Point3f(data[1],data[2],data[3]));
  278. }
  279. }
  280. }