未完
单目相机的特征点提取
1. 提取ORB特征点
ORB特征点是一种局部的特征点,先计算FAST角点再为之添加BRIEF描述子。为了保证特征点具有一定的尺度不变性,ORB会构建一个图像金字塔,并在每一层上计算FAST角点。 为了旋转不变性,ORB还在BRIEF描述子的基础上根据灰度质心添加了方向描述。关于ORB特征点更详细的介绍,我们将放在一个图像处理的专题中进行介绍。
为了满足SLAM系统的需要,ORB-SLAM对ORB特征点的计算进行了一些细微的调整。它以1.2的缩放比例逐层构建了一个8层的图像金字塔,并为每层图像计算FAST角点。 为了保证提取的角点尽量是同分布(homogeneous distribution)的,ORB-SLAM对每层图像都进行了删格化,并尝试在每个单元中提取出至少5个角点。如果某个单元中无法提取足够多的角点, 就降低FAST角点的判定阈值。如果实在检测不出5个角点来,就有多少是多少。至于描述子的计算方法,并没有什么改动。
我们将在本系列的附录中介绍ORB特征提取。下面的代码示例了如何使用ORB-SLAM的特征点提取器计算ORB特征。 我们首先创建了一个容器keys用于保存特征点,使用cv::Mat类型的数据对象来记录各个特征点的描述子,descriptors的每一行对应着keys中的一个特征点。
std::vector<cv::KeyPoint> keys;
cv::Mat descriptors;
ORB_SLAM2::ORBextractor orbor(1000, 1.2, 8, 20, 7);
orbor(img_gray, cv::Mat(), keys, descriptors);
然后构建特征点提取器对象,给构造函数传递了5个参数。第一个参数表示期望提取的特征点数量, 论文中声称对于\(512 \times 384\), \(752 \times 480\)这样的图像提取1000个角点就好了,KITTI数据集的图像都是\(1241 \times 376\)分辨率,需要提取2000个特征点。 第二和第三个参数分别指定了图像金字塔的缩放比例和层数,在ORB-SLAM中分别是1.2和8。最后两个参数是FAST角点的判定阈值,一般ORB-SLAM会用第四个参数计算FAST角点, 当对应删格无法得到5个角点时,就降低阈值使用最后那个参数再次检测角点。
当新一帧的图像到来的时候,需要先将其转换成灰度图,再通过特征点提取器对象获取ORB特征点。ORBExtractor重载了"()"运算符,所以我们可以把它当作一个函数来使用。它有四个参数, 其中img_gray就是待提取特征的灰度图,Keys和descriptors是我们一开始创建的用来保存特征点和描述子的对象。第二个参数是一个cv::Mat类型的数据,它的本意是一个计算特征点的模板矩阵(Mask), 但是没有用到,所以这里随意给了一个值。
#include <XiaoTuCVBox/ORBextractor.h>
#include <iostream>
#include <cassert>
int main(int argc, char *argv[]) {
assert(2 == argc);
std::cout << "OrbExtracotr" << std::endl;
int nFeatures = 1000;
double fScaleFactor = 1.2;
int nLevels = 8;
double fIniThFAST = 20;
double fMinThFAST = 7;
XiaoTuCVBox::ORBextractor * pextractor = new XiaoTuCVBox::ORBextractor(nFeatures, fScaleFactor, nLevels, fIniThFAST, fMinThFAST);
cv::Mat im = cv::imread(argv[1], cv::IMREAD_UNCHANGED);
cv::Mat imGray = im;
if (3 == imGray.channels())
cv::cvtColor(imGray, imGray, cv::COLOR_RGB2GRAY);
std::vector<cv::KeyPoint> vKeys;
cv::Mat descriptors;
(*pextractor)(imGray, cv::Mat(), vKeys, descriptors);
std::cout << "特征点数量:" << vKeys.size() << std::endl;
std::cout << descriptors.size << std::endl;
for (size_t i = 0; i < vKeys.size(); i++) {
cv::circle(im, vKeys[i].pt, 2, cv::Scalar(255, 0, 0), -1);
}
cv::imshow("douniwan", im);
cv::waitKey(0);
return 0;
}