stereo_kitti.cc 5.0 KB

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