基于视觉的闭环检测可以描述为,给定一张输入图像,在历史图像数据库中高效准确地搜索出与之相似的图像。而通常的穷举搜索法效率低下,类帧差法受制于图像视角变化、光照变化、曝光等因素无法稳定识别相似图像。 词袋模型可以解决上述问题,其基于大量图像数据事先训练词袋字典,字典中包含各类图像特征,在实际应用时将输入图像和历史图像转化为几何特征集合进行相似度对比,这一方式更为符合人类的认知方式;通过设计特定的描述子实现特征的稳定提取,利用直接索引和倒排索引实现图像的快速搜索。
- 论文:Gálvez-López D, Tardos J D. Bags of binary words for fast place recognition in image sequences[J]. IEEE Transactions on Robotics, 2012, 28(5): 1188-1197.
- 源码:
图一 词袋模型对图像的解读方式
1.离线词袋字典生成
图像首先提取ORB 特征点,将描述子通过 k-means 进行聚类,根据设定的树的分支数和深度,从根节点一直聚类到叶子节点,得到一个 vocabulary tree,图二展示了分支数为3,深度为4的词袋字典。
- 遍历所有的训练图像,对每幅图像提取ORB特征点。
- 设定vocabulary tree的分支数K和深度L。将特征点的每个描述子用 K-means聚类,变成 K个集合,作为vocabulary tree 的第1层级,然后对每个集合重复该聚类操作,就得到了vocabulary tree的第2层级,继续迭代最后得到满足条件的vocabulary tree,它的规模通常比较大,比如ORB-SLAM2使用的离线字典就有108万+ 个节点。
- 离根节点最远的一层节点称为叶子节点或者单词 Word,对每个单词均会计算一个节点权重(见权重计算部分,权重=节点权重*在线权重)。
相关参数说明: 单词数:
K
L
{K^L}
KL 节点数:
K
L
+
1
K
?
1
\frac {K^{L+1}}{K-1}
K?1KL+1?
图二 分支数为3,深度为4的词袋字典
ORB-SLAM中的词典格式片段
10 6 0 0
0 0 252 188 188 242 169 109 85 143 187 191 164 25 222 255 72 27 129 215 237 16 58 111 219 51 219 211 85 127 192 112 134 34 0
0 0 93 125 221 103 180 14 111 184 112 234 255 76 215 115 153 115 22 196 124 110 233 240 249 46 237 239 101 20 104 243 66 33 0
0 0 58 185 58 250 93 221 82 239 143 13 252 9 46 221 102 16 200 187 215 80 78 43 250 245 251 221 0 123 83 14 238 202 0
0 0 193 156 191 245 160 238 61 55 190 251 86 116 253 55 128 123 167 119 127 8 177 220 179 103 205 255 126 192 136 192 129 121 0
0 0 61 101 105 111 84 95 79 248 85 224 253 10 83 89 157 48 88 204 22 234 201 178 125 190 119 205 165 52 119 187 82 224 0
0 0 10 188 178 154 255 245 184 199 159 95 92 183 172 254 102 204 239 59 191 145 182 75 178 243 31 87 158 235 150 76 173 223 0
0 0 27 223 99 205 118 146 239 117 93 72 94 230 121 206 182 100 126 171 23 237 197 184 37 255 54 109 170 128 63 142 113 253 0
0 0 222 95 254 254 47 86 127 248 189 206 214 167 111 255 55 83 254 245 255 231 236 199 171 238 243 251 239 147 39 247 45 83 0
0 0 111 180 240 83 253 127 254 218 123 255 61 60 202 252 223 190 159 206 247 30 183 114 255 242 63 95 85 255 199 255 222 247 0
0 0 2 205 6 159 220 131 174 239 30 1 218 2 224 234 48 64 121 235 59 193 114 187 11 255 60 38 143 64 21 90 177 136 0
1 0 244 52 157 119 168 111 85 154 178 187 167 24 215 115 73 27 129 214 108 58 56 101 219 2 201 243 117 60 192 113 198 34 0
1 0 236 180 188 250 173 109 81 155 219 127 181 24 222 253 74 59 201 211 253 16 58 103 251 147 219 219 85 127 210 73 198 114 0
1 0 120 189 188 242 169 237 85 207 187 191 172 25 190 247 64 26 129 243 237 16 26 75 218 51 251 215 85 123 192 80 134 43 0
1 0 220 180 188 246 169 108 85 154 187 255 183 57 223 255 75 27 135 215 253 18 58 71 251 34 219 243 117 255 130 113 135 115 0
1 0 232 172 180 116 205 253 84 143 251 183 164 24 170 185 70 191 137 246 232 16 62 111 250 179 219 219 85 127 194 92 206 14 0
1 0 216 188 156 244 169 236 17 7 186 191 166 25 191 183 64 91 129 119 237 16 58 77 211 35 219 243 94 91 128 64 135 43 0
1 0 124 177 185 98 153 109 87 152 99 189 173 8 215 245 73 50 153 214 108 122 26 99 251 48 251 221 5 125 194 123 198 34 0
1 0 196 172 148 191 137 237 20 175 190 179 138 25 230 242 72 91 129 119 104 16 50 77 219 115 173 182 95 127 128 112 135 10 0
1 0 198 180 148 242 233 109 180 202 187 187 177 25 206 255 77 27 167 87 255 19 50 103 218 242 157 210 95 127 192 113 135 131 0
1 0 194 172 148 186 137 237 20 207 191 55 128 25 174 250 76 155 129 115 233 17 54 79 218 243 153 210 95 123 144 84 143 14 0
11 0 212 52 157 247 136 110 85 154 178 191 167 24 215 119 73 91 129 215 109 50 56 69 219 34 217 227 117 20 160 113 135 34 0
10 6 0 0 #分别表示词袋字典的分支数、深度、 相似度、 权重
0 0 252 188 188 242 169 109 85 143 187 191 164 25 222 255 72 27 129 215
237 16 58 111 219 51 219 211 85 127 192 112 134 34 0
…
#0 表示节点的父节点;0 表示是否是叶节点, 是的话为 1, 否则为 0;252-34 表示 orb 特征;最后一位是权重(非叶子节点权重都为0)。
2.在线使用词袋模型
图三 利用词袋搜索描述子对应的单词
在线使用词典模型时:
- 对新来图像帧进行ORB特征提取,得到一定数量的特征点与对应的描述子;
- 将每个描述子转化为词袋向量
BowVector 与特征向量FeatureVector (见下述与源码3.1); - 基于词袋向量与特征向量完成相关的特征匹配、相似度对比等任务。
其中: 词袋向量BowVector: 数据类型:std::map<WordId, WordValue> WordId 和 WordValue 分别表示描述子对应的单词id 和权重。
特征向量FeatureVector: 数据类型:std::map<NodeId, std::vector<unsigned int> > NodeId :距离叶子节点深度为level up对应的节点的id。 std::vector :图像中落在NodeId 下的描述子对应的特征点索引。
FeatureVector 中的 NodeId 为什么不直接设置为父节点?因为后面搜索该Word 的匹配点的时候是在和它具有同样node id下面所有子节点中的Word 进行匹配,搜索区域见下图的 Word’s search region。所以搜索范围大小是根据level up来确定的,level up 值越大,搜索范围越广,速度越慢;level up 值越小,搜索范围越小,速度越快,但能够匹配的特征就越少。
词袋向量中权重的计算方法如下表所示,所有权重均可表示为节点权重NodeWeights 和在线权重的乘积,其中节点权重为构建字典时确定,在线权重在输入每张图像时计算
权重(WordValue)计算方法 | 节点权重 | 在线权重 |
---|
TF_IDF | IDF | TF | TF | 1 | TF | IDF | IDF | 1 | BINARY | 1 | 1 |
IDF称为逆文档频率,表示某单词在词典出现频率的高低,若词典中出现该单词的频率较高,表明该单词很常见,故其值越低,公式如下:
I
D
F
=
l
o
g
N
N
i
{IDF} = log \frac N{N_i}
IDF=logNi?N? 其中
N
{N}
N表示数据集中所有特征的总数,
N
i
{N_i}
Ni?表示某一词汇的出现数量。
TF称为词频:表示某一单词在图像中出现的频率,若图像中出现该单词的频率越高,说明该单词越能代表该图像,故其值越高。
T
F
=
n
i
n
{TF} = \frac {n_i}n
TF=nni?? 其中
n
{n}
n表示图像中所有单词(特征)的总数,
n
i
{n_i}
ni?表示图像中某单词的数量。
将每个描述子转化为词袋向量BowVector 与特征向量FeatureVector 流程:
- 如图三,每个特征点的描述子,从离线创建好的vocabulary tree中开始找自己的位置,从根节点开始,
用该描述子和每个节点的描述子计算汉明距离,选择汉明距离最小的作为自己所在的节点,一直遍历到 叶子节点。描述子最终转换为单词id(WordId ),节点权重(Word weight 即 NodeWeights),父节点ID(NodeId 距离叶子节点深度为level up的节点id);(见源码3.2) - 计算
WordValue 、构建词袋向量与特征向量;
3.源码
3.1 将描述子转为词袋向量与特征向量源码
/
**
* @brief 将一幅图像所有的描述子转化为BowVector和FeatureVector
* *
@tparam TDescriptor
* @tparam F
* @param[in] features 图像中所有的描述子
* @param[in & out] v BowVector
* @param[in & out] fv FeatureVector
* @param[in] levelsup 距离叶子的深度
*/
template<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::transform(
const std::vector<TDescriptor>& features,
BowVector &v, FeatureVector &fv, int levelsup) const
{
v.clear();
fv.clear();
if(empty())
{
return;
}
LNorm norm;
bool must = m_scoring_object->mustNormalize(norm);
typename vector<TDescriptor>::const_iterator fit;
if(m_weighting == TF || m_weighting == TF_IDF)
{
unsigned int i_feature = 0;
for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature)
{
WordId id;
NodeId nid;
WordValue w;
transform(*fit, id, w, &nid, levelsup);
if(w > 0)
{
v.addWeight(id, w);
fv.addFeature(nid, i_feature);
}
}
if(!v.empty() && !must)
{
const double nd = v.size();
for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++)
vit->second /= nd;
}
}
else
{
unsigned int i_feature = 0;
for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature)
{
WordId id;
NodeId nid;
WordValue w;
transform(*fit, id, w, &nid, levelsup);
if(w > 0)
{
v.addIfNotExist(id, w);
fv.addFeature(nid, i_feature);
}
}
if(must) v.normalize(norm);
}
3.2:3.1中 描述子转换为单词id(WordId),节点权重(Word weight 即 NodeWeights),父节点ID(NodeId 距离叶子节点深度为level up的节点id)源码:
template<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::transform(const TDescriptor &feature,
WordId &word_id, WordValue &weight, NodeId *nid, int levelsup) const
{
vector<NodeId> nodes;
typename vector<NodeId>::const_iterator nit;
const int nid_level = m_L - levelsup;
if(nid_level <= 0 && nid != NULL) *nid = 0;
NodeId final_id = 0;
int current_level = 0;
do
{
++current_level;
nodes = m_nodes[final_id].children;
final_id = nodes[0];
double best_d = F::distance(feature, m_nodes[final_id].descriptor);
for(nit = nodes.begin() + 1; nit != nodes.end(); ++nit)
{
NodeId id = *nit;
double d = F::distance(feature, m_nodes[id].descriptor);
if(d < best_d)
{
best_d = d;
final_id = id;
}
} /
/ 记录当前描述子转化为Word后所属的 node id,它距离叶子深度为levelsup
if(nid != NULL && current_level == nid_level)
*nid = final_id;
} while( !m_nodes[final_id].isLeaf() );
word_id = m_nodes[final_id].word_id;
weight = m_nodes[final_id].weight;
}
3.3 3.1中添加词袋向量BowVector 源码
void BowVector::addWeight(WordId id, WordValue v)
{
BowVector::iterator vit = this->lower_bound(id);
if(vit != this->end() && !(this->key_comp()(id, vit->first)))
{
vit->second += v;
}
else
{
this->insert(vit, BowVector::value_type(id, v));
}
}
3.4 3.1中添加特征向量FeatureVector 源码:
void FeatureVector::addFeature(NodeId id, unsigned int i_feature)
{
FeatureVector::iterator vit = this->lower_bound(id);
if(vit != this->end() && vit->first == id)
{
vit->second.push_back(i_feature);
}
else
{
vit = this->insert(vit, FeatureVector::value_type(id,
std::vector<unsigned int>() ));
vit->second.push_back(i_feature);
}
}
3.5节点权重NodeWeights 计算源码:
template<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::setNodeWeights
(const vector<vector<TDescriptor> > &training_features)
{
const unsigned int NWords = m_words.size();
const unsigned int NDocs = training_features.size();
if(m_weighting == TF || m_weighting == BINARY)
{
for(unsigned int i = 0; i < NWords; i++)
m_words[i]->weight = 1;
}
else if(m_weighting == IDF || m_weighting == TF_IDF)
{
vector<unsigned int> Ni(NWords, 0);
vector<bool> counted(NWords, false);
typename vector<vector<TDescriptor> >::const_iterator mit;
typename vector<TDescriptor>::const_iterator fit;
for(mit = training_features.begin(); mit != training_features.end(); ++mit)
{
fill(counted.begin(), counted.end(), false);
for(fit = mit->begin(); fit < mit->end(); ++fit)
{
WordId word_id;
transform(*fit, word_id);
if(!counted[word_id])
{
Ni[word_id]++;
counted[word_id] = true;
}
}
}
for(unsigned int i = 0; i < NWords; i++)
{
if(Ni[i] > 0)
{
m_words[i]->weight = log((double)NDocs / (double)Ni[i]);
}
}
}
}
备注:
-
论文中显示,在这个过程每帧图像会建立自身的直接索引表(Direct index),其中记录着该帧图像中特征所述的节点ID,如图三的直接索引表表示:图像1的特征65属于词袋词典的节点3,特征10、32属于节点44;同时,词袋库会维护逆向索引表(inverse index),其记录着包含第i个word id的所有关键帧,以及每个关键帧对应特征的权重,如图三逆向索引表;id为1的单词在图像65,82中均有出现,且分别对应图像68中的1号特征(其权重为0.79)、图像82的1号特征(权重为0.73)。在实际代码操作中,该部分内容通过BowVector和FeatureVector实现。 -
FeatureVector主要用于不同图像特征点快速匹配,加速几何关系验证,比如ORBmatcher::SearchByBoW 中是这样用的
DBoW2::FeatureVector::const_iterator f1it = vFeatVec1.begin();
DBoW2::FeatureVector::const_iterator f2it = vFeatVec2.begin();
DBoW2::FeatureVector::const_iterator f1end = vFeatVec1.end();
DBoW2::FeatureVector::const_iterator f2end = vFeatVec2.end();
while(f1it != f1end && f2it != f2end)
{
if(f1it->first == f2it->first)
for(size_t i1=0, iend1=f1it->second.size(); i1<iend1; i1++)
{
const size_t idx1 = f1it->second[i1];
MapPoint* pMP1 = vpMapPoints1[idx1];
其他人的解释: 词袋模型一些理解
|