ORB-SLAM2 ---- Frame::ComputeBoW函数

目录

1.该函数的用处及解析(通过上层调用理解)

2  BowVector::addWeight与FeatureVector::addFeature解析

2.1 BowVector::addWeight解析

2.2  FeatureVector::addFeature解析


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()) // safe for subclasses
  {
    return;
  }
  
  // normalize 
  // 根据选择的评分类型来确定是否需要将BowVector 归一化
  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;        // 叶子节点的Word id
      NodeId nid;       // FeatureVector 里的NodeId,用于加速搜索
      WordValue w;      // 叶子节点Word对应的权重

      //  将当前描述子转化为Word id, Word weight,节点所属的父节点id(这里的父节点不是叶子的上一层,它距离叶子深度为levelsup)
      // w is the idf value if TF_IDF, 1 if TF 
      transform(*fit, id, w, &nid, levelsup);
      
      if(w > 0) // not stopped
      { 
        // 如果Word 权重大于0,将其添加到BowVector 和 FeatureVector
        v.addWeight(id, w);
        fv.addFeature(nid, i_feature);
      }
    }
    
    if(!v.empty() && !must)
    {
      // unnecessary when normalizing
      const double nd = v.size();
      for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) 
        vit->second /= nd;
    }
  
  }
  else // IDF || BINARY
  {
    unsigned int i_feature = 0;
    for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature)
    {
      WordId id;
      NodeId nid;
      WordValue w;
      // w is idf if IDF, or 1 if BINARY
      transform(*fit, id, w, &nid, levelsup);
      
      if(w > 0) // not stopped
      {
        v.addIfNotExist(id, w);
        fv.addFeature(nid, i_feature);
      }
    }
  } // if m_weighting == ...
  
  if(must) v.normalize(norm);
}

        再看其上层函数调用

/**
 * @brief 计算当前帧特征点对应的词袋Bow,主要是mBowVec 和 mFeatVec
 * 
 */
void Frame::ComputeBoW()
{
	
    // 判断是否以前已经计算过了,计算过了就跳过
    if(mBowVec.empty())
    {
		// 将描述子mDescriptors转换为DBOW要求的输入格式
        vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
		// 将特征点的描述子转换成词袋向量mBowVec以及特征向量mFeatVec
        mpORBvocabulary->transform(vCurrentDesc,	//当前的描述子vector
								   mBowVec,			//输出,词袋向量,记录的是单词的id及其对应权重TF-IDF值
								   mFeatVec,		//输出,记录node id及其对应的图像 feature对应的索引
								   4);				//4表示从叶节点向前数的层数
    }
}
bool Tracking::TrackReferenceKeyFrame()
{
    // Compute Bag of Words vector
    // Step 1:将当前帧的描述子转化为BoW向量
    mCurrentFrame.ComputeBoW();

        最上层函数调用的意思是将当前帧描述子转化为BoW向量,那具体怎么转化呢,我们看它的函数调用ComputeBoW?

    // Bag of Words Vector structures.
    // 内部实际存储的是std::map<WordId, WordValue>
    // WordId 和 WordValue 表示Word在叶子中的id 和权重
    DBoW2::BowVector mBowVec;
    // 内部实际存储 std::map<NodeId, std::vector<unsigned int> >
    // NodeId 表示节点id,std::vector<unsigned int> 中实际存的是该节点id下所有特征点在图像中的索引
    DBoW2::FeatureVector mFeatVec;
    ///用于重定位的ORB特征字典
    ORBVocabulary* mpORBvocabulary;

        这里先判断mBowVec即词袋向量是否为空,若不空表示之前计算过,则不用计算直接跳过返回调用函数。

        若为空我们先做一步转换,将描述子mDescriptors转换为DBOW要求的输入格式vector<cv::Mat> vCurrentDesc,这是因为orbslam2和DBoW2的描述子格式不匹配。

        调用transform利用orb特征字典将特征点的描述子转换成词袋向量mBowVec以及特征向量mFeatVec,我们输入是转换为DBoW2格式的描述子vCurrentDesc、叶节点向前的索引层数levelsup=4,要求函数返回mBowVec(词袋向量,记录的是单词的id及其对应权重TF-IDF值)、mFeatVec(记录node id及其对应的图像 feature对应的索引)

        这个levelsup是什么意思呢?

         比如我们最终得到的匹配的节点是红色箭头指向的哪个,若levelup = 1,返回

 

         我们接着看TemplatedVocabulary<TDescriptor,F>::transform的一个模板版本,我们先创建了一个存放node的容器及迭代器nit;定义了nid_level = m_L - levelsup = 6(orbslam内定) - 4(参数levelup),其意义是父节点(我们匹配特征点时从这层开始匹配,而不是从树顶开始..,nid_level =2代表从第二层开始匹配)加速匹配的层数,其值越小,特征点匹配速度越慢。

        如果nid_level 的值是小于0的,那么就代表从离线词袋顶层开始匹配,nid = 0。

        设立循环辅助变量final_id存储最优的匹配描述子、current_level记录当前树的深度

        用nodes取出当前节点所有子节点的id,刚开始就是取出离线词袋的跟节点的所有子节点的ID,final_idbest_d分别记录离线词袋和当前特征点描述子匹配最优的节点的ID和最短的汉明距离,初始化为根节点第一个子节点,随后用选择排序方式选出current_level层的父节点的子节点的最优匹配结果final_idbest_d,如果当前层的层数current_levelcurrent_level,且nid!=0,则让nid赋值为current_level 层匹配效果最好的(汉明距离最小)的ID值,取出 vocabulary tree中node距离当前feature 描述子距离最小的那个node的 Word id 和 weight作为函数返回值输出。        

        因此,这个函数做了什么呢?利用离线词袋实现了输入描述子和词袋树描述子的匹配。并且计算出了这个描述子所属节点ID及再离线词袋中的权重。

2  BowVector::addWeight与FeatureVector::addFeature解析

2.1 BowVector::addWeight解析

/**
 * @brief 更新BowVector中的单词权重
 * 
 * @param[in] id    单词的ID
 * @param[in] v     单词的权重
 */
void BowVector::addWeight(WordId id, WordValue v)
{
  // 返回指向大于等于id的第一个值的位置
  BowVector::iterator vit = this->lower_bound(id);
  
  
  if(vit != this->end() && !(this->key_comp()(id, vit->first)))
  {
    // 如果id = vit->first, 说明是同一个Word,权重更新 
    vit->second += v;
  }
  else
  {
    // 如果该Word id不在BowVector中,新添加进来
    this->insert(vit, BowVector::value_type(id, v));
  }
}
class BowVector: public std::map<WordId, WordValue>

        我们先梳理一下BowVector是做什么的吧!当我们调用transform时,它的BowVector &v, FeatureVector &fv都是空的,它对特征点中每个描述子进行匹配,匹配成功时,记录它在离线词典中叶子节点的id,它的匹配节点的nid以及在叶子节点中的权重w。若权重大于0,则执行BowVector::addWeight函数,我们这里对BowVector &v查看其中是否有该叶子节点的id,若没有则创建,若有则为同一节点,让其权重加上离线词典中该节点的权重。

        那么我们现在就应该明白BowVector 是什么了,它是节点id和权重的对组,这个关键点中出现某个描述子的频率越大,它的权重就越高。

2.2  FeatureVector::addFeature解析

/**
 * @brief 把node id下所有的特征点的索引值归属到它的向量里
 * 
 * @param[in] id              节点ID,内部包含很多单词
 * @param[in] i_feature       特征点在图像中的索引
 */
void FeatureVector::addFeature(NodeId id, unsigned int i_feature)
{
  // 返回指向大于等于id的第一个值的位置
  FeatureVector::iterator vit = this->lower_bound(id);
  // 将同样node id下的特征点索引值放在一个向量里
  if(vit != this->end() && vit->first == id)
  {
    // 如果这个node id已经创建,可以直接插入特征点索引
    vit->second.push_back(i_feature);
  }
  else
  {
    // 如果这个node id还未创建,创建后再插入特征点索引
    vit = this->insert(vit, FeatureVector::value_type(id, std::vector<unsigned int>() ));
    vit->second.push_back(i_feature);
  }
}
class FeatureVector: public std::map<NodeId, std::vector<unsigned int> >

        它输入的是上层输入的父节点的idi_feature(当前遍历到这个特征点的第几个描述子),若父节点id还没有在FeatureVector里,则创建;若有,则添加。

 

  • 1
    点赞
  • 8
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

APS2023

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值