初始化图像金字塔相关变量:
变量名 | 描述 | 配置从TUM1.yaml读入(初始值) |
---|---|---|
int nfeatures |
指定要提取的特征点数目 |
ORBextractor.nFeatures: 1000 |
float scaleFactor, |
指定图像金字塔的缩放系数 | ORBextractor.scaleFactor: 1.2 |
int nlevels, | 指定图像金字塔的层数 | ORBextractor.nLevels: 8 |
int iniThFAST | 指定初始的FAST特征点提取参数,可以提取出最明显的角点 | ORBextractor.iniThFAST: 20 |
int minThFAST) | 如果初始阈值没有检测到角点,降低到这个阈值提取出弱一点的角点 |
ORBextractor.minThFAST: 7 |
成员变量 | 描述 | |
std::vector |
分配到每层图像中,要提取的特征点数目 | |
std::vector |
计算特征点方向的时候,有个圆形的图像区域,这个vector中存储了每行u轴的边界(四分之一,其他部分通过对称获得) | |
std::vector |
每层图像的缩放因子 | |
std::vector |
每层缩放因子的倒数 | |
std::vector |
存储每层的sigma^2,即上面每层图像相对于底层图像缩放倍数的平方 | |
std::vector |
sigma平方的倒数 |
初始化:
ORBextractor::ORBextractor(int _nfeatures, //指定要提取的特征点数目
float _scaleFactor, //指定图像金字塔的缩放系数
int _nlevels, //指定图像金字塔的层数
int _iniThFAST, //指定初始的FAST特征点提取参数,可以提取出最明显的角点
int _minThFAST): //如果初始阈值没有检测到角点,降低到这个阈值提取出弱一点的角点
nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
iniThFAST(_iniThFAST), minThFAST(_minThFAST)//设置这些参数
{
//存储每层图像缩放系数的vector调整为符合图层数目的大小
mvScaleFactor.resize(nlevels);
//存储这个sigma^2,其实就是每层图像相对初始图像缩放因子的平方
mvLevelSigma2.resize(nlevels);
mvScaleFactor[0]=1.0f;
mvLevelSigma2[0]=1.0f;
//然后逐层计算图像金字塔中图像相当于初始图像的缩放系数
for(int i=1; i= vmin; --v)
{
while (umax[v0] == umax[v0 + 1])
++v0;
umax[v] = v0;
++v0;
}
}
重点:
1.将特征点均匀划分到每一层https://zhuanlan.zhihu.com/p/61738607
2.为最后面为了计算描述子构成了1个半径为16的圆,利用多边形近似,只计算1/8后对折形呈圆。利用v和半径勾股定理得出umax。
1.首先主函数入口使用了仿函数(类似ceres库)
/**
* _image 输入原始图的图像
* _mask
* _keypoints 存储特征点关键点的向量
* _descriptors 存储特征点描述子的矩阵
*/
void ORBextractor::operator()( InputArray _image, InputArray _mask, vector& _keypoints,
OutputArray _descriptors)
{
// Step 1 检查图像有效性。如果图像为空,那么就直接返回
if(_image.empty())
return;
//转为mat
Mat image = _image.getMat();
//判断图像的格式是否正确,要求是单通道灰度值
assert(image.type() == CV_8UC1 );
// Pre-compute the scale pyramid
// Step 2 构建图像金字塔
ComputePyramid(image);
// Step 3 计算图像的特征点,并且将特征点进行均匀化。均匀的特征点可以提高位姿计算精度
// 存储所有的特征点,注意此处为二维的vector,第一维存储的是金字塔的层数,第二维存储的是那一层金字塔图像里提取的所有特征点
vector < vector > allKeypoints;
//使用四叉树的方式计算每层图像的特征点并进行分配
ComputeKeyPointsOctTree(allKeypoints);
//使用传统的方法提取并平均分配图像的特征点,作者并未使用
//ComputeKeyPointsOld(allKeypoints);
// Step 4 拷贝图像描述子到新的矩阵descriptors
Mat descriptors;
//统计整个图像金字塔中的特征点
int nkeypoints = 0;
//开始遍历每层图像金字塔,并且累加每层的特征点个数
for (int level = 0; level < nlevels; ++level)
nkeypoints += (int)allKeypoints[level].size();
//如果本图像金字塔中没有任何的特征点
if( nkeypoints == 0 )
//通过调用cv::mat类的.realse方法,强制清空矩阵的引用计数,这样就可以强制释放矩阵的数据了
_descriptors.release();
else
{
//如果图像金字塔中有特征点,那么就创建这个存储描述子的矩阵,注意这个矩阵是存储整个图像金字塔中特征点的描述子的
_descriptors.create(nkeypoints, //矩阵的行数,对应为特征点的总个数
32, //矩阵的列数,对应为使用32*8=256位描述子
CV_8U); //矩阵元素的格式
descriptors = _descriptors.getMat();
}
//清空用作返回特征点提取结果的vector容器
_keypoints.clear();
//并预分配正确大小的空间
_keypoints.reserve(nkeypoints);
//因为遍历是一层一层进行的,但是描述子那个矩阵是存储整个图像金字塔中特征点的描述子,所以在这里设置了Offset变量来保存“寻址”时的偏移量,
//辅助进行在总描述子mat中的定位
int offset = 0;
//开始遍历每一层图像
for (int level = 0; level < nlevels; ++level)
{
//获取在allKeypoints中当前层特征点容器
vector& keypoints = allKeypoints[level];
//本层的特征点数
int nkeypointsLevel = (int)keypoints.size();
//如果特征点数目为0,跳出本次循环,继续下一层金字塔
if(nkeypointsLevel==0)
continue;
// preprocess the resized image
// Step 5 对图像进行高斯模糊
// 深拷贝当前金字塔所在层级的图像
Mat workingMat = mvImagePyramid[level].clone();
// 注意:提取特征点的时候,使用的是清晰的原图像;这里计算描述子的时候,为了避免图像噪声的影响,使用了高斯模糊
GaussianBlur(workingMat, //源图像
workingMat, //输出图像
Size(7, 7), //高斯滤波器kernel大小,必须为正的奇数
2, //高斯滤波在x方向的标准差
2, //高斯滤波在y方向的标准差
BORDER_REFLECT_101);//边缘拓展点插值类型
// Compute the descriptors 计算描述子
// desc存储当前图层的描述子
Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
// Step 6 计算高斯模糊后图像的描述子
computeDescriptors(workingMat, //高斯模糊之后的图层图像
keypoints, //当前图层中的特征点集合
desc, //存储计算之后的描述子
pattern); //随机采样模板
// 更新偏移量的值
offset += nkeypointsLevel;
// Scale keypoint coordinates
// Step 6 对非第0层图像中的特征点的坐标恢复到第0层图像(原图像)的坐标系下
// 对于第0层的图像特征点,他们的坐标就不需要再进行恢复了
if (level != 0)
{
// 获取当前图层上的缩放系数
float scale = mvScaleFactor[level];
// 遍历本层所有的特征点
for (vector::iterator keypoint = keypoints.begin(),
keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
// 特征点本身直接乘缩放倍数就可以了
keypoint->pt *= scale;
}
// And add the keypoints to the output
// 将keypoints中内容插入到_keypoints 的末尾
// keypoint其实是对allkeypoints中每层图像中特征点的引用,这样allkeypoints中的所有特征点在这里被转存到输出的_keypoints
_keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
}
}
在frame.cc中进行重载调用
if(flag==0)
// 这里使用了仿函数来完成,重载了括号运算符 ORBextractor::operator()
(*mpORBextractorLeft)(im,
cv::Mat(),
mvKeys,
mDescriptors);
else
(*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight);
}
2.构建图像金字塔
void ORBextractor::ComputePyramid(cv::Mat image)
{
//开始遍历所有的图层
for (int level = 0; level < nlevels; ++level)
{
//获取本层图像的缩放系数
float scale = mvInvScaleFactor[level];
//计算本层图像的像素尺寸大小
Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
//将图像进行“补边”,EDGE_THRESHOLD区域外的图像不进行FAST角点检测
Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
// 定义了两个变量:temp是扩展了边界的图像,masktemp并未使用
Mat temp(wholeSize, image.type()), masktemp;
// 把图像金字塔该图层的图像指针mvImagePyramid指向temp的中间部分(这里为浅拷贝,内存相同)
mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
// Compute the resized image
//计算第0层以上resize后的图像
if( level != 0 )
{
//将上一层金字塔图像根据设定sz缩放到当前层级
resize(mvImagePyramid[level-1], //输入图像
mvImagePyramid[level], //输出图像
sz, //输出图像的尺寸
0, //水平方向上的缩放系数,留0表示自动计算
0, //垂直方向上的缩放系数,留0表示自动计算
cv::INTER_LINEAR); //图像缩放的差值算法类型,这里的是线性插值算法
//这样做是为了能够正确提取边界的FAST角点
copyMakeBorder(mvImagePyramid[level], //源图像
temp, //目标图像(此时其实就已经有大了一圈的尺寸了)
EDGE_THRESHOLD, EDGE_THRESHOLD, //top & bottom 需要扩展的border大小
EDGE_THRESHOLD, EDGE_THRESHOLD, //left & right 需要扩展的border大小
BORDER_REFLECT_101+BORDER_ISOLATED); //扩充方式
//BORDER_ISOLATED 表示对整个图像进行操作
}
else
{
//对于第0层未缩放图像,直接将图像深拷贝到temp的中间,并且对其周围进行边界扩展。此时temp就是对原图扩展后的图像
copyMakeBorder(image,
temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
BORDER_REFLECT_101);
}
}
}
绿色区域是src最边界的像素,蓝色区域是我们扩充的5个像素的扩充边界,而红色区域就是蓝色区域在src的对称部分。
3.提取特征点并进行筛选
如上图所示,提取特征点如果聚集在一起,那么识别效果非常差。提取特征点最重要就是特征点均匀地分布在图像的所有部分,为实现这一目标,编程实现上使用了两个技巧:
1.分块搜索特征点,若某块内特征点响应值太小的话就降低分数重新搜索.
2.对得到的所有特征点进行八叉树筛选,若某区域内特征点数目过于密集,则只取其中响应值最大的那个
void ORBextractor::ComputeKeyPointsOctTree(
vector >& allKeypoints) //所有的特征点,这里第一层vector存储的是某图层里面的所有特征点,
//第二层存储的是整个图像金字塔中的所有图层里面的所有特征点
{
//重新调整图像层数
allKeypoints.resize(nlevels);
//图像cell的尺寸,是个正方形
const float W = 30;
// 对每一层图像做处理
//遍历所有图像
for (int level = 0; level < nlevels; ++level)
{
const int minBorderX = EDGE_THRESHOLD-3; //一般解释:这里的3是因为在计算FAST特征点的时候,需要建立一个半径为3的圆。但这样不好理解,应该解释未要从第16个像素点开始遍历,前面的不应该遍历,所以减3
const int minBorderY = minBorderX; //minY的计算就可以直接拷贝上面的计算结果了
const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
//存储需要进行平均分配的特征点
vector vToDistributeKeys;
//一般地都是过量采集,所以这里预分配的空间大小是nfeatures*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);
//开始遍历图像网格,还是以行开始遍历的
for(int i=0; i=maxBorderY-3)
continue;
if(maxY>maxBorderY)
maxY = maxBorderY;
//开始列的遍历
for(int j=0; j=maxBorderX-6)
continue;
if(maxX>maxBorderX)
maxX = maxBorderX;
// FAST提取兴趣点, 自适应阈值
//这个向量存储这个cell中的特征点
vector vKeysCell;
//调用opencv的库函数来检测FAST角点
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), //待检测的图像,这里就是当前遍历到的图像块
vKeysCell, //存储角点位置的容器
iniThFAST, //检测阈值
true); //使能非极大值抑制
//如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
if(vKeysCell.empty())
{
//那么就使用更低的阈值来进行重新检测
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), //待检测的图像
vKeysCell, //存储角点位置的容器
minThFAST, //更低的检测阈值
true); //使能非极大值抑制
}
//当图像cell中检测到FAST角点的时候执行下面的语句
if(!vKeysCell.empty())
{
//遍历其中的所有FAST角点
for(vector::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
{
//这些角点的坐标都是基于图像cell的
//这样做是因为在下面使用八叉树法整理特征点的时候将会使用得到这个坐标
//在后面将会被继续转换成为在当前图层的扩充图像坐标系下的坐标
(*vit).pt.x+=j*wCell;
(*vit).pt.y+=i*hCell;
//然后将其加入到”等待被分配“的特征点容器中
vToDistributeKeys.push_back(*vit);
}//遍历图像cell中的所有的提取出来的FAST角点,并且恢复其在整个金字塔当前层图像下的坐标
}
}
}
//声明一个对当前图层的特征点的容器的引用
vector & keypoints = allKeypoints[level];
//并且调整其大小为欲提取出来的特征点个数(当然这里也是扩大了的,因为不可能所有的特征点都是在这一个图层中提取出来的)
keypoints.reserve(nfeatures);
// 根据mnFeatuvector & keypoints = allKeypoints[level];resPerLevel,即该层的兴趣点数,对特征点进行剔除
//返回值是一个保存有特征点的vector容器,含有剔除后的保留下来的特征点
//得到的特征点的坐标,依旧是在当前图层下来讲的
keypoints = DistributeOctTree(vToDistributeKeys, //当前图层提取出来的特征点,也即是等待剔除的特征点
//NOTICE 注意此时特征点所使用的坐标都是在“半径扩充图像”下的
minBorderX, maxBorderX, //当前图层图像的边界,而这里的坐标却都是在“边缘扩充图像”下的
minBorderY, maxBorderY,
mnFeaturesPerLevel[level], //希望保留下来的当前层图像的特征点个数
level); //当前层图像所在的图层
//PATCH_SIZE是对于底层的初始图像来说的,现在要根据当前图层的尺度缩放倍数进行缩放得到缩放后的PATCH大小 和特征点的方向计算有关
const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
// Add border to coordinates and scale information
//获取剔除过程后保留下来的特征点数目
const int nkps = keypoints.size();
//然后开始遍历这些特征点,恢复其在当前图层图像坐标系下的坐标
for(int i=0; i
opencv插值法:https://zhuanlan.zhihu.com/p/141681355
4.八叉树筛选特征点:
/**
* @brief 使用四叉树法对一个图像金字塔图层中的特征点进行平均和分发
*
* @param[in] vToDistributeKeys 等待进行分配到四叉树中的特征点
* @param[in] minX 当前图层的图像的边界,坐标都是在“半径扩充图像”坐标系下的坐标
* @param[in] maxX
* @param[in] minY
* @param[in] maxY
* @param[in] N 希望提取出的特征点个数
* @param[in] level 指定的金字塔图层,并未使用
* @return vector 已经均匀分散好的特征点vector容器
*/
vector ORBextractor::DistributeOctTree(const vector& vToDistributeKeys, const int &minX,
const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
{
// Compute how many initial nodes
// Step 1 根据宽高比确定初始节点数目
//计算应该生成的初始节点个数,根节点的数量nIni是根据边界的宽高比值确定的,一般是1或者2
// ! bug: 如果宽高比小于0.5,nIni=0, 后面hx会报错
const int nIni = round(static_cast(maxX-minX)/(maxY-minY));
if(nIni<1) nIni=1;//自加
//一个初始的节点的x方向有多少个像素
const float hX = static_cast(maxX-minX)/nIni;
//存储有提取器节点的链表
list lNodes;
//存储初始提取器节点指针的vector
vector vpIniNodes;
//重新设置其大小
vpIniNodes.resize(nIni);
// Step 2 生成初始提取器节点
for(int i=0; i(i),0); //UpLeft
ni.UR = cv::Point2i(hX*static_cast(i+1),0); //UpRight
ni.BL = cv::Point2i(ni.UL.x,maxY-minY); //BottomLeft
ni.BR = cv::Point2i(ni.UR.x,maxY-minY); //BottomRight
ni.vKeys.reserve(vToDistributeKeys.size());
//将刚才生成的提取节点添加到链表中
lNodes.push_back(ni);
//存储这个初始的提取器节点句柄
vpIniNodes[i] = &lNodes.back();
}
//Associate points to childs
// Step 3 将特征点分配到子提取器节点中
for(size_t i=0;ivKeys.push_back(kp);
}
// Step 4 遍历此提取器节点列表,标记那些不可再分裂的节点,删除那些没有分配到特征点的节点
list::iterator lit = lNodes.begin();
while(lit!=lNodes.end())
{
//如果初始的提取器节点所分配到的特征点个数为1
if(lit->vKeys.size()==1)
{
//那么就标志位置位,表示此节点不可再分
lit->bNoMore=true;
//更新迭代器
lit++;
}
///如果一个提取器节点没有被分配到特征点,那么就从列表中直接删除它
else if(lit->vKeys.empty())
lit = lNodes.erase(lit);
else
lit++;
}
//结束标志位
bool bFinish = false;
//记录迭代次数
int iteration = 0;
//声明一个vector用于存储节点的vSize和句柄对
//这个变量记录了在一次分裂循环中,那些可以再继续进行分裂的节点中包含的特征点数目和其句柄
vector > vSizeAndPointerToNode;
//调整大小,这里的意思是一个初始化节点将“分裂”成为四个
vSizeAndPointerToNode.reserve(lNodes.size()*4);
// Step 5 利用四叉树方法对图像进行划分区域,均匀分配特征点
while(!bFinish)
{
//更新迭代次数计数器
iteration++;
//保存当前节点个数
int prevSize = lNodes.size();
//重新定位迭代器指向列表头部
lit = lNodes.begin();
//需要展开的节点计数,这个一直保持累计,不清零
int nToExpand = 0;
//这个变量记录了在一次分裂循环中,那些可以再继续进行分裂的节点中包含的特征点数目和其句柄
vSizeAndPointerToNode.clear();
// 将目前的子区域进行划分
//开始遍历列表中所有的提取器节点,并进行分解或者保留
while(lit!=lNodes.end())
{
//如果提取器节点只有一个特征点,
if(lit->bNoMore)
{
// If node only contains one point do not subdivide and continue
lit++;
//跳过当前节点,继续下一个
continue;
}
else
{
// If more than one point, subdivide
//如果当前的提取器节点具有超过一个的特征点,那么就要进行继续分裂
ExtractorNode n1,n2,n3,n4;
//再细分成四个子区域
lit->DivideNode(n1,n2,n3,n4);
// Add childs if they contain points
//如果这里分出来的子区域中有特征点,那么就将这个子区域的节点添加到提取器节点的列表中
//注意这里的条件是,有特征点即可
if(n1.vKeys.size()>0)
{
//注意这里也是添加到列表前面的
lNodes.push_front(n1);
//再判断其中子提取器节点中的特征点数目是否大于1
if(n1.vKeys.size()>1)
{
//如果有超过一个的特征点,那么待展开的节点计数加1
nToExpand++;
//保存这个特征点数目和节点指针的信息
vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
// lNodes.front().lit 和前面的迭代的lit 不同,只是名字相同而已
// lNodes.front().lit是node结构体里的一个指针用来记录节点的位置
// 迭代的lit 是while循环里作者命名的遍历的指针名称
lNodes.front().lit = lNodes.begin();
}
}
//后面的操作都是相同的
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();
}
}
//当这个母节点expand之后就从列表中删除它了,能够进行分裂操作说明至少有一个子节点的区域中特征点的数量是>1的
// 分裂方式是后加的节点先分裂,先加的后分裂
lit=lNodes.erase(lit);
continue;
}
}
// Finish if there are more nodes than required features or all nodes contain just one point
//停止这个过程的条件有两个,满足其中一个即可:
if((int)lNodes.size()>=N //判断是否超过了要求的特征点数
|| (int)lNodes.size()==prevSize) //prevSize中保存的是分裂之前的节点个数,如果分裂之前和分裂之后的总节点个数一样,说明当前所有的
//节点区域中只有一个特征点,已经不能够再细分了
{
//停止标志置位
bFinish = true;
}
// Step 6 当再划分之后所有的Node数大于要求数目时,就慢慢划分直到使其刚刚达到或者超过要求的特征点个数
else if(((int)lNodes.size()+nToExpand*3)>N)
{
//如果再分裂一次那么数目就要超了,这里想办法尽可能使其刚刚达到或者超过要求的特征点个数时就退出
//这里的nToExpand和vSizeAndPointerToNode不是一次循环对一次循环的关系,而是前者是累计计数,后者只保存某一个循环的
//一直循环,直到结束标志位被置位
while(!bFinish)
{
//获取当前的list中的节点个数
prevSize = lNodes.size();
//保留那些还可以分裂的节点的信息, 这里是深拷贝
vector > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
//清空
vSizeAndPointerToNode.clear();
// 对需要划分的节点进行排序,对pair对的第一个元素进行排序,默认是从小到大排序
// 优先分裂特征点多的节点,使得特征点密集的区域保留更少的特征点
//! 注意这里的排序规则非常重要!会导致每次最后产生的特征点都不一样。建议使用 stable_sort
sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
//遍历这个存储了pair对的vector,注意是从后往前遍历
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的操作,所以前面才会备份vSizeAndPointerToNode中的数据
//为可能的、后续的又一次for循环做准备
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,如果不是那么就放心大胆地全部进行分裂(因为少了一个判断因此
//其运算速度会稍微快一些),如果会那么就引导到这里进行最后一次分裂
if((int)lNodes.size()>=N)
break;
}
//这里理想中应该是一个for循环就能够达成结束条件了,但是作者想的可能是,有些子节点所在的区域会没有特征点,因此很有可能一次for循环之后
//的数目还是不能够满足要求,所以还是需要判断结束条件并且再来一次
//判断是否达到了停止条件
if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
bFinish = true;
}
}
}
// Retain the best point in each node
// Step 7 保留每个区域响应值最大的一个兴趣点
//使用这个vector来存储我们感兴趣的特征点的过滤结果
vector vResultKeys;
//调整容器大小为要提取的特征点数目
vResultKeys.reserve(nfeatures);
//遍历这个节点链表
for(list::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
{
//得到这个节点区域中的特征点容器句柄
vector &vNodeKeys = lit->vKeys;
//得到指向第一个特征点的指针,后面作为最大响应值对应的关键点
cv::KeyPoint* pKP = &vNodeKeys[0];
//用第1个关键点响应值初始化最大响应值
float maxResponse = pKP->response;
//开始遍历这个节点区域中的特征点容器中的特征点,注意是从1开始哟,0已经用过了
for(size_t k=1;kmaxResponse)
{
//更新pKP指向具有最大响应值的keypoints
pKP = &vNodeKeys[k];
maxResponse = vNodeKeys[k].response;
}
}
//将这个节点区域中的响应值最大的特征点加入最终结果容器
vResultKeys.push_back(*pKP);
}
//返回最终结果容器,其中保存有分裂出来的区域中,我们最感兴趣、响应值最大的特征点
return vResultKeys;
}
下方为计算将区域1分为4:
void ExtractorNode::DivideNode(ExtractorNode &n1,
ExtractorNode &n2,
ExtractorNode &n3,
ExtractorNode &n4)
{
//得到当前提取器节点所在图像区域的一半长宽,当然结果需要取整
const int halfX = ceil(static_cast(UR.x-UL.x)/2);
const int halfY = ceil(static_cast(BR.y-UL.y)/2);
//Define boundaries of childs
//下面的操作大同小异,将一个图像区域再细分成为四个小图像区块
//n1 存储左上区域的边界
n1.UL = UL;
n1.UR = cv::Point2i(UL.x+halfX,UL.y);
n1.BL = cv::Point2i(UL.x,UL.y+halfY);
n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
//用来存储在该节点对应的图像网格中提取出来的特征点的vector
n1.vKeys.reserve(vKeys.size());
//n2 存储右上区域的边界
n2.UL = n1.UR;
n2.UR = UR;
n2.BL = n1.BR;
n2.BR = cv::Point2i(UR.x,UL.y+halfY);
n2.vKeys.reserve(vKeys.size());
//n3 存储左下区域的边界
n3.UL = n1.BL;
n3.UR = n1.BR;
n3.BL = BL;
n3.BR = cv::Point2i(n1.BR.x,BL.y);
n3.vKeys.reserve(vKeys.size());
//n4 存储右下区域的边界
n4.UL = n3.UR;
n4.UR = n2.BR;
n4.BL = n3.BR;
n4.BR = BR;
n4.vKeys.reserve(vKeys.size());
//Associate points to childs
//遍历当前提取器节点的vkeys中存储的特征点
for(size_t i=0;i
5.计算特征点方向
/**
* @brief 计算特征点的方向
* @param[in] image 特征点所在当前金字塔的图像
* @param[in & out] keypoints 特征点向量
* @param[in] umax 每个特征点所在图像区块的每行的边界 u_max 组成的vector
*/
static void computeOrientation(const Mat& image, vector& keypoints, const vector& umax)
{
// 遍历所有的特征点
for (vector::iterator keypoint = keypoints.begin(),
keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
{
// 调用IC_Angle 函数计算这个特征点的方向
keypoint->angle = IC_Angle(image, //特征点所在的图层的图像
keypoint->pt, //特征点在这张图像中的坐标
umax); //每个特征点所在图像区块的每行的边界 u_max 组成的vector
}
}
/**
* @brief 这个函数用于计算特征点的方向,这里是返回角度作为方向。
* 计算特征点方向是为了使得提取的特征点具有旋转不变性。
* 方法是灰度质心法:以几何中心和灰度质心的连线作为该特征点方向
* @param[in] image 要进行操作的某层金字塔图像
* @param[in] pt 当前特征点的坐标
* @param[in] u_max 图像块的每一行的坐标边界 u_max
* @return float 返回特征点的角度,范围为[0,360)角度,精度为0.3°
*/
static float IC_Angle(const Mat& image, Point2f pt, const vector & u_max)
{
//图像的矩,前者是按照图像块的y坐标加权,后者是按照图像块的x坐标加权
int m_01 = 0, m_10 = 0;
//获得这个特征点所在的图像块的中心点坐标灰度值的指针center
const uchar* center = &image.at (cvRound(pt.y), cvRound(pt.x));
// Treat the center line differently, v=0
//这条v=0中心线的计算需要特殊对待
//后面是以中心行为对称轴,成对遍历行数,所以PATCH_SIZE必须是奇数
for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
//注意这里的center下标u可以是负的!中心水平线上的像素按x坐标(也就是u坐标)加权
m_10 += u * center[u];
// Go line by line in the circular patch
//这里的step1表示这个图像一行包含的字节总数。
int step = (int)image.step1();
//注意这里是以v=0中心线为对称轴,然后对称地每成对的两行之间进行遍历,这样处理加快了计算速度
for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
{
// Proceed over the two lines
//本来m_01应该是一列一列地计算的,但是由于对称以及坐标x,y正负的原因,可以一次计算两行
int v_sum = 0;
// 获取某行像素横坐标的最大范围,注意这里的图像块是圆形的!
int d = u_max[v];
//在坐标范围内挨个像素遍历,实际是一次遍历2个
// 假设每次处理的两个点坐标,中心线下方为(x,y),中心线上方为(x,-y)
// 对于某次待处理的两个点:m_10 = Σ x*I(x,y) = x*I(x,y) + x*I(x,-y) = x*(I(x,y) + I(x,-y))
// 对于某次待处理的两个点:m_01 = Σ y*I(x,y) = y*I(x,y) - y*I(x,-y) = y*(I(x,y) - I(x,-y))
for (int u = -d; u <= d; ++u)
{
//得到需要进行加运算和减运算的像素灰度值
//val_plus:在中心线下方x=u时的的像素灰度值
//val_minus:在中心线上方x=u时的像素灰度值
int val_plus = center[u + v*step], val_minus = center[u - v*step];
//在v(y轴)上,2行所有像素灰度值之差
v_sum += (val_plus - val_minus);
//u轴(也就是x轴)方向上用u坐标加权和(u坐标也有正负符号),相当于同时计算两行
m_10 += u * (val_plus + val_minus);
}
//将这一行上的和按照y坐标加权
m_01 += v * v_sum;
}
//为了加快速度还使用了fastAtan2()函数,输出为[0,360)角度,精度为0.3°
return fastAtan2((float)m_01, (float)m_10);
}
///乘数因子,一度对应着多少弧度
const float factorPI = (float)(CV_PI/180.f);
关于灰度质心的数学描述,参见:https://zhuanlan.zhihu.com/p/481373935
6.计算描述子
首先用于计算描述子的pattern变量,pattern是用于计算描述子的256对坐标,其值写死在源码文件ORBextractor.cc里,在构造函数里做类型转换将其转换为const cv::Point*变量。
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)*/,
2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
-2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
-13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
-13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
-13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
-11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
-4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
-13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
-9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
-3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
-6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
节选
计算描述子的核心是在特征点周围的半径16一个圆里,选取256对点,每个点对比较得到一位,一共256位。
我们利用上面计算的特征点方向对256个点对进行旋转,因为对一个圆的像素进行旋转很麻烦。
/**
* @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(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
}
关于
#define GET_VALUE(idx) \
center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
cvRound(pattern[idx].x*a - pattern[idx].y*b)]
参见:#define第二种用法
https://docs.microsoft.com/en-us/cpp/preprocessor/hash-define-directive-c-cpp?view=msvc-170
此类定义也可见rgbdslam_v2:
rgbdslam_v2: aorb.cpp File Reference (ros.org)