orb-slam2程式碼總結(五)DBoW2詞袋模型
orb-slam在SearchByBoW()
函式中做特徵匹配時,用到詞袋模型BoW來加速匹配過程,不僅如此,在重定位和閉環檢測中,也要使用這個BoW,所以很有必要搞明白其原理.
1、視覺詞袋模型
特徵點是由興趣點和描述子表達的,把具有某一類特徵的特徵點放到一起就構成了一個單詞(word
),由所有這些單詞就可以構成字典(vocabulary
)了,有了字典之後,給定任意特徵,只要在字典中逐層查詢(使用的是漢明距離),最後就能找到與之對應的單詞了.
2、單詞的權重
每一類用該類中所有特徵的平均特徵(meanValue
)作為代表,稱為單詞(word
)。每個葉節點被賦予一個權重. 比較常用的一種權重是TF-IDF
- 如果某個詞或短語在一篇文章中出現的頻率
TF
高,並且在其他文章中很少出現,則認為此詞或者短語具有很好的類別區分能力,適合用來分類. TF-IDF
實際上是TF * IDF
,TF
代表詞頻(Term Frequency),表示詞條在文件d
中出現的頻率。IDF
代表逆向檔案頻率(Inverse Document Frequency)。如果包含詞條t
的文件越少,IDF
越大,表明詞條t
具有很好的類別區分能力.
DBoW2作者提供了TF
、IDF
、BINARY
、TF-IDF
等權重作為備選,預設為TF-IDF
.
2、構造離線詞典
orb-slam中的離線詞典就是那個比較大的檔案ORBvoc.txt
,它是DBoW2作者使用orb特徵,使用大量圖片訓練的結果.
2.1 儲存結構
對每一幅訓練影象,提取特徵點,將所有這些特徵點,通過對描述子(descriptors
)聚類的方法,如,k-means++,將其分成若干類(每一類即表示一個單詞),即實現聚類的過程,但是由於我們使用的描述子是256維的,那麼這個類別(單詞)數量不能太小(不然造成誤匹配),至少是成千上萬,那麼這就帶來一個查詢效率問題,O(N)
肯定是不行了,所以視覺BoW一般使用樹的結構進行儲存(以空間換時間唄),時間效率將達到log(N)
級別.
2.2 聚類實現
由於單詞過多,需要提高查詢效率,簡單的方法是進行二分法、N叉樹等,使用k叉樹,深度為d,一共可以構成個單詞,聚類過程如下:
- 從訓練影象中抽取特徵
- 將抽取的特徵用 k-means++ 演算法聚類(使用漢明距離),將描述子空間劃分成 k 類
- 將劃分的每個子空間,繼續利用 k-means++ 演算法做聚類
- 重複次上述過程,將描述子建立成樹形結構,如下圖所示
3、影象識別
3.1 查詢
離線生成視覺詞典以後,在slam過程中(相對於離線,這裡也叫,線上查詢),對一新進來的影象幀,將其中每個特徵點都從單詞樹根節點往下遍歷,取漢明距離最小的節點接著往下遍歷直到葉節點,就可以找到位於葉子節點的單詞了.
為了查詢方便,DBoW2使用了兩種資料結構,逆向索引inverse index
和正向索引direct index
.
使用下面的程式碼,計算詞包mBowVec
和mFeatVec
,其中mFeatVec
記錄了在第4
層所有node節點正向索引.
void Frame::ComputeBoW()
{
if(mBowVec.empty())
{
vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4); //第四層
}
}
3.1 正向索引,用於加速匹配
正向索引的資料結構如下,繼承自std::map
,NodeId
為第4
層上node節點的編號,其範圍在內,表示當前層數(這裡以最上層為0層),std::vector<unsigned int>
是所有經過該node節點特徵編號集合
/// Vector of nodes with indexes of local features
class FeatureVector: public std::map<NodeId, std::vector<unsigned int> >
TrackReferenceKeyFrame() 函式中的 SearchByBoW() 對pKF和F中屬於同一node的特徵點,進行快速匹配. 過程如下:
DBoW2::FeatureVector::const_iterator KFit = vFeatVecKF.begin();
DBoW2::FeatureVector::const_iterator Fit = F.mFeatVec.begin();
DBoW2::FeatureVector::const_iterator KFend = vFeatVecKF.end();
DBoW2::FeatureVector::const_iterator Fend = F.mFeatVec.end();
while(KFit != KFend && Fit != Fend)
{
/*【步驟1】: 分別取出屬於同一node的ORB特徵點(只有屬於同一node,才有可能是匹配點)*/
if(KFit->first == Fit->first)
{
const vector<unsigned int> vIndicesKF = KFit->second;
const vector<unsigned int> vIndicesF = Fit->second;
/*【步驟2】: 遍歷KF中屬於該node的特徵點*/
for(size_t iKF=0; iKF<vIndicesKF.size(); iKF++)
{
const unsigned int realIdxKF = vIndicesKF[iKF];
MapPoint* pMP = vpMapPointsKF[realIdxKF]; // 取出KF中該特徵對應的MapPoint
......
這種加速特徵匹配的方法在ORB-SLAM2中被大量使用。注意到,
- 正向索引的層數如果選擇第
0
層(根節點),那麼時間複雜度和暴力搜尋一樣 - 如果是葉節點層,則搜尋範圍有可能太小,錯失正確的特徵點匹配
- 作者一般選擇第二層或者第三層作為父節點(
L=6
),正向索引的複雜度約為O(N^2/K^m)
3.2 逆向索引,用於迴環和重定位
作者用反向索引記錄每個葉節點對應的影象編號。當識別影象時,根據反向索引選出有著公共葉節點的備選影象並計算得分,而不需要計算與所有影象的得分。
- 為影象生成一個表徵向量,影象中的每個特徵都在詞典中搜索其最近鄰的葉節點。所有葉節點上的
TF-IDF
權重集合構成了BoW向量 - 根據BoW向量,計算當前影象和其它影象之間的範數,有了距離定義,即可根據距離大小選取合適的備選影象
使用詞袋模型,在重定位過程中找出和當前幀具有公共單詞的所有關鍵幀,程式碼如下:
// words是檢測影象是否匹配的樞紐,遍歷該pKF的每一個word
for(DBoW2::BowVector::const_iterator vit=F->mBowVec.begin(), vend=F->mBowVec.end(); vit != vend; vit++)
{
// 提取所有包含該word的KeyFrame
list<KeyFrame*> &lKFs = mvInvertedFile[vit->first];
for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
{
KeyFrame* pKFi=*lit;
if(pKFi->mnRelocQuery!=F->mnId)// pKFi還沒有標記為pKF的候選幀
{
pKFi->mnRelocWords=0;
pKFi->mnRelocQuery=F->mnId;
lKFsSharingWords.push_back(pKFi);
}
pKFi->mnRelocWords++;
}
}
@todo
未完待續
<完>
@leatherwang