/** * This file is part of ORB-SLAM3 * * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. * * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public * License as published by the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License along with ORB-SLAM3. * If not, see . */ #include #include #include #include #include #include using namespace std; void LoadImages(const string &strFile, vector &vstrImageFilenames, vector &vTimestamps); int main(int argc, char **argv) { if(argc != 4) { cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence" << endl; return 1; } // Retrieve paths to images vector vstrImageFilenames; vector vTimestamps; string strFile = string(argv[3])+"/rgb.txt"; LoadImages(strFile, vstrImageFilenames, vTimestamps); int nImages = vstrImageFilenames.size(); // Create SLAM system. It initializes all system threads and gets ready to process frames. ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR,true); float imageScale = SLAM.GetImageScale(); // Vector for tracking time statistics vector vTimesTrack; vTimesTrack.resize(nImages); cout << endl << "-------" << endl; cout << "Start processing sequence ..." << endl; cout << "Images in the sequence: " << nImages << endl << endl; double t_resize = 0.f; double t_track = 0.f; // Main loop cv::Mat im; for(int ni=0; ni >(t_End_Resize - t_Start_Resize).count(); SLAM.InsertResizeTime(t_resize); #endif } #ifdef COMPILEDWITHC11 std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); #else std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); #endif // Pass the image to the SLAM system SLAM.TrackMonocular(im,tframe); #ifdef COMPILEDWITHC11 std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); #else std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); #endif #ifdef REGISTER_TIMES t_track = t_resize + std::chrono::duration_cast >(t2 - t1).count(); SLAM.InsertTrackTime(t_track); #endif double ttrack= std::chrono::duration_cast >(t2 - t1).count(); vTimesTrack[ni]=ttrack; // Wait to load the next frame double T=0; if(ni0) T = tframe-vTimestamps[ni-1]; if(ttrack &vstrImageFilenames, vector &vTimestamps) { ifstream f; f.open(strFile.c_str()); // skip first three lines string s0; getline(f,s0); getline(f,s0); getline(f,s0); while(!f.eof()) { string s; getline(f,s); if(!s.empty()) { stringstream ss; ss << s; double t; string sRGB; ss >> t; vTimestamps.push_back(t); ss >> sRGB; vstrImageFilenames.push_back(sRGB); } } }