-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathmyvideo.cpp
54 lines (40 loc) · 1.53 KB
/
myvideo.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
// 该文件将打开给定的视频文件,并将图像传递给ORB-SLAM2进行定位
// 需要opencv
#include <opencv2/opencv.hpp>
// ORB-SLAM的系统接口
#include "System.h"
#include <string>
#include <chrono> // time stamp
#include <iostream>
using namespace std;
// 参数文件与字典文件
// 如果你系统上的路径不同,请修改它
//string parameterFile = "/home/tianqi/ORB_SLAM2/Examples/Myslam/myvideo.yaml";
//string vocFile = "/home/tianqi/ORB_SLAM2/Vocabulary/ORBvoc.txt";
string parameterFile = "./myvideo.yaml";
string vocFile = "../../Vocabulary/ORBvoc.txt";
// 视频文件
string videoFile = "./myvideo.mp4";
int main(int argc, char **argv) {
// 声明 ORB-SLAM2 系统
ORB_SLAM2::System SLAM(vocFile, parameterFile, ORB_SLAM2::System::MONOCULAR, true);
// 获取视频图像
cv::VideoCapture cap(videoFile); // 如果使用USB的外接相机就设置为1.
// 记录系统时间
auto start = chrono::system_clock::now();
while (1) {
cv::Mat frame;
cap >> frame; // 读取相机数据
if ( frame.data == nullptr )
break;
// 因为图片太大了,需要重新设置尺寸
cv::Mat frame_resized;
cv::resize(frame, frame_resized, cv::Size(640,360));
auto now = chrono::system_clock::now();
auto timestamp = chrono::duration_cast<chrono::milliseconds>(now - start);
SLAM.TrackMonocular(frame_resized, double(timestamp.count())/1000.0);
cv::waitKey(30);
}
SLAM.Shutdown();
return 0;
}