stereo_inertial_tum_vi.cc 10.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301
  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<chrono>
  22. #include <ctime>
  23. #include <sstream>
  24. #include<opencv2/core/core.hpp>
  25. #include<System.h>
  26. #include "ImuTypes.h"
  27. using namespace std;
  28. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  29. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps);
  30. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro);
  31. double ttrack_tot = 0;
  32. int main(int argc, char **argv)
  33. {
  34. const int num_seq = (argc-3)/4;
  35. cout << "num_seq = " << num_seq << endl;
  36. bool bFileName= (((argc-3) % 4) == 1);
  37. string file_name;
  38. if (bFileName)
  39. file_name = string(argv[argc-1]);
  40. if(argc < 7)
  41. {
  42. cerr << endl << "Usage: ./stereo_inertial_tum_vi path_to_vocabulary path_to_settings path_to_image_folder_1 path_to_image_folder_2 path_to_times_file path_to_imu_data (trajectory_file_name)" << endl;
  43. return 1;
  44. }
  45. // Load all sequences:
  46. int seq;
  47. vector< vector<string> > vstrImageLeftFilenames;
  48. vector< vector<string> > vstrImageRightFilenames;
  49. vector< vector<double> > vTimestampsCam;
  50. vector< vector<cv::Point3f> > vAcc, vGyro;
  51. vector< vector<double> > vTimestampsImu;
  52. vector<int> nImages;
  53. vector<int> nImu;
  54. vector<int> first_imu(num_seq,0);
  55. vstrImageLeftFilenames.resize(num_seq);
  56. vstrImageRightFilenames.resize(num_seq);
  57. vTimestampsCam.resize(num_seq);
  58. vAcc.resize(num_seq);
  59. vGyro.resize(num_seq);
  60. vTimestampsImu.resize(num_seq);
  61. nImages.resize(num_seq);
  62. nImu.resize(num_seq);
  63. int tot_images = 0;
  64. for (seq = 0; seq<num_seq; seq++)
  65. {
  66. cout << "Loading images for sequence " << seq << "...";
  67. LoadImages(string(argv[4*(seq+1)-1]), string(argv[4*(seq+1)]), string(argv[4*(seq+1)+1]), vstrImageLeftFilenames[seq], vstrImageRightFilenames[seq], vTimestampsCam[seq]);
  68. cout << "Total images: " << vstrImageLeftFilenames[seq].size() << endl;
  69. cout << "Total cam ts: " << vTimestampsCam[seq].size() << endl;
  70. cout << "first cam ts: " << vTimestampsCam[seq][0] << endl;
  71. cout << "LOADED!" << endl;
  72. cout << "Loading IMU for sequence " << seq << "...";
  73. LoadIMU(string(argv[4*(seq+1)+2]), vTimestampsImu[seq], vAcc[seq], vGyro[seq]);
  74. cout << "Total IMU meas: " << vTimestampsImu[seq].size() << endl;
  75. cout << "first IMU ts: " << vTimestampsImu[seq][0] << endl;
  76. cout << "LOADED!" << endl;
  77. nImages[seq] = vstrImageLeftFilenames[seq].size();
  78. tot_images += nImages[seq];
  79. nImu[seq] = vTimestampsImu[seq].size();
  80. if((nImages[seq]<=0)||(nImu[seq]<=0))
  81. {
  82. cerr << "ERROR: Failed to load images or IMU for sequence" << seq << endl;
  83. return 1;
  84. }
  85. // Find first imu to be considered, supposing imu measurements start first
  86. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][0])
  87. first_imu[seq]++;
  88. first_imu[seq]--; // first imu measurement to be considered
  89. }
  90. // Vector for tracking time statistics
  91. vector<float> vTimesTrack;
  92. vTimesTrack.resize(tot_images);
  93. cout << endl << "-------" << endl;
  94. cout.precision(17);
  95. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  96. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, true, 0, file_name);
  97. int proccIm = 0;
  98. for (seq = 0; seq<num_seq; seq++)
  99. {
  100. // Main loop
  101. cv::Mat imLeft, imRight;
  102. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  103. proccIm = 0;
  104. cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  105. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  106. {
  107. // Read image from file
  108. imLeft = cv::imread(vstrImageLeftFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  109. imRight = cv::imread(vstrImageRightFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  110. // clahe
  111. clahe->apply(imLeft,imLeft);
  112. clahe->apply(imRight,imRight);
  113. double tframe = vTimestampsCam[seq][ni];
  114. if(imLeft.empty() || imRight.empty())
  115. {
  116. cerr << endl << "Failed to load image at: "
  117. << vstrImageLeftFilenames[seq][ni] << endl;
  118. return 1;
  119. }
  120. // Load imu measurements from previous frame
  121. vImuMeas.clear();
  122. if(ni>0)
  123. {
  124. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
  125. {
  126. 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,
  127. vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
  128. vTimestampsImu[seq][first_imu[seq]]));
  129. first_imu[seq]++;
  130. }
  131. }
  132. #ifdef COMPILEDWITHC11
  133. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  134. #else
  135. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  136. #endif
  137. // Pass the image to the SLAM system
  138. SLAM.TrackStereo(imLeft,imRight,tframe,vImuMeas);
  139. #ifdef COMPILEDWITHC11
  140. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  141. #else
  142. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  143. #endif
  144. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  145. ttrack_tot += ttrack;
  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);
  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. // Save camera trajectory
  165. std::chrono::system_clock::time_point scNow = std::chrono::system_clock::now();
  166. std::time_t now = std::chrono::system_clock::to_time_t(scNow);
  167. std::stringstream ss;
  168. ss << now;
  169. if (bFileName)
  170. {
  171. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  172. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  173. SLAM.SaveTrajectoryEuRoC(f_file);
  174. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  175. }
  176. else
  177. {
  178. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  179. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  180. }
  181. sort(vTimesTrack.begin(),vTimesTrack.end());
  182. float totaltime = 0;
  183. for(int ni=0; ni<nImages[0]; ni++)
  184. {
  185. totaltime+=vTimesTrack[ni];
  186. }
  187. cout << "-------" << endl << endl;
  188. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  189. cout << "mean tracking time: " << totaltime/proccIm << endl;
  190. return 0;
  191. }
  192. void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  193. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  194. {
  195. ifstream fTimes;
  196. cout << strPathLeft << endl;
  197. cout << strPathRight << endl;
  198. cout << strPathTimes << endl;
  199. fTimes.open(strPathTimes.c_str());
  200. vTimeStamps.reserve(5000);
  201. vstrImageLeft.reserve(5000);
  202. vstrImageRight.reserve(5000);
  203. while(!fTimes.eof())
  204. {
  205. string s;
  206. getline(fTimes,s);
  207. if(!s.empty())
  208. {
  209. stringstream ss;
  210. ss << s;
  211. vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png");
  212. vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png");
  213. double t;
  214. ss >> t;
  215. vTimeStamps.push_back(t/1e9);
  216. }
  217. }
  218. }
  219. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro)
  220. {
  221. ifstream fImu;
  222. fImu.open(strImuPath.c_str());
  223. vTimeStamps.reserve(5000);
  224. vAcc.reserve(5000);
  225. vGyro.reserve(5000);
  226. while(!fImu.eof())
  227. {
  228. string s;
  229. getline(fImu,s);
  230. if (s[0] == '#')
  231. continue;
  232. if(!s.empty())
  233. {
  234. string item;
  235. size_t pos = 0;
  236. double data[7];
  237. int count = 0;
  238. while ((pos = s.find(',')) != string::npos) {
  239. item = s.substr(0, pos);
  240. data[count++] = stod(item);
  241. s.erase(0, pos + 1);
  242. }
  243. item = s.substr(0, pos);
  244. data[6] = stod(item);
  245. vTimeStamps.push_back(data[0]/1e9);
  246. vAcc.push_back(cv::Point3f(data[4],data[5],data[6]));
  247. vGyro.push_back(cv::Point3f(data[1],data[2],data[3]));
  248. }
  249. }
  250. }