ORB-SLAM2只做定位的话,精度还是挺准确的,所以用单目摄像头录制视频,制作自己的数据集跑一下,看看定位精度,将过程加以记录。
文章目录
一、系统配置
系统 | 版本 |
---|---|
ubuntu | 18.04 |
OpenCV | 3.4.13 |
Eigen | 3.2.10 |
Pangolin | 0.5 |
二、制作数据集
1、脚本编写
test.cpp
#include <opencv2/opencv.hpp>
#include "System.h"
#include <string>
#include <chrono> // for time stamp
#include <iostream>
using namespace std;
// 参数文件与字典文件
// 如果你系统上的路径不同,请修改它
string parameterFile = "./test.yaml";
string vocFile = "./Vocabulary/ORBvoc.txt";
// 视频文件,若不同请修改
string videoFile = "./test.mp4";
int main(int argc, char **argv) {
// 声明 ORB-SLAM2 系统
ORB_SLAM2::System SLAM(vocFile, parameterFile, ORB_SLAM2::System::MONOCULAR, true);
// 获取视频图像
cv::VideoCapture cap(videoFile); // 参数0为usb相机
// 记录系统时间
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;
}
2、配置文件编写
test.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.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: 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
将两个文件复制到ORB_SLAM2根目录下
3、录制视频素材
(1)将手机横向拍摄
(2)开始拍摄时,首先手机左右缓慢水平移动,为了是ORB-SLAM2初始化正常,像螃蟹一样左右移动小步即可
(3)五秒左右,再慢慢往前走,不要走的太快,转弯时不要太快,防止跟踪丢失
(4)录制完成后,将其复制到ORB_SLAM2文件下,重命名为test.mp4
4、修改CMakeLists.txt
修改ORB_SLAM2里面的CMakeLists.txt
,添加如下代码:
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR})
add_executable(test test.cpp)
target_link_libraries(test ${PROJECT_NAME})
5、编译运行
cd ORB_SLAM2
mkdir build
cd build
cmake ..
make -j
cd ..
./test
三、总结
ORB-SLAM2将ORB-SLAM从单目相机扩展到双目和RGB-D相机,包含一种定位模式,只要环境中没有显著变化,它就能对已建图区域中轻量级长期定位非常有用。在这种模式下,局部建图和回环线程没有激活,使用跟踪线程连续地定位相机(如果需要,使用重定位)。在这种模式下,跟踪线程利用视觉里程计匹配和地图点匹配。视觉里程计匹配是当前帧中ORB和之前帧通过双目/深度信息创建的三维点之间的匹配。这些匹配使得定位对于未建图区域较为鲁棒,但是会累积漂移。地图点匹配保证了对现有地图的无漂移定位。