v1
This commit is contained in:
57
Examples/Monocular/EuRoC.yaml
Normal file
57
Examples/Monocular/EuRoC.yaml
Normal file
@@ -0,0 +1,57 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 458.654
|
||||
Camera.fy: 457.296
|
||||
Camera.cx: 367.215
|
||||
Camera.cy: 248.375
|
||||
|
||||
Camera.k1: -0.28340811
|
||||
Camera.k2: 0.07395907
|
||||
Camera.p1: 0.00019359
|
||||
Camera.p2: 1.76187114e-05
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 20.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 1000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#---------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.05
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 0.9
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.08
|
||||
Viewer.CameraLineWidth: 3
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -0.7
|
||||
Viewer.ViewpointZ: -1.8
|
||||
Viewer.ViewpointF: 500
|
||||
|
||||
3682
Examples/Monocular/EuRoC_TimeStamps/MH01.txt
Normal file
3682
Examples/Monocular/EuRoC_TimeStamps/MH01.txt
Normal file
File diff suppressed because it is too large
Load Diff
3040
Examples/Monocular/EuRoC_TimeStamps/MH02.txt
Normal file
3040
Examples/Monocular/EuRoC_TimeStamps/MH02.txt
Normal file
File diff suppressed because it is too large
Load Diff
2700
Examples/Monocular/EuRoC_TimeStamps/MH03.txt
Normal file
2700
Examples/Monocular/EuRoC_TimeStamps/MH03.txt
Normal file
File diff suppressed because it is too large
Load Diff
2033
Examples/Monocular/EuRoC_TimeStamps/MH04.txt
Normal file
2033
Examples/Monocular/EuRoC_TimeStamps/MH04.txt
Normal file
File diff suppressed because it is too large
Load Diff
2273
Examples/Monocular/EuRoC_TimeStamps/MH05.txt
Normal file
2273
Examples/Monocular/EuRoC_TimeStamps/MH05.txt
Normal file
File diff suppressed because it is too large
Load Diff
2912
Examples/Monocular/EuRoC_TimeStamps/V101.txt
Normal file
2912
Examples/Monocular/EuRoC_TimeStamps/V101.txt
Normal file
File diff suppressed because it is too large
Load Diff
1710
Examples/Monocular/EuRoC_TimeStamps/V102.txt
Normal file
1710
Examples/Monocular/EuRoC_TimeStamps/V102.txt
Normal file
File diff suppressed because it is too large
Load Diff
2149
Examples/Monocular/EuRoC_TimeStamps/V103.txt
Normal file
2149
Examples/Monocular/EuRoC_TimeStamps/V103.txt
Normal file
File diff suppressed because it is too large
Load Diff
2280
Examples/Monocular/EuRoC_TimeStamps/V201.txt
Normal file
2280
Examples/Monocular/EuRoC_TimeStamps/V201.txt
Normal file
File diff suppressed because it is too large
Load Diff
2348
Examples/Monocular/EuRoC_TimeStamps/V202.txt
Normal file
2348
Examples/Monocular/EuRoC_TimeStamps/V202.txt
Normal file
File diff suppressed because it is too large
Load Diff
1922
Examples/Monocular/EuRoC_TimeStamps/V203.txt
Normal file
1922
Examples/Monocular/EuRoC_TimeStamps/V203.txt
Normal file
File diff suppressed because it is too large
Load Diff
57
Examples/Monocular/KITTI00-02.yaml
Normal file
57
Examples/Monocular/KITTI00-02.yaml
Normal file
@@ -0,0 +1,57 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 718.856
|
||||
Camera.fy: 718.856
|
||||
Camera.cx: 607.1928
|
||||
Camera.cy: 185.2157
|
||||
|
||||
Camera.k1: 0.0
|
||||
Camera.k2: 0.0
|
||||
Camera.p1: 0.0
|
||||
Camera.p2: 0.0
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 10.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 2000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.1
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 1
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.15
|
||||
Viewer.CameraLineWidth: 2
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -10
|
||||
Viewer.ViewpointZ: -0.1
|
||||
Viewer.ViewpointF: 2000
|
||||
|
||||
57
Examples/Monocular/KITTI03.yaml
Normal file
57
Examples/Monocular/KITTI03.yaml
Normal file
@@ -0,0 +1,57 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 721.5377
|
||||
Camera.fy: 721.5377
|
||||
Camera.cx: 609.5593
|
||||
Camera.cy: 172.854
|
||||
|
||||
Camera.k1: 0.0
|
||||
Camera.k2: 0.0
|
||||
Camera.p1: 0.0
|
||||
Camera.p2: 0.0
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 10.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 2000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.1
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 1
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.15
|
||||
Viewer.CameraLineWidth: 2
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -10
|
||||
Viewer.ViewpointZ: -0.1
|
||||
Viewer.ViewpointF: 2000
|
||||
|
||||
57
Examples/Monocular/KITTI04-12.yaml
Normal file
57
Examples/Monocular/KITTI04-12.yaml
Normal file
@@ -0,0 +1,57 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 707.0912
|
||||
Camera.fy: 707.0912
|
||||
Camera.cx: 601.8873
|
||||
Camera.cy: 183.1104
|
||||
|
||||
Camera.k1: 0.0
|
||||
Camera.k2: 0.0
|
||||
Camera.p1: 0.0
|
||||
Camera.p2: 0.0
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 10.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 2000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.1
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 1
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.15
|
||||
Viewer.CameraLineWidth: 2
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -10
|
||||
Viewer.ViewpointZ: -0.1
|
||||
Viewer.ViewpointF: 2000
|
||||
|
||||
58
Examples/Monocular/TUM1.yaml
Normal file
58
Examples/Monocular/TUM1.yaml
Normal file
@@ -0,0 +1,58 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 517.306408
|
||||
Camera.fy: 516.469215
|
||||
Camera.cx: 318.643040
|
||||
Camera.cy: 255.313989
|
||||
|
||||
Camera.k1: 0.262383
|
||||
Camera.k2: -0.953104
|
||||
Camera.p1: -0.005358
|
||||
Camera.p2: 0.002628
|
||||
Camera.k3: 1.163314
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 30.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 1000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.05
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 0.9
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.08
|
||||
Viewer.CameraLineWidth: 3
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -0.7
|
||||
Viewer.ViewpointZ: -1.8
|
||||
Viewer.ViewpointF: 500
|
||||
|
||||
58
Examples/Monocular/TUM2.yaml
Normal file
58
Examples/Monocular/TUM2.yaml
Normal file
@@ -0,0 +1,58 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 520.908620
|
||||
Camera.fy: 521.007327
|
||||
Camera.cx: 325.141442
|
||||
Camera.cy: 249.701764
|
||||
|
||||
Camera.k1: 0.231222
|
||||
Camera.k2: -0.784899
|
||||
Camera.p1: -0.003257
|
||||
Camera.p2: -0.000105
|
||||
Camera.k3: 0.917205
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 30.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 1000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.05
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 0.9
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.08
|
||||
Viewer.CameraLineWidth: 3
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -0.7
|
||||
Viewer.ViewpointZ: -1.8
|
||||
Viewer.ViewpointF: 500
|
||||
|
||||
57
Examples/Monocular/TUM3.yaml
Normal file
57
Examples/Monocular/TUM3.yaml
Normal file
@@ -0,0 +1,57 @@
|
||||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 535.4
|
||||
Camera.fy: 539.2
|
||||
Camera.cx: 320.1
|
||||
Camera.cy: 247.6
|
||||
|
||||
Camera.k1: 0.0
|
||||
Camera.k2: 0.0
|
||||
Camera.p1: 0.0
|
||||
Camera.p2: 0.0
|
||||
|
||||
# Camera frames per second
|
||||
Camera.fps: 30.0
|
||||
|
||||
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
|
||||
Camera.RGB: 1
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# ORB Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
|
||||
# ORB Extractor: Number of features per image
|
||||
ORBextractor.nFeatures: 1000
|
||||
|
||||
# ORB Extractor: Scale factor between levels in the scale pyramid
|
||||
ORBextractor.scaleFactor: 1.2
|
||||
|
||||
# ORB Extractor: Number of levels in the scale pyramid
|
||||
ORBextractor.nLevels: 8
|
||||
|
||||
# ORB Extractor: Fast threshold
|
||||
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
|
||||
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
|
||||
# You can lower these values if your images have low contrast
|
||||
ORBextractor.iniThFAST: 20
|
||||
ORBextractor.minThFAST: 7
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Viewer Parameters
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Viewer.KeyFrameSize: 0.05
|
||||
Viewer.KeyFrameLineWidth: 1
|
||||
Viewer.GraphLineWidth: 0.9
|
||||
Viewer.PointSize:2
|
||||
Viewer.CameraSize: 0.08
|
||||
Viewer.CameraLineWidth: 3
|
||||
Viewer.ViewpointX: 0
|
||||
Viewer.ViewpointY: -0.7
|
||||
Viewer.ViewpointZ: -1.8
|
||||
Viewer.ViewpointF: 500
|
||||
|
||||
155
Examples/Monocular/mono_euroc.cc
Normal file
155
Examples/Monocular/mono_euroc.cc
Normal file
@@ -0,0 +1,155 @@
|
||||
/**
|
||||
* This file is part of ORB-SLAM2.
|
||||
*
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
||||
* For more information see <https://github.com/raulmur/ORB_SLAM2>
|
||||
*
|
||||
* ORB-SLAM2 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-SLAM2 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-SLAM2. 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 != 5)
|
||||
{
|
||||
cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_image_folder path_to_times_file" << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Retrieve paths to images
|
||||
vector<string> vstrImageFilenames;
|
||||
vector<double> vTimestamps;
|
||||
LoadImages(string(argv[3]), string(argv[4]), vstrImageFilenames, vTimestamps);
|
||||
|
||||
int nImages = vstrImageFilenames.size();
|
||||
|
||||
if(nImages<=0)
|
||||
{
|
||||
cerr << "ERROR: Failed to load images" << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Create SLAM system. It initializes all system threads and gets ready to process frames.
|
||||
ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
|
||||
|
||||
// Vector for tracking time statistics
|
||||
vector<float> vTimesTrack;
|
||||
vTimesTrack.resize(nImages);
|
||||
|
||||
cout << endl << "-------" << endl;
|
||||
cout << "Start processing sequence ..." << endl;
|
||||
cout << "Images in the sequence: " << nImages << endl << endl;
|
||||
|
||||
// Main loop
|
||||
cv::Mat im;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
// Read image from file
|
||||
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
|
||||
double tframe = vTimestamps[ni];
|
||||
|
||||
if(im.empty())
|
||||
{
|
||||
cerr << endl << "Failed to load image at: "
|
||||
<< vstrImageFilenames[ni] << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
#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
|
||||
|
||||
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
|
||||
|
||||
vTimesTrack[ni]=ttrack;
|
||||
|
||||
// Wait to load the next frame
|
||||
double T=0;
|
||||
if(ni<nImages-1)
|
||||
T = vTimestamps[ni+1]-tframe;
|
||||
else if(ni>0)
|
||||
T = tframe-vTimestamps[ni-1];
|
||||
|
||||
if(ttrack<T)
|
||||
usleep((T-ttrack)*1e6);
|
||||
}
|
||||
|
||||
// Stop all threads
|
||||
SLAM.Shutdown();
|
||||
|
||||
// Tracking time statistics
|
||||
sort(vTimesTrack.begin(),vTimesTrack.end());
|
||||
float totaltime = 0;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
totaltime+=vTimesTrack[ni];
|
||||
}
|
||||
cout << "-------" << endl << endl;
|
||||
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
|
||||
cout << "mean tracking time: " << totaltime/nImages << endl;
|
||||
|
||||
// Save camera trajectory
|
||||
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LoadImages(const string &strImagePath, const string &strPathTimes,
|
||||
vector<string> &vstrImages, vector<double> &vTimeStamps)
|
||||
{
|
||||
ifstream fTimes;
|
||||
fTimes.open(strPathTimes.c_str());
|
||||
vTimeStamps.reserve(5000);
|
||||
vstrImages.reserve(5000);
|
||||
while(!fTimes.eof())
|
||||
{
|
||||
string s;
|
||||
getline(fTimes,s);
|
||||
if(!s.empty())
|
||||
{
|
||||
stringstream ss;
|
||||
ss << s;
|
||||
vstrImages.push_back(strImagePath + "/" + ss.str() + ".png");
|
||||
double t;
|
||||
ss >> t;
|
||||
vTimeStamps.push_back(t/1e9);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
159
Examples/Monocular/mono_kitti.cc
Normal file
159
Examples/Monocular/mono_kitti.cc
Normal file
@@ -0,0 +1,159 @@
|
||||
/**
|
||||
* This file is part of ORB-SLAM2.
|
||||
*
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
||||
* For more information see <https://github.com/raulmur/ORB_SLAM2>
|
||||
*
|
||||
* ORB-SLAM2 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-SLAM2 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-SLAM2. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include<iostream>
|
||||
#include<algorithm>
|
||||
#include<fstream>
|
||||
#include<chrono>
|
||||
#include<iomanip>
|
||||
|
||||
#include<opencv2/core/core.hpp>
|
||||
|
||||
#include"System.h"
|
||||
|
||||
#define COMPILEDWITHC11
|
||||
|
||||
using namespace std;
|
||||
|
||||
void LoadImages(const string &strSequence, vector<string> &vstrImageFilenames,
|
||||
vector<double> &vTimestamps);
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
if(argc != 4)
|
||||
{
|
||||
cerr << endl << "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Retrieve paths to images
|
||||
vector<string> vstrImageFilenames;
|
||||
vector<double> vTimestamps;
|
||||
LoadImages(string(argv[3]), vstrImageFilenames, vTimestamps);
|
||||
|
||||
int nImages = vstrImageFilenames.size();
|
||||
|
||||
// Create SLAM system. It initializes all system threads and gets ready to process frames.
|
||||
ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
|
||||
|
||||
// Vector for tracking time statistics
|
||||
vector<float> vTimesTrack;
|
||||
vTimesTrack.resize(nImages);
|
||||
|
||||
cout << endl << "-------" << endl;
|
||||
cout << "Start processing sequence ..." << endl;
|
||||
cout << "Images in the sequence: " << nImages << endl << endl;
|
||||
|
||||
// Main loop
|
||||
cv::Mat im;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
// Read image from file
|
||||
im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
|
||||
double tframe = vTimestamps[ni];
|
||||
|
||||
if(im.empty())
|
||||
{
|
||||
cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
#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
|
||||
|
||||
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
|
||||
|
||||
vTimesTrack[ni]=ttrack;
|
||||
|
||||
// Wait to load the next frame
|
||||
double T=0;
|
||||
if(ni<nImages-1)
|
||||
T = vTimestamps[ni+1]-tframe;
|
||||
else if(ni>0)
|
||||
T = tframe-vTimestamps[ni-1];
|
||||
|
||||
if(ttrack<T)
|
||||
usleep((T-ttrack)*1e6);
|
||||
}
|
||||
|
||||
// Stop all threads
|
||||
SLAM.Shutdown();
|
||||
|
||||
// Tracking time statistics
|
||||
sort(vTimesTrack.begin(),vTimesTrack.end());
|
||||
float totaltime = 0;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
totaltime+=vTimesTrack[ni];
|
||||
}
|
||||
cout << "-------" << endl << endl;
|
||||
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
|
||||
cout << "mean tracking time: " << totaltime/nImages << endl;
|
||||
|
||||
// Save camera trajectory
|
||||
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilenames, vector<double> &vTimestamps)
|
||||
{
|
||||
ifstream fTimes;
|
||||
string strPathTimeFile = strPathToSequence + "/times.txt";
|
||||
fTimes.open(strPathTimeFile.c_str());
|
||||
while(!fTimes.eof())
|
||||
{
|
||||
string s;
|
||||
getline(fTimes,s);
|
||||
if(!s.empty())
|
||||
{
|
||||
stringstream ss;
|
||||
ss << s;
|
||||
double t;
|
||||
ss >> t;
|
||||
vTimestamps.push_back(t);
|
||||
}
|
||||
}
|
||||
|
||||
string strPrefixLeft = strPathToSequence + "/image_0/";
|
||||
|
||||
const int nTimes = vTimestamps.size();
|
||||
vstrImageFilenames.resize(nTimes);
|
||||
|
||||
for(int i=0; i<nTimes; i++)
|
||||
{
|
||||
stringstream ss;
|
||||
ss << setfill('0') << setw(6) << i;
|
||||
vstrImageFilenames[i] = strPrefixLeft + ss.str() + ".png";
|
||||
}
|
||||
}
|
||||
155
Examples/Monocular/mono_tum.cc
Normal file
155
Examples/Monocular/mono_tum.cc
Normal file
@@ -0,0 +1,155 @@
|
||||
/**
|
||||
* This file is part of ORB-SLAM2.
|
||||
*
|
||||
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
|
||||
* For more information see <https://github.com/raulmur/ORB_SLAM2>
|
||||
*
|
||||
* ORB-SLAM2 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-SLAM2 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-SLAM2. 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 &strFile, vector<string> &vstrImageFilenames,
|
||||
vector<double> &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<string> vstrImageFilenames;
|
||||
vector<double> 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_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true);
|
||||
|
||||
// Vector for tracking time statistics
|
||||
vector<float> vTimesTrack;
|
||||
vTimesTrack.resize(nImages);
|
||||
|
||||
cout << endl << "-------" << endl;
|
||||
cout << "Start processing sequence ..." << endl;
|
||||
cout << "Images in the sequence: " << nImages << endl << endl;
|
||||
|
||||
// Main loop
|
||||
cv::Mat im;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
// Read image from file
|
||||
im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED);
|
||||
double tframe = vTimestamps[ni];
|
||||
|
||||
if(im.empty())
|
||||
{
|
||||
cerr << endl << "Failed to load image at: "
|
||||
<< string(argv[3]) << "/" << vstrImageFilenames[ni] << endl;
|
||||
return 1;
|
||||
}
|
||||
|
||||
#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
|
||||
|
||||
double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count();
|
||||
|
||||
vTimesTrack[ni]=ttrack;
|
||||
|
||||
// Wait to load the next frame
|
||||
double T=0;
|
||||
if(ni<nImages-1)
|
||||
T = vTimestamps[ni+1]-tframe;
|
||||
else if(ni>0)
|
||||
T = tframe-vTimestamps[ni-1];
|
||||
|
||||
if(ttrack<T)
|
||||
usleep((T-ttrack)*1e6);
|
||||
}
|
||||
|
||||
// Stop all threads
|
||||
SLAM.Shutdown();
|
||||
|
||||
// Tracking time statistics
|
||||
sort(vTimesTrack.begin(),vTimesTrack.end());
|
||||
float totaltime = 0;
|
||||
for(int ni=0; ni<nImages; ni++)
|
||||
{
|
||||
totaltime+=vTimesTrack[ni];
|
||||
}
|
||||
cout << "-------" << endl << endl;
|
||||
cout << "median tracking time: " << vTimesTrack[nImages/2] << endl;
|
||||
cout << "mean tracking time: " << totaltime/nImages << endl;
|
||||
|
||||
// Save camera trajectory
|
||||
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &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);
|
||||
}
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user