2023-11-28 19:20:25 +08:00
|
|
|
/**
|
|
|
|
* 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 <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include<iostream>
|
|
|
|
#include<algorithm>
|
|
|
|
#include<fstream>
|
|
|
|
#include<chrono>
|
|
|
|
|
|
|
|
#include<opencv2/core/core.hpp>
|
|
|
|
|
|
|
|
#include<System.h>
|
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
|
|
|
|
void LoadImages(const string &strImagePath, const string &strPathTimes,
|
|
|
|
vector<string> &vstrImages, vector<double> &vTimeStamps);
|
|
|
|
|
|
|
|
int main(int argc, char **argv)
|
|
|
|
{
|
|
|
|
if(argc < 3)
|
|
|
|
{
|
|
|
|
cerr << endl << "Usage: ./mono_euroc path_to_vocabulary path_to_settings path_to_sequence_folder_1 path_to_times_file_1 (path_to_image_folder_2 path_to_times_file_2 ... path_to_image_folder_N path_to_times_file_N) (trajectory_file_name)" << endl;
|
|
|
|
return 1;
|
|
|
|
}
|
|
|
|
|
|
|
|
const int num_seq = 1;
|
|
|
|
cout << "num_seq = " << num_seq << endl;
|
|
|
|
|
|
|
|
// Load all sequences:
|
|
|
|
int seq;
|
|
|
|
vector< vector<string> > vstrImageFilenames;
|
|
|
|
vector< vector<double> > vTimestampsCam;
|
|
|
|
vector<int> nImages;
|
|
|
|
|
|
|
|
vstrImageFilenames.resize(num_seq);
|
|
|
|
vTimestampsCam.resize(num_seq);
|
|
|
|
nImages.resize(num_seq);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Vector for tracking time statistics
|
|
|
|
vector<float> vTimesTrack;
|
|
|
|
// vTimesTrack.resize(tot_images);
|
|
|
|
|
|
|
|
cout << endl << "-------" << endl;
|
|
|
|
cout.precision(19);
|
|
|
|
|
|
|
|
|
|
|
|
// int fps = 30;
|
|
|
|
// float dT = 1.f/fps;
|
|
|
|
// 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();
|
|
|
|
|
|
|
|
double t_resize = 0.f;
|
|
|
|
double t_track = 0.f;
|
|
|
|
|
|
|
|
for (seq = 0; seq<num_seq; seq++)
|
|
|
|
{
|
|
|
|
|
|
|
|
// Main loop
|
|
|
|
cv::VideoCapture cap = cv::VideoCapture(0);
|
|
|
|
cap.set(cv::CAP_PROP_FRAME_WIDTH, 640);
|
|
|
|
cap.set(cv::CAP_PROP_FRAME_HEIGHT, 480);
|
|
|
|
|
|
|
|
if (!cap.isOpened()) {
|
|
|
|
std::cerr << "Error: Could not open camera." << std::endl;
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
|
|
|
|
int fps = cap.get(cv::CAP_PROP_FPS);
|
|
|
|
int delay = 1000/fps;
|
|
|
|
|
|
|
|
while(1)
|
|
|
|
{
|
|
|
|
cv::Mat im;
|
|
|
|
cap >> im;
|
|
|
|
if(im.empty())
|
|
|
|
{
|
|
|
|
cerr << endl << "Error: Couldn't capture a frame"
|
|
|
|
<< endl;
|
|
|
|
return 1;
|
|
|
|
}
|
|
|
|
// Show the origin image.
|
2023-11-29 00:00:34 +08:00
|
|
|
// cv::imshow("img",im);
|
2023-11-28 19:20:25 +08:00
|
|
|
|
|
|
|
auto currentTime = std::chrono::high_resolution_clock::now();
|
|
|
|
auto timestamp = std::chrono::duration_cast<std::chrono::nanoseconds>(currentTime.time_since_epoch());
|
|
|
|
double tframe = static_cast<double>(timestamp.count());
|
|
|
|
|
|
|
|
if(imageScale != 1.f)
|
|
|
|
{
|
|
|
|
#ifdef REGISTER_TIMES
|
|
|
|
#ifdef COMPILEDWITHC11
|
|
|
|
std::chrono::steady_clock::time_point t_Start_Resize = std::chrono::steady_clock::now();
|
|
|
|
#else
|
|
|
|
std::chrono::monotonic_clock::time_point t_Start_Resize = std::chrono::monotonic_clock::now();
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
int width = im.cols * imageScale;
|
|
|
|
int height = im.rows * imageScale;
|
|
|
|
cv::resize(im, im, cv::Size(width, height));
|
|
|
|
#ifdef REGISTER_TIMES
|
|
|
|
#ifdef COMPILEDWITHC11
|
|
|
|
std::chrono::steady_clock::time_point t_End_Resize = std::chrono::steady_clock::now();
|
|
|
|
#else
|
|
|
|
std::chrono::monotonic_clock::time_point t_End_Resize = std::chrono::monotonic_clock::now();
|
|
|
|
#endif
|
|
|
|
t_resize = std::chrono::duration_cast<std::chrono::duration<double,std::milli> >(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
|
|
|
|
// cout << "tframe = " << tframe << endl;
|
|
|
|
SLAM.TrackMonocular(im, tframe); // TODO change to monocular_inertial
|
|
|
|
|
|
|
|
#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<std::chrono::duration<double,std::milli> >(t2 - t1).count();
|
|
|
|
SLAM.InsertTrackTime(t_track);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
|
|
|
|
// std::cout<<"ttrack:"<<ttrack<<std::endl;
|
|
|
|
|
|
|
|
// vTimesTrack[ni]=ttrack;
|
|
|
|
|
|
|
|
// Wait to load the next frame
|
|
|
|
double T = 0;
|
|
|
|
// if(ni<nImages[seq]-1)
|
|
|
|
// T = vTimestampsCam[seq][ni+1]-tframe;
|
|
|
|
// else if(ni>0)
|
|
|
|
// T = tframe-vTimestampsCam[seq][ni-1];
|
|
|
|
|
|
|
|
// std::cout << "T: " << T << std::endl;
|
|
|
|
// std::cout << "ttrack: " << ttrack << std::endl;
|
|
|
|
|
|
|
|
// if(ttrack<T) {
|
|
|
|
// //std::cout << "usleep: " << (dT-ttrack) << std::endl;
|
|
|
|
// usleep((T-ttrack)*1e6); // 1e6
|
|
|
|
// }
|
|
|
|
}
|
|
|
|
|
|
|
|
if(seq < num_seq - 1)
|
|
|
|
{
|
|
|
|
string kf_file_submap = "./SubMaps/kf_SubMap_" + std::to_string(seq) + ".txt";
|
|
|
|
string f_file_submap = "./SubMaps/f_SubMap_" + std::to_string(seq) + ".txt";
|
|
|
|
SLAM.SaveTrajectoryEuRoC(f_file_submap);
|
|
|
|
SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file_submap);
|
|
|
|
|
|
|
|
cout << "Changing the dataset" << endl;
|
|
|
|
|
|
|
|
SLAM.ChangeDataset();
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
// Stop all threads
|
|
|
|
SLAM.Shutdown();
|
|
|
|
|
|
|
|
// Save camera trajectory
|
|
|
|
if (1)
|
|
|
|
{
|
|
|
|
const string kf_file = "kf_" + string(argv[argc-1]) + ".txt";
|
|
|
|
const string f_file = "f_" + string(argv[argc-1]) + ".txt";
|
|
|
|
SLAM.SaveTrajectoryEuRoC(f_file);
|
|
|
|
SLAM.SaveKeyFrameTrajectoryEuRoC(kf_file);
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
|
|
|
SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
|
|
|
|
SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");
|
|
|
|
}
|
|
|
|
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|