mono_kitti.cc 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150
  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. // Main loop
  46. cv::Mat im;
  47. for(int ni=0; ni<nImages; ni++)
  48. {
  49. // Read image from file
  50. im = cv::imread(vstrImageFilenames[ni],cv::IMREAD_UNCHANGED);
  51. double tframe = vTimestamps[ni];
  52. if(im.empty())
  53. {
  54. cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl;
  55. return 1;
  56. }
  57. #ifdef COMPILEDWITHC11
  58. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  59. #else
  60. std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now();
  61. #endif
  62. // Pass the image to the SLAM system
  63. SLAM.TrackMonocular(im,tframe,vector<ORB_SLAM3::IMU::Point>(), vstrImageFilenames[ni]);
  64. #ifdef COMPILEDWITHC11
  65. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  66. #else
  67. std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now();
  68. #endif
  69. double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
  70. vTimesTrack[ni]=ttrack;
  71. // Wait to load the next frame
  72. double T=0;
  73. if(ni<nImages-1)
  74. T = vTimestamps[ni+1]-tframe;
  75. else if(ni>0)
  76. T = tframe-vTimestamps[ni-1];
  77. if(ttrack<T)
  78. usleep((T-ttrack)*1e6);
  79. }
  80. // Stop all threads
  81. SLAM.Shutdown();
  82. // Tracking time statistics
  83. sort(vTimesTrack.begin(),vTimesTrack.end());
  84. float totaltime = 0;
  85. for(int ni=0; ni<nImages; ni++)
  86. {
  87. totaltime+=vTimesTrack[ni];
  88. }
  89. cout << "-------" << endl << endl;
  90. cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
  91. cout << "mean tracking time: " << totaltime/nImages << endl;
  92. // Save camera trajectory
  93. SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
  94. return 0;
  95. }
  96. void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
  97. {
  98. ifstream fTimes;
  99. string strPathTimeFile = strPathToSequence + "/times.txt";
  100. fTimes.open(strPathTimeFile.c_str());
  101. while(!fTimes.eof())
  102. {
  103. string s;
  104. getline(fTimes,s);
  105. if(!s.empty())
  106. {
  107. stringstream ss;
  108. ss << s;
  109. double t;
  110. ss >> t;
  111. vTimestamps.push_back(t);
  112. }
  113. }
  114. string strPrefixLeft = strPathToSequence + "/image_0/";
  115. const int nTimes = vTimestamps.size();
  116. vstrImageFilenames.resize(nTimes);
  117. for(int i=0; i<nTimes; i++)
  118. {
  119. stringstream ss;
  120. ss << setfill('0') << setw(6) << i;
  121. vstrImageFilenames[i] = strPrefixLeft + ss.str() + ".png";
  122. }
  123. }