# ORBextractor.cpp
### ORBextractor::ORBextractor()
構建ORB特徵提取器 [知識點1]
在[Tracking::Tracking()](#Tracking::Tracking())中引用
#### 定義
```
ORBextractor::ORBextractor(int _nfeatures, //提取的特徵點數目
float _scaleFactor, //金字塔縮放係數
int _nlevels, //金字塔層數
int _iniThFAST, //提取fast特徵點的默認閾值
int _minThFAST) //如果使用iniThFAST默認閾值提取不到特徵點則使用最小閾值再次提取
```
#### 函式流程
1. 建構圖像金字塔的縮放相關變數 [知識點3]
2. 逐層分配特徵點數量 [知識點3]
3. 建立描述子模板 [知識點2]
4. 構建灰度質心計算範圍公式 [知識點3]
#### 知識點
1. FAST特徵點(Features from Accelerated Segments Test)
ORB特徵檢測的第一步是查找圖像中的關鍵點,這一步驟中使用的是FAST算法。

FAST是Features from Accelerated Segments Test 的簡稱,可以快速選擇關鍵點,算法步驟如下:
* 選取像素p,假設它的亮度為Ip
* 設置一個閾值T(比如Ip的20%)
* 以像素p為中心,選取半徑為3的圓上的16個像素點
* 假如選取的圓上,有連續的N個點的亮度大於Ip+T或小於Ip-T,那麼像素p可以被認為是特徵點
* 循環以上4步,對每一個像素執行相同操作
2. BRIEF描述子(Binary Robust Independent Elementary Features)
BRIEF算法的核心思想是在關鍵點P的周圍以一定模式選取N個點對,把這N個點對的比較結果組合起來作為描述子,每個描述符是僅包含1和0的特徵向量。每個關鍵點由一個二進制特徵向量描述,該向量一般為128-512位的字符串,其中僅包含1和0。


BRIEF算法生成特徵描述符的具體步驟如下:
* 首先利用高斯核對給定圖像進行平滑處理,以防描述符對高頻噪點過於敏感。.
* 然後對於給定關鍵點(綠點),以該關鍵點為中心的高斯分佈中抽取一個像素,將該點稱作關鍵點的一號點(藍點),標準差為σ。

* 以一號點為中心的高斯分佈中抽取一個像素,將該點稱作關鍵點的二號點(黃點),標準差為σ/2(這麼取是因為經驗表明這種選擇提高了特徵匹配率)。
* 為關鍵點構建二進制特徵描述符,方法是比較 2.和 3.得到的一號點和二號點的灰度值。如果一號點比二號點亮,則為描述符中的相應位分配值1,否則分配值0。
* 然後針對同一關鍵點選擇新的一號點和二號點,比較它們的灰度並為特徵向量中的下個位分配1或0。(即跳轉到2.重複循環)
* 對於設定的生成不同維度的具體程序,BRIEF算法會重複2.~4.對應次數,產生指定長度的特徵描述符。並對每一特徵點重複以上算法。
3. 縮放不變性及旋轉不變性的改進
BRIEF 算法可以生成二進制特徵描述符,但並不滿足圖像的縮放旋轉不變性,故不能直接用於要求較高的圖像匹配中,為克服這一缺點,將BRIEF作改進。
* 縮放不變性
為使特徵滿足縮放不變性,BRIEF算法構建圖像金字塔。

這是一個包含5個級別的圖形金字塔示例,在每個級別圖像都以1/2的比例下採樣。
ORB創建好圖像金字塔後,會使用FAST算法從每個級別不同大小的圖像中快速找到關鍵點。因為金字塔的每個級別由原始圖像的更小版本組成,因此原始圖像中的任何對像在金字塔的每個級別也會降低大小。

通過確定每個級別的關鍵點ORB 能夠有效發現不同尺寸的對象的關鍵點,這樣的話ORB 實現了部分縮放不變性。
* 旋轉不變性
原始的FAST關鍵點沒有方向信息,這樣當圖像發生旋轉後,brief描述子也會發生變化,使得特徵點對旋轉不魯棒,因此使用灰度質心法來計算特徵點的方向,而灰度質心法會在一個圓的範圍內計算灰度的質心。
m00為區域內灰度值的總和:

m10及m01分別為區域內沿著x軸及y軸的灰度值總和:

質心即為:

關鍵點的方向就可以表示為圓心O指向質心C的方向向量OC,因此關鍵點的旋轉角度為:

#### 流程詳解
1. 建構圖像金字塔的縮放相關變數
```
//按照金字塔層數初始化縮放相關變數
mvScaleFactor.resize(nlevels);
mvLevelSigma2.resize(nlevels);
//初始縮放係數為1
mvScaleFactor[0]=1.0f;
mvLevelSigma2[0]=1.0f;
//建構每一層的縮放係數
for(int i=1; i<nlevels; i++)
{
mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
mvLevelSigma2[i]=mvScaleFactor[i]*mvScaleFactor[i];
}
//縮放係數的倒數
mvInvScaleFactor.resize(nlevels);
mvInvLevelSigma2.resize(nlevels);
for(int i=0; i<nlevels; i++)
{
mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
}
```
2. 逐層分配特徵點數量
```
// 總共期望提取nfeatures個特徵點,根據尺度因子等比數列,計算出金字塔最底層期望提取的特徵點個數
float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
// 根據尺度因子計算金字塔每一層期望提取的特徵點個數(越往上提取的特徵點個數越少)
int sumFeatures = 0;
for( int level = 0; level < nlevels-1; level++ )
{
mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
sumFeatures += mnFeaturesPerLevel[level];
nDesiredFeaturesPerScale *= factor;
}
//最後一層為所有特徵點減去前面所有層的特徵點
mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
```
3. 建立描述子模板
```
//下面的 bit_pattern_31_ 宣告為
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)*/,
...
}
//是用來給描述子的點對取座標用的
```
```
//總共512個點對
const int npoints = 512;
//獲取用於計算BRIEF描述子的隨機採樣點指標
const Point* pattern0 = (const Point*)bit_pattern_31_;
//從pattern0到pattern0+npoints段的點以cv::point格式複製到當前類對像中的變數pattern中
std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
```
4. 構建灰度質心計算範圍公式
```
umax.resize(HALF_PATCH_SIZE + 1);
//v是y軸的數值 , vmax是圓的y軸的45度角的值+1(1的目的是與vmin為不同點,這裡vmax與vmin試是根據45度角區分的兩個點)
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;
//計算在45度角前圓的x軸的
for (v = 0; v <= vmax; ++v)
umax[v] = cvRound(sqrt(hp2 - v * v));
// 由於前面有四捨五入,不能直接計算,因此根據45度角前計算的結果計算45度後的數值
for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
{
while (umax[v0] == umax[v0 + 1])
++v0;
umax[v] = v0;
++v0;
}
```
### ORBextractor::operator()
建構ORB仿函數
在[Frame::ExtractORB()](#Frame::ExtractORB())中引用
#### 定義
```
void ORBextractor:: ()( InputArray _image, //輸入影像
InputArray _mask, //輔助影像處理的遮罩
vector<KeyPoint>& _keypoints, //特徵點
OutputArray _descriptors) //輸出的描述子
```
#### 函式流程
1. 構建影像金字塔
2. 提取特徵點
3. 計算描述子
#### 流程詳解
1. 構建影像金字塔
```
ComputePyramid(image);
```
跳至[ORBextractor::ComputePyramid](#ORBextractor::ComputePyramid)
2. 提取特徵點
```
vector < vector<KeyPoint> > allKeypoints; // vector<vector<KeyPoint>>
ComputeKeyPointsOctTree(allKeypoints);
```
跳至[ORBextractor::ComputeKeyPointsOctTree](#ORBextractor::ComputeKeyPointsOctTree)
3. 計算描述子
```
Mat descriptors;
//儲存特徵點數量
int nkeypoints = 0;
//算特徵點總數
for (int level = 0; level < nlevels; ++level)
nkeypoints += (int)allKeypoints[level].size();
//如果沒有特徵點
if( nkeypoints == 0 )
_descriptors.release();
else
{
//建立描述子
_descriptors.create(nkeypoints, 32, CV_8U);
descriptors = _descriptors.getMat(); //將OutputArray數據轉換成Mat類型
}
_keypoints.clear();
_keypoints.reserve(nkeypoints);
int offset = 0;
//遍歷特徵金字塔每一層
for (int level = 0; level < nlevels; ++level)
{
//當前層的特徵點
vector<KeyPoint>& keypoints = allKeypoints[level];
int nkeypointsLevel = (int)keypoints.size();
//當前層的特徵點為0就跳出這層
if(nkeypointsLevel==0)
continue;
// preprocess the resized image
Mat workingMat = mvImagePyramid[level].clone();
//做高斯模糊,目的是將一些小雜訊剃除,保留影像中大的特徵
GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
// Compute the descriptors
Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
//計算描述子
computeDescriptors(workingMat, //高斯模糊後的影像
keypoints, //當前層的特徵點集合
desc, //輸出的特徵點
pattern); //隨機採樣的模板
//更新偏移量
offset += nkeypointsLevel;
// Scale keypoint coordinates
//將非第0層的特徵點轉換到原影像座標下
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.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
}
```
跳至 [computeDescriptors()](#computeDescriptors())
### ORBextractor::ComputePyramid()
構建影像金字塔
在[ORBextractor::operator()](#ORBextractor::operator())引用
#### 定義
```
void ORBextractor::ComputePyramid(cv::Mat image //輸入影像
)
```
#### 函式流程
1. 遍歷所有金字塔層數
2. 構建影像金字塔
#### 流程詳解
1. 遍歷所有金字塔層數
```
for (int level = 0; level < nlevels; ++level)
{
```
2. 構建影像金字塔
```
//該層縮放係數
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(wholeSize, image.type()), masktemp;
//構建影像金字塔
mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
if( level != 0 )
{
resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, cv::INTER_LINEAR);
//把原影像複製到輸出影像的中央,四邊填充(給高斯濾波用的)
copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
BORDER_REFLECT_101+BORDER_ISOLATED);
}
else
{
copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
BORDER_REFLECT_101);
}
```
### ORBextractor::ComputeKeyPointsOctTree
使用ORB提取特徵,用八叉樹演算法分配特徵點,並用灰度質心法計算特徵方向。
在[ORBextractor::operator()](#ORBextractor::operator())中使用
#### 定義
```
void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint>>& allKeypoints //輸出的特徵點(有兩層vector,第一層為單層特徵點,第二層為整個金字塔的特徵點)
)
```
#### 函式流程
1. 遍歷金字塔每一層
2. 設定當層變數
3. 對每一個八叉樹網格遍歷行
4. 對每一個八叉樹網格遍歷列
5. 提取FAST關鍵點
6. 將特徵點座標從網格恢復到整張影像
7. 計算八叉樹
8. 計算特徵點方向
#### 流程詳解
1. 遍歷金字塔每一層
```
//根據層數resize大小
allKeypoints.resize(nlevels);
//八叉樹單元的大小
const float W = 30;
for (int level = 0; level < nlevels; ++level)
{
```
2. 設定當層變數
```
//計算當層影像的邊界
const int minBorderX = EDGE_THRESHOLD-3; //3為在邊界時計算特徵點會超出的範圍
const int minBorderY = minBorderX;
const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
//要平均分配的特徵點
vector<cv::KeyPoint> vToDistributeKeys;
//預先分配10倍nfeatures大小
vToDistributeKeys.reserve(nfeatures*10); //nfeatures為目標提取的特徵點數量
//提取特徵點區域的大小
const float width = (maxBorderX-minBorderX);
const float height = (maxBorderY-minBorderY);
// 每個八叉樹區域塊的大小為W*W,將圖像劃分為(nRows*nCols)個區域,在無法整除的情況下,調整每個區域大小為(wCell*hCell)
const int nCols = width/W;
const int nRows = height/W;
const int wCell = ceil(width/nCols);
const int hCell = ceil(height/nRows);
```
3. 對每一個八叉樹網格遍歷行
```
for(int i=0; i<nRows; i++)
{
//計算網格Y座標
const float iniY =minBorderY+i*hCell;
float maxY = iniY+hCell+6; //左右邊界各+3
//邊界檢測
if(iniY>=maxBorderY-3)
continue;
if(maxY>maxBorderY)
maxY = maxBorderY;
```
4. 對每一個八叉樹網格遍歷列
```
for(int j=0; j<nCols; j++)
{
//計算網格X座標
const float iniX =minBorderX+j*wCell;
float maxX = iniX+wCell+6; //左右邊界各+3
//邊界檢測
if(iniX>=maxBorderX-6)
continue;
if(maxX>maxBorderX)
maxX = maxBorderX;
```
5. 提取FAST關鍵點
```
//儲存當前網格特徵點
vector<cv::KeyPoint> vKeysCell;
//FAST()特徵檢測定義於 opencv/modules/features2d/src/fast.cpp
//在(iniX, iniY)(maxX, maxY)範圍內提取FAST關鍵點, 並開啟非極大值抑制(防止在一個很小的區域內提取過多的特徵點)
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), //輸入的影像
vKeysCell, //輸出特徵點的vector
iniThFAST, //檢測閾值
true); //使用NMS非極大值抑制
//如果使用默認閾值提取不到特徵點則使用最小閾值minThFAST再次提取
if(vKeysCell.empty())
{
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),vKeysCell,minThFAST,true);
}
```
6. 將特徵點座標從網格恢復到整張影像
```
//當有偵測到特徵點時
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.push_back(*vit);
}
}
```
7. 計算八叉樹
```
vector<KeyPoint> & keypoints = allKeypoints[level];
keypoints.reserve(nfeatures);
// 根據mnFeaturesPerLevel,即該層的興趣點數,對特徵點進行剔除
keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
// Add border to coordinates and scale information
const int nkps = keypoints.size();
//記錄關鍵點在圖片實際坐標(包含邊界),記錄該金字塔level
for(int i=0; i<nkps ; i++)
{
keypoints[i].pt.x+=minBorderX;
keypoints[i].pt.y+=minBorderY;
keypoints[i].octave=level;
keypoints[i].size = scaledPatchSize;
}
```
跳到[ORBextractor::DistributeOctTree](#ORBextractor::DistributeOctTree)
8. 計算特徵點方向
```
for (int level = 0; level < nlevels; ++level)
computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
```
跳至ORBextractor.cpp裡的 [computeOrientation()](#computeOrientation())
### ORBextractor::DistributeOctTree
將特徵點進行平均分配跟剃除 [知識點1]
#### 定義
```
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 //金字塔層樹
)
```
#### 函式流程
1. 根據寬高比確定初始節點數目
2. 遍歷每個節點並生成初始提取器節點
3. 根據座標將特徵點分配到子提取器中
4. 標記及刪除節點
5. 分割節點
6. 接近分割完的時候就慢慢分割
7. 保留各節點響應值最高的特徵點,避免造成重複的特徵點被計算
8. 返回特徵點列表
#### 知識點
1. 八叉樹演算法

#### 流程詳解
1. 根據寬高比確定初始節點數目
```
//初始節點數目 (只是根據長寬比隨便給的,通常為1或2)
const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY)); //static_cast<float>為轉型成float?
// 一個初始的節點的x方向有多少個像素
const float hX = static_cast<float>(maxX-minX)/nIni;
//儲存節點的list
list<ExtractorNode> lNodes;
//儲存指向節點的vector
vector<ExtractorNode*> vpIniNodes;
//假設初始節點數目為2,就將vector size定為2
vpIniNodes.resize(nIni);
```
2. 遍歷每個節點並生成初始提取器節點
```
//遍歷每個節點
for(int i=0; i<lNodes; i++)
{
ExtractorNode ni; // 生成一個提取器節點
// 設置提取器節點的圖像邊界
ni.UL = cv::Point2i(hX*static_cast<float>(i),0);
ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
//用來保存有當前節點的特徵點
ni.vKeys.reserve(vToDistributeKeys.size());
lNodes.push_back(ni);
//將最新push的node傳給vpIniNodes
vpIniNodes[i] = &lNodes.back();
}
```
3. 根據座標將特徵點分配到子提取器中
```
//遍歷每個特徵點
for(size_t i=0;i<vToDistributeKeys.size();i++)
{
const cv::KeyPoint &kp = vToDistributeKeys[i]; //每個特徵點
// 按特徵點的橫軸位置,分配給屬於那個圖像區域的提取器節點(最初的提取器節點)
vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
}
```
4. 標記及刪除節點
```
list<ExtractorNode>::iterator lit = lNodes.begin();
//遍歷此提取器節點列表
while(lit!=lNodes.end())
{
if(lit->vKeys.size()==1) //如果提取器節點所分配到的特徵點個數為1
{
lit->bNoMore=true; // 標誌此位置,表示此節點不可再分割
lit++;
}
else if(lit->vKeys.empty()) //如果提取器節點沒有分配到特徵點
lit = lNodes.erase(lit);//刪除節點
else
lit++;
}
```
5. 分割節點
```
bool bFinish = false;
int iteration = 0;
//聲明一個vector用於存儲節點的vSize和句柄對
//這個變量記錄了在一次分裂循環中,那些可以再繼續進行分裂的節點中包含的特徵點數目和其句柄
vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
vSizeAndPointerToNode.reserve(lNodes.size()*4);
while(!bFinish)
{
iteration++;
int prevSize = lNodes.size(); //當前節點個數
lit = lNodes.begin(); //迭代器指向list頭部
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);
if(n1.vKeys.size()>1)
{
nToExpand++;
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)
{
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=lNodes.erase(lit); // 當這個母節點分裂後就從列表中刪除它了
continue;
}
}
```
lit->DivideNode(n1,n2,n3,n4): 跳至[ExtractorNode::DivideNode](#ExtractorNode::DivideNode)
6. 接近分割完的時候就慢慢分割
```
//當滿足以下條件時,便標記為完成
if((int)lNodes.size()>=N || //當特徵點數量大於指定數量
(int)lNodes.size()==prevSize //無法再分割節點
)
{
bFinish = true;
}
//當再分割一次特徵點數量就會超過指定數量時,便慢慢分割
else if(((int)lNodes.size()+nToExpand*3)>N)
{
//當為完成分割時
while(!bFinish)
{
//獲得節點數量
prevSize = lNodes.size();
//儲存還可以分割的節點
vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
vSizeAndPointerToNode.clear();
//根據待分裂節點的特徵點數量大小來由小到大排序(之後是由大到小取用,比較多特徵點的比較好用)。
sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
{
ExtractorNode n1,n2,n3,n4;
vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4); // second其實就是pair中第二個元素,也就是節點
// 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);
if((int)lNodes.size()>=N)
break;
}
if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
bFinish = true;
}
}
```
7. 保留各節點響應值最高的特徵點,避免造成重複的特徵點被計算
```
//儲存最終結果
vector<cv::KeyPoint> vResultKeys;
vResultKeys.reserve(nfeatures);
//遍歷所有結點
for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
{
//獲取此結點下的特徵點
vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
//此結點下指向第一個特徵點的指標
cv::KeyPoint* pKP = &vNodeKeys[0];
//初始化最大響應值
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.push_back(*pKP);
}
```
8. 返回特徵點列表
```
return vResultKeys;
```
### ExtractorNode::DivideNode()
#### 定義
```
void ExtractorNode::DivideNode(ExtractorNode &n1, //輸出的四個節點
ExtractorNode &n2,
ExtractorNode &n3,
ExtractorNode &n4
)
```
#### 函式流程
1. 計算新節點們的邊界
2. 將特徵點分配到新節點們裡面
3. 確認新節點們是否不可再被分割
#### 流程詳解
1. 計算新節點們的邊界
```
const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);
//Define boundaries of childs
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);
n1.vKeys.reserve(vKeys.size());
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.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.UL = n3.UR;
n4.UR = n2.BR;
n4.BL = n3.BR;
n4.BR = BR;
n4.vKeys.reserve(vKeys.size());
```
2. 將特徵點分配到新節點們裡面
```
for(size_t i=0;i<vKeys.size();i++)
{
const cv::KeyPoint &kp = vKeys[i];
if(kp.pt.x<n1.UR.x)
{
if(kp.pt.y<n1.BR.y)
n1.vKeys.push_back(kp);
else
n3.vKeys.push_back(kp);
}
else if(kp.pt.y<n1.BR.y)
n2.vKeys.push_back(kp);
else
n4.vKeys.push_back(kp);
}
```
3. 確認新節點們是否不可再被分割
```
if(n1.vKeys.size()==1)
n1.bNoMore = true;
if(n2.vKeys.size()==1)
n2.bNoMore = true;
if(n3.vKeys.size()==1)
n3.bNoMore = true;
if(n4.vKeys.size()==1)
n4.bNoMore = true;
```
### computeOrientation()
計算特徵點方向
#### 定義
```
static void computeOrientation(const Mat& image, //當前層的影像
vector<KeyPoint>& keypoints, //特徵點向量
const vector<int>& umax) //每個特徵點計算用的區域邊界
```
#### 函式流程
1. 針對每一個特徵點分別計算方向
#### 函式詳解
1. 針對每一個特徵點分別計算方向
```
for (vector<KeyPoint>::iterator keypoint = keypoints.begin(), keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
{
keypoint->angle = IC_Angle(image, keypoint->pt, umax);
}
```
跳至ORBextractor.cpp裡的 [IC_Angle()](#IC_Angle())
### IC_Angle()
使用灰度質心法:以幾何中心和灰度質心的連線作為該特徵點方向(回顧[ORBextractor::ORBextractor()旋轉不變性](#ORBextractor::ORBextractor()))。
#### 定義
```
static float IC_Angle(const Mat& image, //輸入影像
Point2f pt, //輸入的此特徵點座標
const vector<int> & u_max) //每一行的座標邊界
```
#### 函式流程

1. 計算Y軸為0的灰度總和
為上圖的紅線區域
#### 函式詳解
1. 計算Y軸為0的X方向灰度總和
```
int m_01 = 0, m_10 = 0;
//特徵點座標的灰度值
const uchar* center = &image.at<uchar> (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)
m_10 += u * center[u];
```
2. 計算Y方向與X方向灰度總和
```
//每一行的像素數量
int step = (int)image.step1();
//遍歷Y軸方向
for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
{
// Proceed over the two lines
int v_sum = 0;
//X方向的範圍
int d = u_max[v];
//遍歷X方向,從-d~d
for (int u = -d; u <= d; ++u)
{
//val_plus為(x,y)的灰度值,val_minus為(x,-y)的灰度值
int val_plus = center[u + v*step], val_minus = center[u - v*step];
// Y方向灰度值相加,由於y1 + (-y2) = y1 - y2
v_sum += (val_plus - val_minus);
// X方向灰度值相加 * u
m_10 += u * (val_plus + val_minus);
}
// Y方向灰度值 * v
m_01 += v * v_sum;
}
```
3. 計算角度
```
return fastAtan2((float)m_01, (float)m_10);
```
### computeDescriptors()
計算描述子
在[ORBextractor::operator()](#ORBextractor::operator())引用
#### 定義
```
static void computeDescriptors(const Mat& image, //高斯模糊後的影像
vector<KeyPoint>& keypoints, //當前層的特徵點集合
Mat& descriptors, //輸出的特徵點
const vector<Point>& pattern) //事先定義好的隨機採樣的模板
```
#### 函式流程
1. 對所有特徵點分別計算描述子
#### 函式詳解
1. 對所有特徵點分別計算描述子
```
//儲存描述子
descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);
//遍歷特徵點
for (size_t i = 0; i < keypoints.size(); i++)
computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i)); //計算當前特徵點的描述子
```
跳至 [computeOrbDescriptor()](#computeOrbDescriptor())
### computeOrbDescriptor()
計算單個特徵點的描述子
在[computeDescriptors()](#computeDescriptors())引用
#### 定義
```
static void computeOrbDescriptor(const KeyPoint& kpt, //輸入特徵點
const Mat& img, //輸入影像
const Point* pattern, //對應此特徵點的隨機採樣
uchar* desc) //輸出計算好的描述子
```
#### 函式流程
1. 計算特徵點旋轉矩陣 [知識點1]
2. 計算所有點對的描述子並組合起來
#### 知識點
1. 旋轉矩陣
假設要將點v(x,y)旋轉至點v'(x',y')。

公式為:

旋轉矩陣就為:

#### 函式詳解
1. 計算特徵點旋轉矩陣
```
const float factorPI = (float)(CV_PI/180.f);
//將特徵點的角度轉成弧度,[0,360] -> [0,2pi]
float angle = (float)kpt.angle*factorPI;
//計算sin(),cos()
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;
//旋轉矩陣
#define GET_VALUE(idx) \
center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
cvRound(pattern[idx].x*a - pattern[idx].y*b)]
```
2. 計算所有點對的描述子並組合起來
```
//每個描述子都有32*8位元
//遍歷所有隨機點對;pattern+16為一次處理8個點對,也就是16個點;總共32次
for (int i = 0; i < 32; ++i, pattern += 16)
{
int t0, t1, val;
t0 = GET_VALUE(0); t1 = GET_VALUE(1);
val = t0 < t1; //bit 0
t0 = GET_VALUE(2); t1 = GET_VALUE(3);
val |= (t0 < t1) << 1; //bit 1
t0 = GET_VALUE(4); t1 = GET_VALUE(5);
val |= (t0 < t1) << 2; //bit 2
t0 = GET_VALUE(6); t1 = GET_VALUE(7);
val |= (t0 < t1) << 3; //bit 3
t0 = GET_VALUE(8); t1 = GET_VALUE(9);
val |= (t0 < t1) << 4; //bit 4
t0 = GET_VALUE(10); t1 = GET_VALUE(11);
val |= (t0 < t1) << 5; //bit 5
t0 = GET_VALUE(12); t1 = GET_VALUE(13);
val |= (t0 < t1) << 6; //bit 6
t0 = GET_VALUE(14); t1 = GET_VALUE(15);
val |= (t0 < t1) << 7; //bit 7
//儲存描述子
desc[i] = (uchar)val;
}
//使用完後取消這個define
#undef GET_VALUE
```