mono_kitti.cc 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  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<iomanip>
  23. #include<opencv2/core/core.hpp>
  24. #include"System.h"
  25. using namespace std;
  26. void LoadImages(const string &strSequence, vector<string> &vstrImageFilenames,
  27. vector<double> &vTimestamps);
  28. int main(int argc, char **argv)
  29. {
  30. if(argc != 4)
  31. {
  32. cerr << endl << "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
  33. return 1;
  34. }
  35. // Retrieve paths to images
  36. vector<string> vstrImageFilenames;
  37. vector<double> vTimestamps;
  38. LoadImages(string(argv[3]), vstrImageFilenames, vTimestamps);
  39. int nImages = vstrImageFilenames.size();
  40. // Create SLAM system. It initializes all system threads and gets ready to process frames.
  41. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true);
  42. // Vector for tracking time statistics
  43. vector<float> vTimesTrack;
  44. vTimesTrack.resize(nImages);
  45. cout << endl << "-------" << endl;
  46. cout << "Start processing sequence ..." << endl;
  47. cout << "Images in the sequence: " << nImages << endl << endl;
  48. // Main loop
  49. cv::Mat im;
  50. for(int ni=0; ni<nImages; ni++)
  51. {
  52. // Read image from file
  53. im = cv::imread(vstrImageFilenames[ni],cv::IMREAD_UNCHANGED);
  54. double tframe = vTimestamps[ni];
  55. if(im.empty())
  56. {
  57. cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl;
  58. return 1;
  59. }
  60. #ifdef COMPILEDWITHC11
  61. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  62. #else
  63. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  64. #endif
  65. // Pass the image to the SLAM system
  66. SLAM.TrackMonocular(im,tframe,vector<ORB_SLAM3::IMU::Point>(), vstrImageFilenames[ni]);
  67. #ifdef COMPILEDWITHC11
  68. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  69. #else
  70. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  71. #endif
  72. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  73. vTimesTrack[ni]=ttrack;
  74. // Wait to load the next frame
  75. double T=0;
  76. if(ni<nImages-1)
  77. T = vTimestamps[ni+1]-tframe;
  78. else if(ni>0)
  79. T = tframe-vTimestamps[ni-1];
  80. if(ttrack<T)
  81. usleep((T-ttrack)*1e6);
  82. }
  83. // Stop all threads
  84. SLAM.Shutdown();
  85. // Tracking time statistics
  86. sort(vTimesTrack.begin(),vTimesTrack.end());
  87. float totaltime = 0;
  88. for(int ni=0; ni<nImages; ni++)
  89. {
  90. totaltime+=vTimesTrack[ni];
  91. }
  92. cout << "-------" << endl << endl;
  93. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  94. cout << "mean tracking time: " << totaltime/nImages << endl;
  95. // Save camera trajectory
  96. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  97. return 0;
  98. }
  99. void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
  100. {
  101. ifstream fTimes;
  102. string strPathTimeFile = strPathToSequence + "/times.txt";
  103. fTimes.open(strPathTimeFile.c_str());
  104. while(!fTimes.eof())
  105. {
  106. string s;
  107. getline(fTimes,s);
  108. if(!s.empty())
  109. {
  110. stringstream ss;
  111. ss << s;
  112. double t;
  113. ss >> t;
  114. vTimestamps.push_back(t);
  115. }
  116. }
  117. string strPrefixLeft = strPathToSequence + "/image_0/";
  118. const int nTimes = vTimestamps.size();
  119. vstrImageFilenames.resize(nTimes);
  120. for(int i=0; i<nTimes; i++)
  121. {
  122. stringstream ss;
  123. ss << setfill('0') << setw(6) << i;
  124. vstrImageFilenames[i] = strPrefixLeft + ss.str() + ".png";
  125. }
  126. }