0.简介与说明
本篇笔记对应ORB-SLAM2系统的ORB特征提取部分,涉及到的代码文件主要是ORBextractor.h
和ORBextractor.cc
。完整的代码笔记与注释见Github项目,点击前往。因为深知阅读源码最痛苦的莫过于面对成千上万行代码不知从何读起,各个函数之间怎么设计、调用的、为什么要这样。因此本篇笔记的主要目的是从总体上总结ORB特征提取的过程,给读者一个宏观和框架上的认识,旨在给读者提供一个阅读源码的方向与参考,并且也会涉及代码中一些值得注意的地方。本篇笔记假设读者已经掌握了ORB的基本原理,因此不会涉及很多理论上的内容,如果不了解建议阅读ORB、ORB-SLAM或ORB-SLAM2的论文。如果不想阅读论文,这篇博客对ORB特征原理进行了简单介绍,也可以帮助你快速了解。
废话不多说,下面进入正题。笔记可能有点长,推荐静下心来慢慢看。
1.ORB-SLAM2中ORB特征的提取流程
在看代码时一定要对代码实现的总体流程有个了解,不然很容易一叶障目不见泰山,一头雾水,在细枝末节的地方打转。简单来说ORB特征和其它特征一样,主要包含角点提取与特征描述两大步骤。具体而言,ORB基于FAST提取角点,基于BRIEF对角点进行描述,此处不过多介绍。如果你对OpenCV比较了解应该知道OpenCV里面直接就有ORB提取的现成API可以调用,那么作者为什么还非要在ORB-SLAM2里自己又实现一遍呢?原因在于相比于OpenCV里的ORB多了使用OctTree进行角点过滤这一步骤。之所以要这样是为了让最终提取到的特征点分布更加均匀,这对后续帧间位姿估计是十分有利的。所以在ORB-SLAM2中的ORB特征提取主要包含以下三大步骤:
(1)计算影像金字塔。之所以要计算影像金字塔是为了应对不同影像间的特征尺度变化,比较好理解。
(2)利用OctTree对影像进行拆分并进行特征提取。这一步是角点提取的核心,也是和OpenCV中的ORB不同的地方。当然如果抛开OctTree拆分影像和过滤特征点的话,其实就是普通的FAST角点提取操作。这一步骤进一步可以分为以下四步,对于金字塔的每一层都会执行一遍,然后到下一层。
-
a.影像拆分与格网初始化。根据一些初始数据将每一层的影像拆分成不同大小的格网。
-
b.在每个格网内提取FAST角点。在每个格网内根据用户提供的参数提取FAST角点。
-
c.进一步拆分格网与过滤角点,直到满足条件。这步是核心的核心,通过多个循环嵌套实现对影像的划分。如果迭代的节点个数大于等于期望特征点个数或者节点个数不再变化则停止迭代。
-
d.计算提过滤后FAST角点的方向。基于灰度质心法计算角度。
(3)特征描述。结合前面计算的方向对每个过滤好的FAST角点计算BRIEF描述子。
2.带你看代码
上面简单介绍了ORB提取的主要流程,下面就结合实际的代码和函数对上面的过程进行细化。当然限于篇幅不可能把所有代码和注释都贴出来,这里只贴一些关键步骤。如果想进一步了解,强烈推荐去笔记开头的【里去看代码注释。因为相比于网络上其它代码注释,几乎是事无巨细地把每一行代码都写了注释,基本你想了解的细节都有。明确了代码的功能和目标以后,下面就从使用者的角度和特征提取流程去看代码,这样更易于理解。
(1)构造函数
在ORB-SLAM2中,提取ORB特征的相关功能被封装到了ORBextractor
这个类中,也就是说我们要想在外部调用需要先定义一个ORBextractor
的对象,然后条用这个对象的某个成员函数来实现ORB特征的提取。这个思路是完全正确的。也就是说我们需要从这个类的构造函数入手,开始看起。然后再看刚刚说的那个用来实现ORB特征提取的那个成员函数,那么在这里这个成员函数是什么呢?它就是括号运算符()
。没错,在ORBextractor
这个类中重载了括号运算符。这样做的目的是对于一个对象,我们可以像调用函数一样调用它,而不用再去”点”出来某个成员函数,比较方便。当然如果你不重载括号运算符,给成员函数起个名字也是完全可以的。至此我们就总体上了解了看代码的顺序,首先应该看ORBextractor
的构造函数,然后看重载的()
函数。
类的构造函数在头文件中的声明如下:
// ORBextractor的构造函数
ORBextractor(int nfeatures, float scaleFactor, int nlevels,
int iniThFAST, int minThFAST);
一上来用户需要提供5个参数,而且这5个参数没有默认值,必须提供。分别是期望提取的特征点个数、金字塔尺度因子、金字塔层数、FAST阈值1、FAST阈值2。其中特征点个数这个参数需要注意一下。由于有多层金字塔,因此每一层提取多少个特征点是根据这个值算出来的,这个过程在构造函数中完成。当然如果仅仅是作为使用者的用户不会察觉到这一点,最终返回的就是指定数量的特征点。两个FAST阈值一个高一个低,简单来说就是当用高的阈值在某个小格网里没能提取到特征点时就切换到低的阈值。
一般而言构造函数都是根据传入的一些参数对类的成员变量进行赋值,这里也不例外。建议在看构造函数内容前,建议先简单了解下类都有哪些成员变量。这样在看的时候才不至于糊涂,分不清是成员变量还是传入的参数。类的成员变量主要有这些:
class ORBextractor
{
public:
// 影像金字塔,里面存放每一层影像的内容
std::vector<cv::Mat> mvImagePyramid;
protected:
std::vector<cv::Point> pattern;
// 特征提取相关参数
// 它们都是protected的,也就是说外部函数无法直接访问
// 特征提取数量,这里需要理解的是由于有多层金字塔,
// 因此这里的特征点数量指的是所有层特征加一起的总数,并不是初始层的特征点个数
// 初始层的特征点个数可以根据等比数列求和公式算出来,是小于这个数值的
int nfeatures;
double scaleFactor; // 金字塔的尺度缩放因子
int nlevels; // 金字塔层数
int iniThFAST; // 初始FAST阈值
int minThFAST; // 最小FAST阈值
// 用于存储每一层的特征点个数
std::vector<int> mnFeaturesPerLevel;
std::vector<int> umax;
// 多个vector,用于储存每层的尺度因子和逆尺度相关信息
std::vector<float> mvScaleFactor;
std::vector<float> mvInvScaleFactor;
std::vector<float> mvLevelSigma2;
std::vector<float> mvInvLevelSigma2;
有些变量暂时不理解是做什么的也没关系,不用着急,后面看代码慢慢也就会明白了。下面就摘取构造函数贴出来。
ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
int _iniThFAST, int _minThFAST):
nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
iniThFAST(_iniThFAST), minThFAST(_minThFAST)
{
// 所有ORB参数在构造函数中就对应赋给了各个成员变量,所以后续就可以直接用了
// mvScaleFactor和mvLevelSigma2是ORBextractor的成员变量vector,根据传入的层数设置了它的长度
mvScaleFactor.resize(nlevels);
mvLevelSigma2.resize(nlevels);
// 它们的初值都是1
mvScaleFactor[0]=1.0f;
mvLevelSigma2[0]=1.0f;
// 对于这里的尺度可以理解为一个是以当前大小按指定的ScaleFactor不断放大
// 对于逆尺度可以理解为是以当前大小按照指定的ScaleFactor分之一逐渐缩小
// 按照层数依次计算缩放尺度
for(int i=1; i<nlevels; i++)
{
// 用了两种方法计算,一种是上一层尺度乘以缩放因子,得到下一层尺度
// 另一种是当前尺度缩放因子的平方
// 这里的scaleFactor是类的成员变量,在构造函数一开始就赋了初值
mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
mvLevelSigma2[i]=mvScaleFactor[i]*mvScaleFactor[i];
}
// 设置逆尺度列表长度
mvInvScaleFactor.resize(nlevels);
mvInvLevelSigma2.resize(nlevels);
// 每一层的尺度和逆尺度相乘为1,所以这里直接用1除以已经算出来的尺度就好
for(int i=0; i<nlevels; i++)
{
// 和上面尺度信息是对应的
mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
}
// 类的public的vector成员变量,根据金字塔层数设置长度,每一项对应一层影像
mvImagePyramid.resize(nlevels);
// 类的protected的vector成员变量,这里设置vector长度
mnFeaturesPerLevel.resize(nlevels);
// 这里其实相当于是给后面迭代提供一个初值
// scaleFactor是类的protected的成员变量,是金字塔的尺度缩放因子,由用户指定,在上面也有用到
// 这里求的factor其实是scaleFactor的反向
float factor = 1.0f / scaleFactor;
// 详细推导见博客,等比数列求和公式
// 简单来说就是nfeatures并不是每一层的特征点数量,而是所有层特征点加一起的总数
// 而各个层之间的特征点数量又满足等比关系,因此可以求解一个第一层应该有多少特征
// 后面各层对应的数量按照等比数列公式就可以推出来
float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
// 在上面,我们已经求得了第一层应该有多少特征,因此这里以此为初值循环求解各层特征数量
int sumFeatures = 0;
for( int level = 0; level < nlevels-1; level++ )
{
// 由于factor是小于1的,所以nDesiredFeaturesPerScale会越来越小
mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
sumFeatures += mnFeaturesPerLevel[level];
// factor就是等比公式里的因子,因此把当前项再乘以factor系数就可以得到下一项
nDesiredFeaturesPerScale *= factor;
}
// 最后一层提取的特征的个数等于用户指定的总特征数量nfeatures减去前面各层特征点数量的累积和
// 这里你可能会有个疑问,既然前面都求出等比数列的推导公式了,最后一层为什么不直接算出来,而是要拿总数减去前面的。
// 这里的核心就在于for循环的cvRound函数,这是一个四舍五入取整函数
// 换句话说就是每次都会丢失一点点,多层累加起来以后是一个不太能忽视的数字
// 例如每层都丢0.9,8层总共就是7.2个
// 如果最后一层还是按照等比数列来算,最后总的特征数量肯定是小于用户指定的nfeatures
// 为了弥补这种丢失,采用这种相减的办法将之前一点点丢失的一次性补回来
mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
// 对成员变量pattern进行赋值操作
const int npoints = 512; // 指定一共有512个点
// 构造一个Point类型的指针,这一步其实很重要,
// 将一个长度为1024的int类型的一维数组(bit_pattern_31_)变成了一个长度为512的Point类型的一维数组(pattern0)
// 程序会自动将两个数字组合在一起形成一个Point,例如
// 8,-3, 9,5
// 4,2, 7,-12
// 经过转换就是[8,-3],[9,5],[4,2],[7,-12]四个点,因此经过转换后的pattern0共有512个点
const Point* pattern0 = (const Point*)bit_pattern_31_;
// copy()函数用于将一个序列(sequence)拷贝到一个容器(container)中去
// 第一个参数是待拷贝序列的首地址,第二个参数是待拷贝序列的最后一个元素的下一个地址,第三个参数是拷贝目标容器的首地址
std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
//This is for orientation
// pre-compute the end of a row in a circular patch
// 类的vector成员变量,这里对它设置个长度
umax.resize(HALF_PATCH_SIZE + 1);
// 这里cvFloor只会返回一个值给vmax,v,v0并没有赋初值
// 这里不要受python的影响以为cvFloor会返回三个值给它们
int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);
int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);
const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;
// v=0到vmax
for (v = 0; v <= vmax; ++v)
umax[v] = cvRound(sqrt(hp2 - v * v));
// Make sure we are symmetric
for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
{
while (umax[v0] == umax[v0 + 1])
++v0;
umax[v] = v0;
++v0;
}
}
构造函数中可能不太好理解的是nDesiredFeaturesPerScale
的计算,为什么是这么奇怪一长串。这就是在上面说的由于有多层金字塔,因此每一层该提取多少特征点并非直接由用户指定。而是用户指定特征点总数,然后各层应该提取的特征点个数按照等比数列求解。这个因子就是用户指定的scaleFactor
。在这里就简单推导一下代码中的计算公式。首先如下图所示:
用户设置的scaleFactor
为1.2,因此可以很容易算出factor
为1/1.2,约为0.83。设nFeatures
为num,也就是说用户期望提取到num个特征点,所有层的特征总数加一起应该为num。不妨设原始大小影像(金字塔第一层)上需要提取m个特征点,金字塔共有n层。按照等比数列的关系,可以很容易算出其它层上应该要提取的特征点个数,如上图所示。按等比数列前n项求和公式:
在这里\(a_{1}\)为m,\(a_{n}\)为\(0.83^{n-1}m\),q为0.83,\(S_{n}\)为num,唯一的未知量是m。则有下式:
\[S_{n}=\frac{m-0.83^{n-1}m\cdot 0.83}{1-0.83}=\frac{m-0.83^{n}m}{1-0.83}\]也就是说:
\[num=\frac{(1-0.83^{n})m}{1-0.83}\]即:
\[m=\frac{num(1-0.83)}{1-0.83^{n}}\]可以对比,这里m就是对应代码中的nDesiredFeaturesPerScale
。
(2)特征提取函数
在看完构造函数后,下面就要看特征提取的函数了。首先头文件定义如下:
// Compute the ORB features and descriptors on an image.
// ORB are dispersed on the image using an octree.
// Mask is ignored in the current implementation.
// 重载了括号运算符,方便直接调用
// 这样新建了一个对象后就可以像调用函数一样调用它了
// 这也是对外执行ORB特征提取的唯一接口
// 例如:
// ORB_SLAM2::ORBextractor orb = ORB_SLAM2::ORBextractor(1000, 1.2, 8, 20, 10);
// orb(img_gray, cv::Mat(), keypoints, descriptors);
void operator()( cv::InputArray image, cv::InputArray mask,
std::vector<cv::KeyPoint>& keypoints,
cv::OutputArray descriptors);
需要输入的是影像以及掩膜mask
(没用到),还要输入一个vector
用于存放提取的特征点,一个Mat
用于存放描述子。下面贴出来函数内容的代码。
void ORBextractor::operator()( InputArray _image, InputArray _mask, vector<KeyPoint>& _keypoints,
OutputArray _descriptors)
{
if(_image.empty())
return;
Mat image = _image.getMat();
// assert宏的原型定义在<assert.h>中,其作用是如果它的条件返回错误,则终止程序执行
// 对于这里意思就是说,如果输入的影像不是灰度,则报错,必须是灰度影像
assert(image.type() == CV_8UC1 );
// Pre-compute the scale pyramid
// 它的返回值是直接返回给了ORB提取对象的public成员变量mvImagePyramid,所以这里看起来没有返回值
// 这也是这种看起来很费劲觉得错综复杂的原因
// 他把很多返回值、变量以类的成员变量形式实现了共享,对读者而言在一定程度上“藏起来”了
ComputePyramid(image);
// 注意,之所以是vector < vector<KeyPoint> >是因为有多层,每层又有多个特征,所以需要用两个vector嵌套
vector < vector<KeyPoint> > allKeypoints;
// 表面上看起来只传给这个函数一个参数,但其实通过类成员变量的方式直接在函数内部获取到了相关数据
// 这里为了分布均匀,采用OctTree分割影像
ComputeKeyPointsOctTree(allKeypoints);
//ComputeKeyPointsOld(allKeypoints);
// 开始特征描述相关操作
Mat descriptors;
// 先统计一下各层提取到的特征的总和
int nkeypoints = 0;
for (int level = 0; level < nlevels; ++level)
nkeypoints += (int)allKeypoints[level].size();
// 如果一个特征都没提取到
if( nkeypoints == 0 )
// 就把传入的_descriptors释放掉,不用描述了
_descriptors.release();
else
{
// 否则的化就创建一个Mat用于描述
// 这个描述矩阵共有nkeypoints行,32列,元素数据类型为CV_8U
// 也就是说每个特征点由32个CV_8U的数字描述
_descriptors.create(nkeypoints, 32, CV_8U);
// 将传入的描述矩阵先赋给新建的descriptors方便操作
descriptors = _descriptors.getMat();
}
// 先对传入的特征vector清空,防止出错
_keypoints.clear();
_keypoints.reserve(nkeypoints); // 设置长度
// 描述子的偏移量,用于在迭代计算描述子时找到正确的位置
int offset = 0;
// 按层数依次遍历特征点
for (int level = 0; level < nlevels; ++level)
{
// 根据索引获取每一层的特征点vector
vector<KeyPoint>& keypoints = allKeypoints[level];
int nkeypointsLevel = (int)keypoints.size(); // 当前层特征点的数量
// 如果为0则直接跳过本次循环
if(nkeypointsLevel==0)
continue;
// preprocess the resized image
// 先获取当前层对应的影像内容赋给workingMat方便后续处理
Mat workingMat = mvImagePyramid[level].clone();
// 调用OpenCV的高斯模糊函数对影像进行模糊,第一个参数是输入,第二个参数是输出
// 第三个参数是高斯卷积核大小
// 第四、第五个参数是X、Y方向上的方差sigma
// 第六个参数是扩边方式
GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
// Compute the descriptors
// 获取当前层所包含特征点数量的行数作为描述子待填充的Mat
Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
// 传入影像、特征点、待填充的描述子以及pattern即可
// 这个pattern也是类的protected vector成员变量之一,在构造函数中被赋值
computeDescriptors(workingMat, keypoints, desc, pattern);
// 将偏移量增加nkeypointsLevel
offset += nkeypointsLevel;
// Scale keypoint coordinates
// 如果不是金字塔的第一层(没有缩放),就对特征点坐标乘上缩放因子
if (level != 0)
{
float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor);
for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
keypoint->pt *= scale;
}
// And add the keypoints to the output
// 最后,将提取的特征点插入传入的参数_keypoints的尾部
// 但因为在上面已经先清空了_keypoints,所以这里其实是不存在其它特征点的
_keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
}
// 至此,特征点提取与描述的所有内容就全部介绍完了!
}
由于代码的注释已经写得很详细了,这里就不再赘述了。整体而言,核心的是ComputePyramid()
、ComputeKeyPointsOctTree()
、computeDescriptors()
这三个函数。
a.金字塔计算函数
ComputePyramid()
函数摘出来如下:
void ORBextractor::ComputePyramid(cv::Mat image)
{
// 这里的nlevels是成员变量,在构造函数里被初始化
for (int level = 0; level < nlevels; ++level)
{
// 这里获取的是vector成员变量mvInvScaleFactor的内容,也就是说里面的尺度因子都是小于1且慢慢变小的
// (用户指定的尺度因子大于1的情况下)
float scale = mvInvScaleFactor[level];
// 根据尺度因子计算下一层的长宽尺寸
Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
// 由于还涉及到扩边的问题,所以对图像长宽都加上一定数值
Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
// 新建两个Mat,temp类型和输入的image一致
Mat temp(wholeSize, image.type()), masktemp;
// 取temp的一定范围内的影像内容放到vector里
mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
// Compute the resized image
if( level != 0 )
{
resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
// BORDER_REFLECT_101是以镜面对称的方式扩边,BORDER_ISOLATED是以0灰度值填充。它们两个混合使用的效果和单独的reflect101效果一样
// 函数的第一个参数是输入影像,第二个参数是输出影像,后面的四个参数是上下左右方向扩展的距离,这里都是一样的
copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
BORDER_REFLECT_101+BORDER_ISOLATED);
}
else
{
// 将image扩边,返回给temp,四个方向大小相同都为EDGE_THRESHOLD,方式是REFLECT_101
copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
BORDER_REFLECT_101);
}
}
}
b.节点划分与特征过滤函数
ComputeKeyPointsOctTree()
是提取FAST角点和利用OctTree的关键函数,如下。
void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
{
// allKeypoints每一个元素是一个vector,存放的是这一层提取到的特征点
allKeypoints.resize(nlevels);
// 每一个小格网的大小,这里宽高都是30个像素
const float W = 30;
// 对每一层循环进行特征点提取
for (int level = 0; level < nlevels; ++level)
{
// 对于提取范围边界的一些计算
const int minBorderX = EDGE_THRESHOLD-3;
const int minBorderY = minBorderX;
const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
// 每一层都临时新建个vector变量用于存放特征点
vector<cv::KeyPoint> vToDistributeKeys;
// reserve函数用于申请内存
// 在需要对大量数据进行处理的时候就要使用reserve主动分配内存以提升程序执行效率
// 这里保留的是用户指定总特征个数的10倍的内存
vToDistributeKeys.reserve(nfeatures*10);
const float width = (maxBorderX-minBorderX);
const float height = (maxBorderY-minBorderY);
const int nCols = width/W; // 格网列数
const int nRows = height/W; // 格网行数
const int wCell = ceil(width/nCols); // 每个格网的宽度,向上取整
const int hCell = ceil(height/nRows); // 每个格网的高度
// 依照行列遍历每个格网进行处理
// 这一部分其实可以考虑用GPU进行并行加速,因为每个格网提取FAST角点的过程是各自独立的
for(int i=0; i<nRows; i++)
{
// 一系列格网坐标相关的判断与处理,不用过于深究
const float iniY =minBorderY+i*hCell;
float maxY = iniY+hCell+6;
if(iniY>=maxBorderY-3)
continue;
if(maxY>maxBorderY)
maxY = maxBorderY;
for(int j=0; j<nCols; j++)
{
// 一系列格网坐标相关的判断与处理,不用过于深究
const float iniX =minBorderX+j*wCell;
float maxX = iniX+wCell+6;
if(iniX>=maxBorderX-6)
continue;
if(maxX>maxBorderX)
maxX = maxBorderX;
// 每一个格网都会建一个临时的vector用于存放这个小格子里的特征点
vector<cv::KeyPoint> vKeysCell;
// 在每一小块内提取FAST角点(调用OpenCV的FAST函数),就是上面求得的iniY,maxY,iniX,maxX
// 要注意的是这里的阈值首先是iniThFAST,这个阈值就是普通的FAST阈值的含义
// 也就是中心像素与周围一圈像素灰度值差异,小于这个值认为灰度相同,大于则认为不同
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
vKeysCell,iniThFAST,true);
// 如果提取的角点为空,则使用指定的小阈值
if(vKeysCell.empty())
{
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
vKeysCell,minThFAST,true);
}
// 对于每一小块,如果提取的特征点vector不为空进行后续处理
if(!vKeysCell.empty())
{
// 构造一个迭代器迭代小格网里的每个特征点
for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
{
// 具体而言其实就是坐标转换,将特征点在小格网里的坐标转换到全图坐标
(*vit).pt.x+=j*wCell;
(*vit).pt.y+=i*hCell;
// 并将提取到的特征点添加到每层金字塔对应的vToDistributeKeys中
vToDistributeKeys.push_back(*vit);
}
}
}
}
// allKeypoints是传入的变量,根据索引level获取到当前层对应的元素并赋给keypoints
// 这样我在后续修改keypoints的时候就直接把传入的变量都改了,因为是引用传递
vector<KeyPoint> & keypoints = allKeypoints[level];
keypoints.reserve(nfeatures);
// 其实仔细观察就会发现,到这里,每一层提取的特征点的数量我们是不知道或者说不能直接精准控制的
// 上面在提取FAST角点的时候,设置的是FAST角点的阈值,并不是特征点的个数
// 因此在这里,我们完全不知道vToDistributeKeys到底有多少特征点,有没有达到期望的数量
// 因此才有了下面的这个函数,这个函数主要有两个作用:
// 1.看提取的特征点是否达到预期,多退少补 2.尽可能均匀分布特征点
// 利用八叉树对每一层提取的特征点进行过滤,使其均匀分布
// vToDistributeKeys 刚刚提取到的每一层未经处理的FAST角点
// minBorderX, maxBorderX, minBorderY, maxBorderY 坐标边界相关变量
// mnFeaturesPerLevel 类的成员变量,在构造函数里被赋值,根据用户指定的特征点数量计算得到的每一层应该提取的数量
keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
// 缩放后的每一块的大小
// 后面在计算FAST角点的方向的时候有用到PATCH_SIZE
// 因此这里的scaledPatchSize可以看作是特征点所代表的范围
const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
// Add border to coordinates and scale information
// 由于上面提取的特征点是不包括扩展的边界的,因此这里再手动加上边界
const int nkps = keypoints.size();
for(int i=0; i<nkps ; i++)
{
// 其实就是相当于整体平移一下
keypoints[i].pt.x+=minBorderX;
keypoints[i].pt.y+=minBorderY;
// octave是OpenCV的KeyPoint类的属性之一,int类型,说明这个特征点是位于金字塔的哪一层
keypoints[i].octave=level;
// size也是KeyPoint的属性之一,float类型,说明该特征点的有效范围(直径)
// FAST本身并没有严格意义上的有效范围概念(硬要说也有,就是中心点与周围比较像素构成的圆的直径),但ORB用的是Oriented FAST,
// 在计算方向时有用到PATCH_SIZE,因此在这里就把计算方向的范围作为特征点的有效范围
// 根据上面的计算公式也知道,scaledPatchSize与PATCH_SIZE和不同层的缩放因子有关
// 在PATCH_SIZE一定的情况下(例如这里在代码一开始就设置为了30)只与缩放因子有关,每一层的特征点有效范围都一样
keypoints[i].size = scaledPatchSize;
}
// 经过上面的步骤,金字塔一层的特征点就提取完了
}
// 经过上面的步骤,就完成了特征点的提取
// 但如果细心的话就会发现上面其实核心就是FAST,只不过用OctTree对其进行过滤了一下而已,以满足均匀分布
// ORB不是号称是Oriented FAST吗?这个Oriented到目前为止并没有体现出来
// 下面就是计算方向的代码,也是特征点提取的倒数第二步(最后一步是计算描述子)
// compute orientations
for (int level = 0; level < nlevels; ++level)
// 传入的参数是影像、对应特征点vector以及umax vector
// umax是类的protected vector成员变量,在构造函数里被赋值
computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
// 至此特征提取就完成了,还差描述
}
细心的话会发现这里面又调用了DistributeOctTree()
和computeOrientation()
函数。DistributeOctTree()
是拆分节点过滤特征点的关键函数。computeOrientation()
则用于计算角点的方向。
c.节点拆分函数
DistributeOctTree()
函数贴出来如下:
vector<cv::KeyPoint> ORBextractor::DistributeOctTree(const vector<cv::KeyPoint>& vToDistributeKeys, const int &minX,
const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
{
// Compute how many initial nodes
// 前面说过了,static_cast理解为强制类型转换就好
// 求解X方向上初始节点的个数,至于为什么用dx/dy再四舍五入取整这样比较奇怪的方式计算X方向初始节点个数暂时不知道
const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));
// 根据上面获得的X方向上的节点个数求解初始节点的水平宽度
const float hX = static_cast<float>(maxX-minX)/nIni;
// 新建一个ExtractorNode类型的list用于存放节点
// 这个list后面会频繁用到
list<ExtractorNode> lNodes;
// 新建一个ExtractorNode指针类型的vector,
// 它里面存放的是每次循环向lNodes添加元素后其最后一个元素的地址
vector<ExtractorNode*> vpIniNodes;
vpIniNodes.resize(nIni); // 长度就设置为刚刚计算出来的个数
// 依次循环,构造节点放入vector中
// 执行完这个循环其实只是将图像进行了X方向上的节点划分
// 因为在循环中所有节点的四角点的Y坐标值都是对应相同的
for(int i=0; i<nIni; i++)
{
// 每次循环都新建一个临时变量ni,四角点坐标的计算比较简单,一看就懂
ExtractorNode ni;
// 上面两个坐标,所以y方向都为0
ni.UL = cv::Point2i(hX*static_cast<float>(i),0);
ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
// 下面两个坐标,所以y方向都为dy,也就是maxY-minY
ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
// 设置节点的特征点vector长度为传入的vector的长度
// 不要忘记了这个传入的vToDistributeKeys是哪里来的
// 它里面是金字塔每一层提取的未经任何处理的原始特征点
ni.vKeys.reserve(vToDistributeKeys.size());
lNodes.push_back(ni); // 将节点放入lNodes中
// back()返回lNodes的最后一个元素的可读写的引用,换句话说你可以直接利用lNodes.back()修改最后一个元素的值
// 但这里需要注意的是vpIniNodes是ExtractorNode指针型的vector,因此要在前面加个取地址符才可以
vpIniNodes[i] = &lNodes.back();
}
//Associate points to childs
// 遍历所有特征点,按照X方向上的位置安放到对应的节点中去
for(size_t i=0;i<vToDistributeKeys.size();i++)
{
// 获得特征点
const cv::KeyPoint &kp = vToDistributeKeys[i];
// 根据特征点x坐标和节点宽度计算得到其所对应的节点索引
// 再根据节点索引获得对应节点,利用->操作符获取节点对象内的public的vector成员变量
// 最后将该特征点push到这个vector中
vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
}
// 构造一个迭代器,指向lNodes的第一个元素,后面就不新建一直用这个了
list<ExtractorNode>::iterator lit = lNodes.begin();
// 循环遍历节点,对于只含一个特征点和不含特征点的节点单独进行处理
while(lit!=lNodes.end())
{
// 如果当前节点只含一个特征点,那么就把当前节点的bNoMore设为true
// 也就是说指定当前节点不可以再继续分割了
if(lit->vKeys.size()==1)
{
lit->bNoMore=true;
lit++; // 迭代器迭代到下一个
}
// 如果说当前节点不含特征点,那么就直接把当前节点从lNodes中抹去
else if(lit->vKeys.empty())
// erase()函数的用法需要注意一下
// 它的输入参数是指向需要抹去元素的迭代器
// 而它相比于remove()函数无返回值,它是有返回值的,
// 它的返回值就是指向下一个元素的迭代器
// 因此,在这个分支里就不再需要lit++了
lit = lNodes.erase(lit);
// 如果当前节点既不为空也不仅包含一个特征点,那么就什么都不做,直接跳过
else
lit++;
}
bool bFinish = false; // 一个flag变量,用于指示分割是否完成,是否停止迭代
int iteration = 0; // 迭代次数
// 一个vector用于存放尺寸与指向该节点的指针,长度设置为当前节点总数的4倍
vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
vSizeAndPointerToNode.reserve(lNodes.size()*4);
// 开始迭代!
while(!bFinish)
{
iteration++; // 迭代次数累加1
int prevSize = lNodes.size(); // 当前节点总数,其是否变换会作为迭代终止的判断条件之一
lit = lNodes.begin(); // 把迭代器指向当前lNodes的第一个元素
int nToExpand = 0; // 累加变量,包含特征个数大于1的节点个数
vSizeAndPointerToNode.clear(); // 清空
// 开始正式迭代、遍历lNodes中的节点
while(lit!=lNodes.end())
{
// 前面说过了,如果节点的bNoMore为true也就是说不可再分,那么直接跳过
// 但别忘了把迭代器加一下
if(lit->bNoMore)
{
// If node only contains one point do not subdivide and continue
lit++;
continue;
}
// 如果当前节点的bNoMore为false,也就说明还可以继续分割,则进行下面的操作
else
{
// If more than one point, subdivide
// 新建四个临时节点变量,对应拆分的4个子节点
ExtractorNode n1,n2,n3,n4;
// 根据迭代器利用->操作符调用当前节点的成员函数DivideNode
// 由于函数参数是引用传递,因此它的输出值就是这四个子节点
// 这个函数做了哪些事情需要清楚,简单来说是三件事
// 1.根据父节点,对4个子节点的坐标范围进行了计算,4个子节点按照行优先顺序排列1 2;3 4
// 2.根据父节点特征点的x、y坐标,将各个特征点放到所属的子节点中
// 3.判断子节点是否为叶子节点(不可再分),如果是,bNoMore设为True
// 最后需要说明的是这个函数并没有对父节点做任何操作,只是新建了4个覆盖父节点的子节点
// 因此需要在后续的操作中删除它们的父节点
lit->DivideNode(n1,n2,n3,n4);
// Add childs if they contain points
// 这里分别对拆分好的4个子节点依次进行了操作
// 如果子节点1中的特征点个数不为空,则执行下列操作
if(n1.vKeys.size()>0)
{
// 将当前n1子节点添加到lNodes中
// 注意push_front是将元素添加到序列的最前面,而push_back则是添加到末尾
// 另外需要注意的是只有当节点包含的特征不为空时才会添加到lNodes
// 换句话说就是lNodes中的每个节点都至少包含一个或以上的特征点
// 若lNodes的长度等于期望特征数N,则实际提取到的特征点个数应该是大于等于N的
lNodes.push_front(n1);
// 进一步判断,如果当前节点包含的特征点多于1的话,也就说非叶子节点,bNoMore为false,则执行下面操作
if(n1.vKeys.size()>1)
{
nToExpand++; // 累加变量+1,只有当前节点包含特征点个数大于1才累加
// 这里利用make_pair函数构造了一个pair放到了vSizeAndPointerToNode中
// size就是当前节点的特征点个数,
// 由于上面将当前节点放到了lNodes的最前面,所以当前节点就是lNodes的第一个元素
// 由于定义的类型是ExtractorNode的指针,因此前面要加个取地址符
vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
// 这里的操作是把指向lNodes的第一个元素(也就是当前节点)的迭代器赋给lNodes中第一个元素(当前节点)的lit成员变量(别忘了节点中是有个迭代器成员变量的)
lNodes.front().lit = lNodes.begin();
}
}
// 下面的n2,n3,n4都和上面的n1一样,这里就不再赘述了
if(n2.vKeys.size()>0)
{
lNodes.push_front(n2);
if(n2.vKeys.size()>1)
{
nToExpand++;
vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
if(n3.vKeys.size()>0)
{
lNodes.push_front(n3);
if(n3.vKeys.size()>1)
{
nToExpand++;
vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
if(n4.vKeys.size()>0)
{
lNodes.push_front(n4);
if(n4.vKeys.size()>1)
{
nToExpand++;
vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
// 如果还记得在前面lit->DivideNode那行注释说的话的话,这里就是把父节点删掉的操作
// erase函数在前面也介绍过了,不仅会删除当前元素,还会返回指向下一个元素的迭代器
// 所以这里也就不再需要手动累加了
lit=lNodes.erase(lit);
continue;
}
}
// 经过上面的操作,lNodes中的所有节点就都被遍历被迭代拆分了
// 但别忘了这是在另一个更大的while循环里,
// 直到目前为止我们并没有更改终止条件bFinish
// 下面就是是否终止迭代的一系列判断与操作
// Finish if there are more nodes than required features
// or all nodes contain just one point
// 如果lNodes中节点的个数大于期望提取的特征数量N(别忘了,这是函数传入的参数之一)
// 或者lNodes中节点的个数和上次迭代一样,也就是说拆分不动了
// 以上两种情况就停止迭代,bFinish设为true
if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
{
bFinish = true;
}
// 而如果当前节点总数加上3倍nToExpand大于N,则执行下面操作
// 这里体现的就是nToExpand的作用,上面说了nToExpand表示的是经过迭代后包含特征点数量大于1的节点的个数
// 如果说当前节点总数加上3倍nToExpand大于N,则说明当前分割结果不够“干净”、“均匀”,还包含了大量特征多余1的节点
// 至于说为什么是3,暂时还不太清楚
else if(((int)lNodes.size()+nToExpand*3)>N)
{
// 如果进入到这里,目前bFinish还为false所以会继续执行下面的代码,这其实和上面的是类似的
while(!bFinish)
{
prevSize = lNodes.size(); // 将当前的lNodes个数赋给prevSize
// 将当前的vSizeAndPointerToNode赋给vPrevSizeAndPointerToNode做个记录
vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
vSizeAndPointerToNode.clear(); // 然后清空当前vector
// 对vPrevSizeAndPointerToNode做了个排序,默认为升序
// 另外排序默认是按照pair的第一个元素进行,且排序直接修改原始数据,没有另外的返回值
// 这样排完以后vPrevSizeAndPointerToNode中的元素是按照节点所包含的特征点个数按照从小到大的顺序排序
// 越往后节点包含的特征点个数越多,换句话说就是越可以继续拆分,直到一个节点包含一个特征点
sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
// for循环遍历其中的每个元素,从后往前,原因在上一行已经说了
for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
{
// 循环里的操作其实和前面是一样的
ExtractorNode n1,n2,n3,n4;
vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);
// Add childs if they contain points
if(n1.vKeys.size()>0)
{
lNodes.push_front(n1);
if(n1.vKeys.size()>1)
{
vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
if(n2.vKeys.size()>0)
{
lNodes.push_front(n2);
if(n2.vKeys.size()>1)
{
vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
if(n3.vKeys.size()>0)
{
lNodes.push_front(n3);
if(n3.vKeys.size()>1)
{
vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
if(n4.vKeys.size()>0)
{
lNodes.push_front(n4);
if(n4.vKeys.size()>1)
{
vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
lNodes.front().lit = lNodes.begin();
}
}
// 添加完子节点以后还是别忘了把父节点删掉
lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);
// 如果当前节点个数大于期望值N,就直接结束for循环
if((int)lNodes.size()>=N)
break;
}
// 判断条件和前面一样,满足的话bFinish设为true
if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
bFinish = true;
}
}
}
// Retain the best point in each node
// 建立vector用于保存结果
vector<cv::KeyPoint> vResultKeys;
vResultKeys.reserve(nfeatures);
// 循环遍历每个节点
for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
{
// 获取到节点所包含的所有特征点
vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
// 获取到vector的第一个元素
// 这里并不需要担心获取为空的问题,因为前面说了,能够加到lNodes的节点至少都包含了一个特征点
cv::KeyPoint* pKP = &vNodeKeys[0];
// 先将这个特征点的相应值作为最大值
// 这里简单说一下response是OpenCV中KeyPoint的属性之一,
// 可以理解为这个值越高说明特征点的质量越好
float maxResponse = pKP->response;
// 如果说当前节点包含多个特征点,
// 那就遍历所有特征点,找到最大响应值以及其对应的特征点
for(size_t k=1;k<vNodeKeys.size();k++)
{
// 响应值比较,比较好懂
if(vNodeKeys[k].response>maxResponse)
{
pKP = &vNodeKeys[k];
maxResponse = vNodeKeys[k].response;
}
}
// 最后将这个有最大响应值的特征点添加到vResultKeys中
vResultKeys.push_back(*pKP);
}
// 终于返回了
// 通过上面这个循环也可以看出,最后每个节点只选取一个特征点
// 所以提取的特征点数量和节点数量是相等的
return vResultKeys;
}
d.方向计算函数
而computeOrientation()
的核心其实是IC_Angle()
函数,这里就不贴了,完整代码和注释见Github项目。DistributeOctTree()
和computeOrientation()
都是在ComputeKeyPointsOctTree()
中被调用的,用于拆分节点过滤特征点和计算角点的方向。
(3)特征描述函数
执行到这一步其实角点就提取好了,还差最后一步就是描述,由computeDescriptors()
实现,如下。
static void computeDescriptors(const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors,
const vector<Point>& pattern)
{
// 这里其实也是一层包装,核心函数是computeOrbDescriptor
// 这里相当于对传入的descriptors重新赋值,元素全部为0,
// 行数为特征点个数,列数为32(描述子长度),元素数据类型为8位无符号整型(最大为255)
descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);
// 依次遍历每个特征点,计算描述子
for (size_t i = 0; i < keypoints.size(); i++)
// 第一个参数是特征点,第二个参数是影像,第三个参数是Point对象,第四个参数就是待填充的描述子
// 注意一下传入的描述子的类型与大小,它其实是一个uchar类型的指针,可以根据索引获取到第i行的所有元素,因此可以说大小为1x32
computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i));
}
可以看出来很明显它也是一个包装,真正计算描述子的是computeOrbDescriptor()
函数,如下。
const float factorPI = (float)(CV_PI/180.f); // 角度转成弧度制的系数
static void computeOrbDescriptor(const KeyPoint& kpt,
const Mat& img, const Point* pattern,
uchar* desc)
// 传入的参数中带const的都是不会修改,只读的
// 另外这里看起来传入的是一个Point指针类型的pattern,但其实是一个数组,可以根据索引获取其它元素
{
// 在特征提取的最后,会在computeOrientation函数中计算特征点的角度
float angle = (float)kpt.angle*factorPI; // 将角度转换为弧度
float a = (float)cos(angle), b = (float)sin(angle); // 相关变量计算
// 和之前一样,这里获取的是一个指向特征点像素的uchar类型的指针,并非是特征点所对应像素的灰度值,需要注意
// 如果把img前面的取地址符&去掉,获取的就是该位置对应的灰度值了
// 换句话说是可以对center进行索引操作获取其它元素的值的,这在下面定义的宏中就有体现
const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
// 这里的step是Mat的属性之一,表示一个数据所占字节长度,方便后面迭代时候跳过指定步长
// 例如一个单通道灰度影像一个像素值在我这里字节长度是700,而RGB影像一个像素的长度是2100
const int step = (int)img.step;
// 这里定义了一个宏,用于后续计算的方便
// 这里的center就是上面获取的uchar的指针,而pattern就是传入的参数
// 这里面一长串其实都是在计算索引,而对center取索引获取到的就是该索引(位置)所对应的灰度值
#define GET_VALUE(idx) \
center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
cvRound(pattern[idx].x*a - pattern[idx].y*b)]
// 前面定义的描述子有32列,对应这里的32次循环
// 注意这里的pattern指向的地址随着迭代也在变化,每次增加16
// 这16其实就是对应一次迭代读取pattern的步长,在一次迭代中,一共会获取16个元素,所以下一次迭代从16开始16
// 另外,根据这个算法,可以计算出一共要有32×16个点用于迭代,而在代码一开始的pattern中就是512个点,在类的构造函数初始化pattern的时候也有体现
for (int i = 0; i < 32; ++i, pattern += 16)
{
int t0, t1, val; // 临时变量
// 获取0,1索引对应的像素的灰度值,然后进行比较,比较结果放到val里
t0 = GET_VALUE(0); t1 = GET_VALUE(1);
val = t0 < t1; // true为1,false为0
t0 = GET_VALUE(2); t1 = GET_VALUE(3); // 和上面一样
// |表示两个相应的二进制位中只要有一个为1,该位的结果值为1,否则为0
// 而这里又多了个等号,就类似于+=这种操作,表示按位或赋值,
// 将val与t0 < t1进行按位或运算,并将结果再赋给val
// <<用来将一个数的各二进制位全部左移N位,高位舍弃,低位补0
// 另外还需要注意的是这里的运算顺序
// 这里认为添加了括号,所以先运算括号里的内容,然后运算<<,最后运算后的结果再按位或赋值
// 这里之所以要左移1位是因为上面第一位已经有了内容,如果不左移的话,数据就被覆盖了
val |= (t0 < t1) << 1;
t0 = GET_VALUE(4); t1 = GET_VALUE(5);
val |= (t0 < t1) << 2;
t0 = GET_VALUE(6); t1 = GET_VALUE(7);
val |= (t0 < t1) << 3;
t0 = GET_VALUE(8); t1 = GET_VALUE(9);
val |= (t0 < t1) << 4;
t0 = GET_VALUE(10); t1 = GET_VALUE(11);
val |= (t0 < t1) << 5;
t0 = GET_VALUE(12); t1 = GET_VALUE(13);
val |= (t0 < t1) << 6;
t0 = GET_VALUE(14); t1 = GET_VALUE(15);
val |= (t0 < t1) << 7;
// 每次比较都有一个0或1的结果,上面比较了8次,因此到这里val是8位的0、1二进制串
// 而且根据desc数据类型的定义,是8U,最大值为255,所以将8位的二进制串转成uchar类型不会有任何数据丢失问题
// 另外前面说了,desc可以看成是有32个元素的数组,因此直接基于索引就可以进行赋值
// 将二进制串转换为uchar类型的数值后就可以直接赋给desc[i],就完成了一个描述子的一个数的计算
// 迭代32次就可以把整个描述子计算出来
desc[i] = (uchar)val;
}
// 结束定义的宏
#undef GET_VALUE
}
如果能看到这里,那么你对ORB的特征提取应该有比较详细的了解了。当然受限于篇幅,一些变量、函数等没能一一贴出来,完整注释见Github项目。另外需要说明的是如果这篇笔记中的注释内容与Github项目中的不同,请以Github项目中的为准。因为有时候可能修改了一些内容但没有在博客里更新。
最后要说一下,其实看到这里你会发现,整个ORB特征提取并没有依赖除了OpenCV以外的其它第三方库,也就说只要把这两个文件放到你需要的地方就可以使用了。而且在一开始也说了,相比于OpenCV自带的ORB,它提取的特征点分布更加均匀,有利于帧间位姿估计。
3.简单测试
下面代码简单演示了ORBextractor
的用法以及提取的特征点的一些属性值,对应Github项目learn/learn_orb_extractor.cpp
文件内容。
#include "ORBextractor.h"
#include <iostream>
#include <opencv/cv.hpp>
using namespace std;
using namespace cv;
int main() {
Mat img, img_gray, img_show;
vector<cv::KeyPoint> keypoints;
Mat descriptors;
img = imread("/root/test.jpg");
cvtColor(img, img_gray, cv::COLOR_BGR2GRAY);
ORB_SLAM2::ORBextractor orb = ORB_SLAM2::ORBextractor(1000, 1.2, 8, 20, 10);
orb(img_gray, cv::Mat(), keypoints, descriptors);
img.copyTo(img_show);
for (size_t i = 0; i < keypoints.size(); ++i) {
KeyPoint tmp_kp = keypoints[i];
cout << endl << "------" << i + 1 << "------" << endl;
cout << "size:" << tmp_kp.size << endl;
cout << "angle:" << tmp_kp.angle << endl;
cout << "octave:" << tmp_kp.octave << endl;
cout << "pt:" << tmp_kp.pt << endl;
cout << "response:" << tmp_kp.response << endl;
circle(img_show, keypoints[i].pt, 2, cv::Scalar(0, 255, 255), 2);
}
cout << "Total keypoints:" << keypoints.size() << endl;
cv::imwrite("/root/test_kps.jpg", img_show);
return 0;
}
下面是待提取特征点的原图。 下面是提取到的ORB特征点,可以看到总体分布还是比较均匀的。
本文作者原创,未经许可不得转载,谢谢配合