首先保证你已经安装好ORB_SLAM2并且已经可以跑通TUM数据集了。如果不知道怎么配置ORB_SLAM2环境可以参考我其他的文章。
起初你的ORB_SLAM2文件夹应该基本长这样
用手机拍摄一段视频,我拍的是实验室工位大约2分钟视频。在拍摄开始,要对准一个位置慢慢左右移动镜头,因为,单目一开始要初始化,然后再拍摄其他地方,镜头旋转速度不要太快。拐弯处也不要太快。将拍好的视频上传到电脑,命名为myvideo.mp4,放在ORB-SLAM2文件夹中。
如果你的电脑打不开视频显示需要HEVC解码器,附上一个扩展(安装64位即可)
https://niamia.lanzouw.com/icUmB0yizpkd
第一步:新建一个 myvideo.yaml
打开终端输入指令
gedit myvideo.yaml
在跳出来的文件中输入以下代码(设置手机参数)
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 500.0
Camera.fy: 500.0
Camera.cx: 320.0
Camera.cy: 240.0
Camera.k1: 0
Camera.k2: 0
Camera.p1: 0
Camera.p2: 0
Camera.k3: 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: 0
#--------------------------------------------------------------------------------------------
# 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: 10
ORBextractor.minThFAST: 5
#--------------------------------------------------------------------------------------------
# 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
第二步:新建 myvideo.cpp
打开终端输入指令
gedit myvideo.cpp
在跳出来的文件输入以下代码
#include <opencv2/opencv.hpp>
#include "System.h"
#include <string>
#include <chrono> // for time stamp
#include <iostream>
using namespace std;
// 参数文件与字典文件
// 如果你系统上的路径不同,请修改它
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); // change to 0 if you want to use USB camera.
// 记录系统时间
auto start = chrono::system_clock::now();
while (1) {
cv::Mat frame;
cap >> frame; // 读取相机数据
if ( frame.data == nullptr )
continue;
// rescale because image is too large
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);
}
return 0;
}
myvideo.yaml、ORBvoc.txt、myvideo.mp4的具体位置可自行修改。
第三步:修改CMakeLists.txt
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR})
add_executable(myvideo myvideo.cpp)
target_link_libraries(myvideo ${PROJECT_NAME})
最后打开终端输入以下指令就可以运行了。
cd ORB_SLAM2
mkdir build
cd build
cmake ..
make -j
cd ..
./myvideo
我的运行结果,我是没太移动所以变化不太明显