/** * 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 &strAssociationFilename, vector &vstrImageFilenamesRGB, vector &vstrImageFilenamesD, vector &vTimestamps); int main(int argc, char **argv) { if(argc != 5) { cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association" << endl; return 1; } // Retrieve paths to images vector vstrImageFilenamesRGB; vector vstrImageFilenamesD; vector vTimestamps; string strAssociationFilename = string(argv[4]); LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps); // Check consistency in the number of images and depthmaps int nImages = vstrImageFilenamesRGB.size(); if(vstrImageFilenamesRGB.empty()) { cerr << endl << "No images found in provided path." << endl; return 1; } else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size()) { cerr << endl << "Different number of images for rgb and depth." << endl; return 1; } // 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::RGBD,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; // Main loop cv::Mat imRGB, imD; for(int ni=0; ni >(t2 - t1).count(); vTimesTrack[ni]=ttrack; // Wait to load the next frame double T=0; if(ni0) T = tframe-vTimestamps[ni-1]; if(ttrack &vstrImageFilenamesRGB, vector &vstrImageFilenamesD, vector &vTimestamps) { ifstream fAssociation; fAssociation.open(strAssociationFilename.c_str()); while(!fAssociation.eof()) { string s; getline(fAssociation,s); if(!s.empty()) { stringstream ss; ss << s; double t; string sRGB, sD; ss >> t; vTimestamps.push_back(t); ss >> sRGB; vstrImageFilenamesRGB.push_back(sRGB); ss >> t; ss >> sD; vstrImageFilenamesD.push_back(sD); } } }