mono_inertial_euroc.cc 8.7 KB

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