stereo_inertial_tum_vi.cc 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353
  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 <ctime>
  23. #include <sstream>
  24. #include<opencv2/core/core.hpp>
  25. #include<System.h>
  26. #include "ImuTypes.h"
  27. using namespace std;
  28. void LoadImagesTUMVI(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. LoadImagesTUMVI(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. /*cout << "Start processing sequence ..." << endl;
  96. cout << "Images in the sequence: " << nImages << endl;
  97. cout << "IMU data in the sequence: " << nImu << endl << endl;*/
  98. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  99. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, true, 0, file_name);
  100. float imageScale = SLAM.GetImageScale();
  101. double t_resize = 0.f;
  102. double t_track = 0.f;
  103. int proccIm = 0;
  104. for (seq = 0; seq<num_seq; seq++)
  105. {
  106. // Main loop
  107. cv::Mat imLeft, imRight;
  108. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  109. proccIm = 0;
  110. cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  111. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  112. {
  113. // Read image from file
  114. imLeft = cv::imread(vstrImageLeftFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  115. imRight = cv::imread(vstrImageRightFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  116. if(imageScale != 1.f)
  117. {
  118. #ifdef REGISTER_TIMES
  119. #ifdef COMPILEDWITHC14
  120. std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
  121. #else
  122. std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
  123. #endif
  124. #endif
  125. int width = imLeft.cols * imageScale;
  126. int height = imLeft.rows * imageScale;
  127. cv::resize(imLeft, imLeft, cv::Size(width, height));
  128. cv::resize(imRight, imRight, cv::Size(width, height));
  129. #ifdef REGISTER_TIMES
  130. #ifdef COMPILEDWITHC14
  131. std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
  132. #else
  133. std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
  134. #endif
  135. t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t_End_Resize - t_Start_Resize).count();
  136. SLAM.InsertResizeTime(t_resize);
  137. #endif
  138. }
  139. // clahe
  140. clahe->apply(imLeft,imLeft);
  141. clahe->apply(imRight,imRight);
  142. double tframe = vTimestampsCam[seq][ni];
  143. if(imLeft.empty() || imRight.empty())
  144. {
  145. cerr << endl << "Failed to load image at: "
  146. << vstrImageLeftFilenames[seq][ni] << endl;
  147. return 1;
  148. }
  149. // Load imu measurements from previous frame
  150. vImuMeas.clear();
  151. if(ni>0)
  152. {
  153. // cout << "t_cam " << tframe << endl;
  154. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
  155. {
  156. // vImuMeas.push_back(ORB_SLAM3::IMU::Point(vAcc[first_imu],vGyro[first_imu],vTimestampsImu[first_imu]));
  157. 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,
  158. vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
  159. vTimestampsImu[seq][first_imu[seq]]));
  160. // cout << "t_imu = " << fixed << vImuMeas.back().t << endl;
  161. first_imu[seq]++;
  162. }
  163. }
  164. /*cout << "first imu: " << first_imu[seq] << endl;
  165. cout << "first imu time: " << fixed << vTimestampsImu[seq][0] << endl;
  166. cout << "size vImu: " << vImuMeas.size() << endl;*/
  167. #ifdef COMPILEDWITHC14
  168. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  169. #else
  170. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  171. #endif
  172. // Pass the image to the SLAM system
  173. SLAM.TrackStereo(imLeft,imRight,tframe,vImuMeas);
  174. #ifdef COMPILEDWITHC14
  175. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  176. #else
  177. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  178. #endif
  179. #ifdef REGISTER_TIMES
  180. t_track = t_resize + std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(t2 - t1).count();
  181. SLAM.InsertTrackTime(t_track);
  182. #endif
  183. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  184. ttrack_tot += ttrack;
  185. // std::cout << "ttrack: " << ttrack << std::endl;
  186. vTimesTrack[ni]=ttrack;
  187. // Wait to load the next frame
  188. double T=0;
  189. if(ni<nImages[seq]-1)
  190. T = vTimestampsCam[seq][ni+1]-tframe;
  191. else if(ni>0)
  192. T = tframe-vTimestampsCam[seq][ni-1];
  193. if(ttrack<T)
  194. usleep((T-ttrack)*1e6); // 1e6
  195. }
  196. if(seq < num_seq - 1)
  197. {
  198. cout << "Changing the dataset" << endl;
  199. SLAM.ChangeDataset();
  200. }
  201. }
  202. // Stop all threads
  203. SLAM.Shutdown();
  204. // Tracking time statistics
  205. // Save camera trajectory
  206. std::chrono::system_clock::time_point scNow = std::chrono::system_clock::now();
  207. std::time_t now = std::chrono::system_clock::to_time_t(scNow);
  208. std::stringstream ss;
  209. ss << now;
  210. if (bFileName)
  211. {
  212. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  213. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  214. SLAM.SaveTrajectoryEuRoC(f_file);
  215. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  216. }
  217. else
  218. {
  219. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  220. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  221. }
  222. sort(vTimesTrack.begin(),vTimesTrack.end());
  223. float totaltime = 0;
  224. for(int ni=0; ni<nImages[0]; ni++)
  225. {
  226. totaltime+=vTimesTrack[ni];
  227. }
  228. cout << "-------" << endl << endl;
  229. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  230. cout << "mean tracking time: " << totaltime/proccIm << endl;
  231. return 0;
  232. }
  233. void LoadImagesTUMVI(const string &strPathLeft, const string &strPathRight, const string &strPathTimes,
  234. vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps)
  235. {
  236. ifstream fTimes;
  237. cout << strPathLeft << endl;
  238. cout << strPathRight << endl;
  239. cout << strPathTimes << endl;
  240. fTimes.open(strPathTimes.c_str());
  241. vTimeStamps.reserve(5000);
  242. vstrImageLeft.reserve(5000);
  243. vstrImageRight.reserve(5000);
  244. while(!fTimes.eof())
  245. {
  246. string s;
  247. getline(fTimes,s);
  248. if(!s.empty())
  249. {
  250. if (s[0] == '#')
  251. continue;
  252. int pos = s.find(' ');
  253. string item = s.substr(0, pos);
  254. vstrImageLeft.push_back(strPathLeft + "/" + item + ".png");
  255. vstrImageRight.push_back(strPathRight + "/" + item + ".png");
  256. double t = stod(item);
  257. vTimeStamps.push_back(t/1e9);
  258. }
  259. }
  260. }
  261. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro)
  262. {
  263. ifstream fImu;
  264. fImu.open(strImuPath.c_str());
  265. vTimeStamps.reserve(5000);
  266. vAcc.reserve(5000);
  267. vGyro.reserve(5000);
  268. while(!fImu.eof())
  269. {
  270. string s;
  271. getline(fImu,s);
  272. if (s[0] == '#')
  273. continue;
  274. if(!s.empty())
  275. {
  276. string item;
  277. size_t pos = 0;
  278. double data[7];
  279. int count = 0;
  280. while ((pos = s.find(',')) != string::npos) {
  281. item = s.substr(0, pos);
  282. data[count++] = stod(item);
  283. s.erase(0, pos + 1);
  284. }
  285. item = s.substr(0, pos);
  286. data[6] = stod(item);
  287. vTimeStamps.push_back(data[0]/1e9);
  288. vAcc.push_back(cv::Point3f(data[4],data[5],data[6]));
  289. vGyro.push_back(cv::Point3f(data[1],data[2],data[3]));
  290. }
  291. }
  292. }