mono_inertial_tum_vi.cc 9.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290
  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 &strImagePath, const string &strPathTimes,
  29. vector<string> &vstrImages, 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)/3;
  35. cout << "num_seq = " << num_seq << endl;
  36. bool bFileName= ((argc % 3) == 1);
  37. string file_name;
  38. if (bFileName)
  39. file_name = string(argv[argc-1]);
  40. cout << "file name: " << file_name << endl;
  41. if(argc < 6)
  42. {
  43. cerr << endl << "Usage: ./mono_inertial_tum_vi path_to_vocabulary path_to_settings path_to_image_folder_1 path_to_times_file_1 path_to_imu_data_1 (path_to_image_folder_2 path_to_times_file_2 path_to_imu_data_2 ... path_to_image_folder_N path_to_times_file_N path_to_imu_data_N) (trajectory_file_name)" << endl;
  44. return 1;
  45. }
  46. // Load all sequences:
  47. int seq;
  48. vector< vector<string> > vstrImageFilenames;
  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. vstrImageFilenames.resize(num_seq);
  56. vTimestampsCam.resize(num_seq);
  57. vAcc.resize(num_seq);
  58. vGyro.resize(num_seq);
  59. vTimestampsImu.resize(num_seq);
  60. nImages.resize(num_seq);
  61. nImu.resize(num_seq);
  62. int tot_images = 0;
  63. for (seq = 0; seq<num_seq; seq++)
  64. {
  65. cout << "Loading images for sequence " << seq << "...";
  66. LoadImages(string(argv[3*(seq+1)]), string(argv[3*(seq+1)+1]), vstrImageFilenames[seq], vTimestampsCam[seq]);
  67. cout << "LOADED!" << endl;
  68. cout << "Loading IMU for sequence " << seq << "...";
  69. LoadIMU(string(argv[3*(seq+1)+2]), vTimestampsImu[seq], vAcc[seq], vGyro[seq]);
  70. cout << "LOADED!" << endl;
  71. nImages[seq] = vstrImageFilenames[seq].size();
  72. tot_images += nImages[seq];
  73. nImu[seq] = vTimestampsImu[seq].size();
  74. if((nImages[seq]<=0)||(nImu[seq]<=0))
  75. {
  76. cerr << "ERROR: Failed to load images or IMU for sequence" << seq << endl;
  77. return 1;
  78. }
  79. // Find first imu to be considered, supposing imu measurements start first
  80. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][0])
  81. first_imu[seq]++;
  82. first_imu[seq]--; // first imu measurement to be considered
  83. }
  84. // Vector for tracking time statistics
  85. vector<float> vTimesTrack;
  86. vTimesTrack.resize(tot_images);
  87. cout << endl << "-------" << endl;
  88. cout.precision(17);
  89. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  90. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_MONOCULAR, true, 0, file_name);
  91. int proccIm = 0;
  92. for (seq = 0; seq<num_seq; seq++)
  93. {
  94. // Main loop
  95. cv::Mat im;
  96. vector<ORB_SLAM3::IMU::Point> vImuMeas;
  97. proccIm = 0;
  98. cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(3.0, cv::Size(8, 8));
  99. for(int ni=0; ni<nImages[seq]; ni++, proccIm++)
  100. {
  101. // Read image from file
  102. im = cv::imread(vstrImageFilenames[seq][ni],cv::IMREAD_GRAYSCALE);
  103. // clahe
  104. clahe->apply(im,im);
  105. double tframe = vTimestampsCam[seq][ni];
  106. if(im.empty())
  107. {
  108. cerr << endl << "Failed to load image at: "
  109. << vstrImageFilenames[seq][ni] << endl;
  110. return 1;
  111. }
  112. // Load imu measurements from previous frame
  113. vImuMeas.clear();
  114. if(ni>0)
  115. {
  116. while(vTimestampsImu[seq][first_imu[seq]]<=vTimestampsCam[seq][ni])
  117. {
  118. 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,
  119. vGyro[seq][first_imu[seq]].x,vGyro[seq][first_imu[seq]].y,vGyro[seq][first_imu[seq]].z,
  120. vTimestampsImu[seq][first_imu[seq]]));
  121. first_imu[seq]++;
  122. }
  123. }
  124. #ifdef COMPILEDWITHC11
  125. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  126. #else
  127. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  128. #endif
  129. // Pass the image to the SLAM system
  130. SLAM.TrackMonocular(im,tframe,vImuMeas);
  131. #ifdef COMPILEDWITHC11
  132. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  133. #else
  134. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  135. #endif
  136. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  137. ttrack_tot += ttrack;
  138. vTimesTrack[ni]=ttrack;
  139. // Wait to load the next frame
  140. double T=0;
  141. if(ni<nImages[seq]-1)
  142. T = vTimestampsCam[seq][ni+1]-tframe;
  143. else if(ni>0)
  144. T = tframe-vTimestampsCam[seq][ni-1];
  145. if(ttrack<T)
  146. usleep((T-ttrack)*1e6);
  147. }
  148. if(seq < num_seq - 1)
  149. {
  150. cout << "Changing the dataset" << endl;
  151. SLAM.ChangeDataset();
  152. }
  153. }
  154. // Stop all threads
  155. SLAM.Shutdown();
  156. // Save camera trajectory
  157. if (bFileName)
  158. {
  159. const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
  160. const string f_file = "f_" + string(argv[argc-1]) + ".txt";
  161. SLAM.SaveTrajectoryEuRoC(f_file);
  162. SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
  163. }
  164. else
  165. {
  166. SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
  167. SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
  168. }
  169. sort(vTimesTrack.begin(),vTimesTrack.end());
  170. float totaltime = 0;
  171. for(int ni=0; ni<nImages[0]; ni++)
  172. {
  173. totaltime+=vTimesTrack[ni];
  174. }
  175. cout << "-------" << endl << endl;
  176. cout << "median tracking time: " << vTimesTrack[nImages[0]/2] << endl;
  177. cout << "mean tracking time: " << totaltime/proccIm << endl;
  178. return 0;
  179. }
  180. void LoadImages(const string &strImagePath, const string &strPathTimes,
  181. vector<string> &vstrImages, vector<double> &vTimeStamps)
  182. {
  183. ifstream fTimes;
  184. cout << strImagePath << endl;
  185. cout << strPathTimes << endl;
  186. fTimes.open(strPathTimes.c_str());
  187. vTimeStamps.reserve(5000);
  188. vstrImages.reserve(5000);
  189. while(!fTimes.eof())
  190. {
  191. string s;
  192. getline(fTimes,s);
  193. if(!s.empty())
  194. {
  195. stringstream ss;
  196. ss << s;
  197. vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
  198. double t;
  199. ss >> t;
  200. vTimeStamps.push_back(t/1e9);
  201. }
  202. }
  203. }
  204. void LoadIMU(const string &strImuPath, vector<double> &vTimeStamps, vector<cv::Point3f> &vAcc, vector<cv::Point3f> &vGyro)
  205. {
  206. ifstream fImu;
  207. fImu.open(strImuPath.c_str());
  208. vTimeStamps.reserve(5000);
  209. vAcc.reserve(5000);
  210. vGyro.reserve(5000);
  211. while(!fImu.eof())
  212. {
  213. string s;
  214. getline(fImu,s);
  215. if (s[0] == '#')
  216. continue;
  217. if(!s.empty())
  218. {
  219. string item;
  220. size_t pos = 0;
  221. double data[7];
  222. int count = 0;
  223. while ((pos = s.find(',')) != string::npos) {
  224. item = s.substr(0, pos);
  225. data[count++] = stod(item);
  226. s.erase(0, pos + 1);
  227. }
  228. item = s.substr(0, pos);
  229. data[6] = stod(item);
  230. vTimeStamps.push_back(data[0]/1e9);
  231. vAcc.push_back(cv::Point3f(data[4],data[5],data[6]));
  232. vGyro.push_back(cv::Point3f(data[1],data[2],data[3]));
  233. }
  234. }
  235. }