本文系ORB-SLAM2原理 代码实战系列原创文章,对应的视频课程见: 如何真正搞透视觉SLAM?
大家好,从今天开始我们陆续更新ORB-SLAM2/3系列的原创文章,以小白和师兄对话的形式阐述背景原理 代码解析,喜欢的点个赞分享,支持的人越多,更新越有动力!如有错误欢迎留言指正!
代码注释地址:
https://github.com/electech6/ORB_SLAM2_detailed_comments
VSLAM系列原创01讲 | 深入理解ORB关键点提取:原理 代码
接上回继续。。。
小白:我们计算出来的这个角点具体怎么用呢?
师兄:在关键点部分我们根据灰度质心法得到关键点的旋转角度后,在计算描述子之前我们会先用这个角度进行旋转。如下图所示P为圆形区域的几何中心,Q为圆形区域的灰度质心,我们的目的就是把下图左中像素旋转到和主方向坐标轴对齐。
描述子 Steered BRIEF
师兄:前面我们用Oriented FAST确定了关键点,下面就要对每个关键点的信息进行量化,计算其描述子。ORB特征点里的描述子是在BRIEF基础上进行改进的,称之为Steered BRIEF。我们先来了解一下什么是BRIEF。
BRIEF是一种二进制编码的描述子,在ORB-SLAM2里面它是一个256 bit的向量,其中每个bit是0或者1。这样我们在比较两个描述子的时候可以直接用异或位运算来计算汉明距离,速度非常快。
以下是 BRIEF 描述子的具体计算方法:
- 第1步:为减少噪声干扰,先对图像进行高斯滤波。
- 第2步:以关键点为中心,取一定大小的图像窗口 。在窗口内随机选取一对点,比较二者像素的大小,进行如下二进制赋值。 其中 表示像素 在窗口 内的灰度值。
- 第3步:在窗口中随机选取(ORB-SLAM2中)对随机点,重复步骤2的二进制赋值,最后得到一个256维的二进制描述子。
对于上述第2步,在ORB-SLAM2里采用了一种固定的选点模板,这个模板是精心设计的,保证了描述子具有较高的辨识度。下面是模板的前4行:
代码语言:javascript复制static int bit_pattern_31_[256*4] =
{
8,-3, 9,5/*mean (0), correlation (0)*/,
4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
-11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
...
}
我们看到这是一个个值组成的数组。256就代表描述子的维度,每行的4个值表示一对点的坐标,比如第一行表示,根据BRIEF的第2步即可判断这一行对应的二进制是0还是1,这样最终就得到了 256 维的描述子。
ORB特征点里对原始的BRIEF进行了改进,利用前面我们计算的关键点的主方向来旋转BRIEF描述子,旋转之后的BRIEF描述子称之为Steered BRIEF,这样ORB的描述子就具有了旋转不变性。那么具体怎么做呢?
假设我们现在有一个点,我们把原点指向它的向量旋转角度,得到一个新的点,那么在数学上如何实现呢?
我们来推导一下,如上图所示,我们假设向量 和水平轴 的夹角为 ,向量模长 ,则有
根据三角公式容易得到:
将上式写为矩阵形式可以得到:
以上就是 Steered BRIEF 的原理,源码实现如下:
代码语言:javascript复制/**
* @brief 计算ORB特征点的描述子
* @param[in] kpt 特征点对象
* @param[in] img 提取特征点的图像
* @param[in] pattern 预定义好的采样模板
* @param[out] desc 用作输出变量,保存计算好的描述子,维度为32*8 = 256 bit
*/
static void computeOrbDescriptor(const KeyPoint& kpt, const Mat& img, const Point* pattern, uchar* desc)
{
//得到特征点的角度,用弧度制表示。其中kpt.angle是角度制,范围为[0,360)度
float angle = (float)kpt.angle*factorPI;
//计算这个角度的余弦值和正弦值
float a = (float)cos(angle), b = (float)sin(angle);
//获得图像中心指针
const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
//获得图像的每行的字节数
const int step = (int)img.step;
//原始的BRIEF描述子没有方向不变性,通过加入关键点的方向来计算描述子,称之为Steer BRIEF,具有较好旋转不变特性
//具体地,在计算的时候需要将这里选取的采样模板中点的x轴方向旋转到特征点的方向。
//获得采样点中某个idx所对应的点的灰度值,这里旋转前坐标为(x,y), 旋转后坐标(x',y'),他们的变换关系:
// x'= xcos(θ) - ysin(θ), y'= xsin(θ) ycos(θ)
// 下面表示 y'* step x'
#define GET_VALUE(idx) center[cvRound(pattern[idx].x*b pattern[idx].y*a)*step cvRound(pattern[idx].x*a - pattern[idx].y*b)]
//brief描述子由32*8位组成
//其中每一位是来自于两个像素点灰度的直接比较,所以每比较出8bit结果,需要16个随机点,这也就是为什么pattern需要 =16的原因
for (int i = 0; i < 32; i, pattern = 16)
{
int t0, //参与比较的第1个特征点的灰度值
t1, //参与比较的第2个特征点的灰度值
val; //描述子这个字节的比较结果,0或1
t0 = GET_VALUE(0); t1 = GET_VALUE(1);
val = t0 < t1; //描述子本字节的bit0
t0 = GET_VALUE(2); t1 = GET_VALUE(3);
val |= (t0 < t1) << 1; //描述子本字节的bit1
t0 = GET_VALUE(4); t1 = GET_VALUE(5);
val |= (t0 < t1) << 2; //描述子本字节的bit2
t0 = GET_VALUE(6); t1 = GET_VALUE(7);
val |= (t0 < t1) << 3; //描述子本字节的bit3
t0 = GET_VALUE(8); t1 = GET_VALUE(9);
val |= (t0 < t1) << 4; //描述子本字节的bit4
t0 = GET_VALUE(10); t1 = GET_VALUE(11);
val |= (t0 < t1) << 5; //描述子本字节的bit5
t0 = GET_VALUE(12); t1 = GET_VALUE(13);
val |= (t0 < t1) << 6; //描述子本字节的bit6
t0 = GET_VALUE(14); t1 = GET_VALUE(15);
val |= (t0 < t1) << 7; //描述子本字节的bit7
//保存当前比较的出来的描述子的这个字节
desc[i] = (uchar)val;
}
//为了避免和程序中的其他部分冲突在,在使用完成之后就取消这个宏定义
#undef GET_VALUE
}