ORBSLAM2源码学习(3) Map类和KeyFrameDataBase类

将这两个类放在一起是因为代码都比较短,比较容易理解,否则一个类单独一篇那恐怕要写好久了...

1.Map类

Map类管理整个地图,因此其具有的属性是所有的地图点和关建针,即普通的帧是不管的,另外还有一些帧编号之类的东西,该类具有添加、删除关键帧的方法和添加、删除地图点的方法,另外就是一个返回属性的函数。直接上代码了。

#ifndef MAP_H
#define MAP_H

#include "MapPoint.h"
#include "KeyFrame.h"
#include 
#include 

namespace ORB_SLAM2
{

class MapPoint;
class KeyFrame;

class Map
{
public:
    Map();

    void AddKeyFrame(KeyFrame* pKF);
    void AddMapPoint(MapPoint* pMP);
    void EraseMapPoint(MapPoint* pMP);
    void EraseKeyFrame(KeyFrame* pKF);
    void SetReferenceMapPoints(const std::vector &vpMPs);

    std::vector GetAllKeyFrames();
    std::vector GetAllMapPoints();
    std::vector GetReferenceMapPoints();

    long unsigned int MapPointsInMap();
    long unsigned  KeyFramesInMap();

    long unsigned int GetMaxKFid();

    void clear();

    vector mvpKeyFrameOrigins;

    std::mutex mMutexMapUpdate;

    // This avoid that two points are created simultaneously in separate threads (id conflict)
    std::mutex mMutexPointCreation;

protected:
    std::set mspMapPoints; ///< MapPoints
    std::set mspKeyFrames; ///< Keyframs

    std::vector mvpReferenceMapPoints;

    long unsigned int mnMaxKFid;

    std::mutex mMutexMap;
};

} //namespace ORB_SLAM

#endif // MAP_H
#include "Map.h"
#include

namespace ORB_SLAM2
{

Map::Map():mnMaxKFid(0)
{
}
//增加关键帧
void Map::AddKeyFrame(KeyFrame *pKF)
{
    unique_lock lock(mMutexMap);
    mspKeyFrames.insert(pKF);
    if(pKF->mnId>mnMaxKFid)
        mnMaxKFid=pKF->mnId;
}

//增加地图点
void Map::AddMapPoint(MapPoint *pMP)
{
    unique_lock lock(mMutexMap);
    mspMapPoints.insert(pMP);
}

//擦除地图点
void Map::EraseMapPoint(MapPoint *pMP)
{
    unique_lock lock(mMutexMap);
    mspMapPoints.erase(pMP);

    // TODO: This only erase the pointer.
    // Delete the MapPoint
}

//擦除关键帧
void Map::EraseKeyFrame(KeyFrame *pKF)
{
    unique_lock lock(mMutexMap);
    mspKeyFrames.erase(pKF);

    // TODO: This only erase the pointer.
    // Delete the MapPoint
}

//设置参考地图点
void Map::SetReferenceMapPoints(const vector &vpMPs)
{
    unique_lock lock(mMutexMap);
    mvpReferenceMapPoints = vpMPs;
}
//获取所有关键帧
vector Map::GetAllKeyFrames()
{
    unique_lock lock(mMutexMap);
    return vector(mspKeyFrames.begin(),mspKeyFrames.end());
}
//获取所有地图点
vector Map::GetAllMapPoints()
{
    unique_lock lock(mMutexMap);
    return vector(mspMapPoints.begin(),mspMapPoints.end());
}
//返回地图中含有的地图点的个数
long unsigned int Map::MapPointsInMap()
{
    unique_lock lock(mMutexMap);
    return mspMapPoints.size();
}
//返回地图中关键帧的个数
long unsigned int Map::KeyFramesInMap()
{
    unique_lock lock(mMutexMap);
    return mspKeyFrames.size();
}

vector Map::GetReferenceMapPoints()
{
    unique_lock lock(mMutexMap);
    return mvpReferenceMapPoints;
}

long unsigned int Map::GetMaxKFid()
{
    unique_lock lock(mMutexMap);
    return mnMaxKFid;
}

void Map::clear()
{
    for(set::iterator sit=mspMapPoints.begin(), send=mspMapPoints.end(); sit!=send; sit++)
        delete *sit;

    for(set::iterator sit=mspKeyFrames.begin(), send=mspKeyFrames.end(); sit!=send; sit++)
        delete *sit;

    mspMapPoints.clear();
    mspKeyFrames.clear();
    mnMaxKFid = 0;
    mvpReferenceMapPoints.clear();
    mvpKeyFrameOrigins.clear();
}

} //namespace ORB_SLAM

2.KeyFrameDataBase类

这个类是关键帧的数据库,主要用于计算闭环检测和重定位时的候选帧,类中维护一个每个元素都是链表的vector容器,容器的每个元素是预先训练好的特征词汇,然后对应的连表上放的都是关键帧,包含这个词汇的关键帧。

#ifndef KEYFRAMEDATABASE_H
#define KEYFRAMEDATABASE_H

#include 
#include 
#include 

#include "KeyFrame.h"
#include "Frame.h"
#include "ORBVocabulary.h"

#include


namespace ORB_SLAM2
{

class KeyFrame;
class Frame;


class KeyFrameDatabase
{
public:

    KeyFrameDatabase(const ORBVocabulary &voc);

   void add(KeyFrame* pKF);

   void erase(KeyFrame* pKF);

   void clear();

   // Loop Detection
   std::vector DetectLoopCandidates(KeyFrame* pKF, float minScore);

   // Relocalization
   std::vector DetectRelocalizationCandidates(Frame* F);

protected:

  // Associated vocabulary
  const ORBVocabulary* mpVoc; // 预先训练好的词典

  // Inverted file
  // mvInvertedFile[i]表示包含了第i个word id的所有关键帧
  std::vector > mvInvertedFile; 

  // Mutex
  std::mutex mMutex;
};

} //namespace ORB_SLAM

#endif

具体实现

#include "KeyFrameDatabase.h"

#include "KeyFrame.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"

#include

using namespace std;

namespace ORB_SLAM2
{

KeyFrameDatabase::KeyFrameDatabase (const ORBVocabulary &voc):
    mpVoc(&voc)
{
    mvInvertedFile.resize(voc.size()); // number of words
}

void KeyFrameDatabase::add(KeyFrame *pKF)
{
    unique_lock lock(mMutex);

    // 为每一个word添加该KeyFrame
    for(DBoW2::BowVector::const_iterator vit= pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
        mvInvertedFile[vit->first].push_back(pKF);
}

// 关键帧被删除后,更新数据库
void KeyFrameDatabase::erase(KeyFrame* pKF)
{
    unique_lock lock(mMutex);

    // Erase elements in the Inverse File for the entry
    // 每一个KeyFrame包含多个words,遍历mvInvertedFile中的这些words,然后在word中删除该KeyFrame
    for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
    {
        // List of keyframes that share the word
        list &lKFs = mvInvertedFile[vit->first];

        for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
        {
            if(pKF==*lit)
            {
                lKFs.erase(lit);
                break;
            }
        }
    }
}

void KeyFrameDatabase::clear()
{
    mvInvertedFile.clear();// mvInvertedFile[i]表示包含了第i个word id的所有关键帧
    mvInvertedFile.resize(mpVoc->size());// mpVoc:预先训练好的词典
}

// 在闭环检测中找到与该关键帧可能闭环的关键帧
vector KeyFrameDatabase::DetectLoopCandidates(KeyFrame* pKF, float minScore)
{
    // 提出所有与该pKF相连的KeyFrame,这些相连Keyframe都是局部相连,在闭环检测的时候将被剔除
	// 即局部图中带有权重的关键帧
    set spConnectedKeyFrames = pKF->GetConnectedKeyFrames();
    list lKFsSharingWords;// 用于保存可能与pKF形成回环的候选帧

    // Search all keyframes that share a word with current keyframes
    // Discard keyframes connected to the query keyframe
    // 1:找出和当前帧具有公共单词的所有不在局部图中的关键帧
    {
        unique_lock lock(mMutex);

        for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++)
        {
            // 提取所有包含该word的KeyFrame
            list &lKFs =   mvInvertedFile[vit->first];

            for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
            {
                KeyFrame* pKFi=*lit;
                if(pKFi->mnLoopQuery!=pKF->mnId)// pKFi还没有标记
                {
                    pKFi->mnLoopWords=0;
                    if(!spConnectedKeyFrames.count(pKFi))// 与pKF局部链接的关键帧不进入闭环候选帧
                    {
                        pKFi->mnLoopQuery=pKF->mnId;// pKFi标记为pKF的候选帧
                        lKFsSharingWords.push_back(pKFi);
                    }
                }
                pKFi->mnLoopWords++;	// 记录pKFi与pKF具有相同词汇的个数
            }
        }
    }

    if(lKFsSharingWords.empty())
        return vector();

    list > lScoreAndMatch;

    // Only compare against those keyframes that share enough words
    // 2:统计上一步所有闭环候选帧中与pKF具有共同单词最多的单词数
    int maxCommonWords=0;
    for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
    {
        if((*lit)->mnLoopWords>maxCommonWords)
            maxCommonWords=(*lit)->mnLoopWords;
    }

	// 设置下限
    int minCommonWords = maxCommonWords*0.8f;

    int nscores=0;

    // Compute similarity score. Retain the matches whose score is higher than minScore
    // 3:遍历所有闭环候选帧,挑选出共有单词数大于minCommonWords且单词匹配度大于minScore的关键帧存入lScoreAndMatch
    for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
    {
        KeyFrame* pKFi = *lit;

        // 挑选出共有单词数大于minCommonWords
        if(pKFi->mnLoopWords>minCommonWords)
        {
            nscores++;

			// 计算相似度
            float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec);

            pKFi->mLoopScore = si;
			// 只保留得分大于minScore的帧
            if(si>=minScore)
                lScoreAndMatch.push_back(make_pair(si,pKFi));
        }
    }

    if(lScoreAndMatch.empty())
        return vector();

    list > lAccScoreAndMatch;
    float bestAccScore = minScore;

    // Lets now accumulate score by covisibility
    // 将上一步中的每一帧的共视程度最高的前十个关键帧归为一组,计算累计得分
    // 具体而言:lScoreAndMatch中每一个KeyFrame都把与自己共视程度较高的帧归为一组,
	// 每一组会计算组得分并记录该组分数最高的KeyFrame,记录于lAccScoreAndMatch,最后保存这个组内得分最高的KeyFrame
    for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++)
    {
        KeyFrame* pKFi = it->second;
        vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);

        float bestScore = it->first; 	// 该组最高分数
        float accScore = it->first;  	// 该组累计得分
        KeyFrame* pBestKF = pKFi;    	// 该组最高分数对应的关键帧
        for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++)
        {
            KeyFrame* pKF2 = *vit;
			// pKF2在候选帧中且共同词汇数量大于阈值
            if(pKF2->mnLoopQuery==pKF->mnId && pKF2->mnLoopWords>minCommonWords)
            {
                accScore+=pKF2->mLoopScore;
                if(pKF2->mLoopScore>bestScore)// 统计得到组里分数最高的KeyFrame
                {
                    pBestKF=pKF2;
                    bestScore = pKF2->mLoopScore;
                }
            }
        }
		// 保存组内得分最高的一帧
        lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF));
        if(accScore>bestAccScore)	// 记录所有组中组得分最高的组
            bestAccScore=accScore;
    }

    // Return all those keyframes with a score higher than 0.75*bestScore
	// 设置下限
    float minScoreToRetain = 0.75f*bestAccScore;

    set spAlreadyAddedKF;
    vector vpLoopCandidates;
    vpLoopCandidates.reserve(lAccScoreAndMatch.size());

    // 得到组得分大于minScoreToRetain的组,得到组中分数最高的关键帧 0.75*bestScore
    for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++)
    {
        if(it->first>minScoreToRetain)
        {
            KeyFrame* pKFi = it->second;
            if(!spAlreadyAddedKF.count(pKFi))	
            {
                vpLoopCandidates.push_back(pKFi);
                spAlreadyAddedKF.insert(pKFi);
            }
        }
    }

    return vpLoopCandidates;
}

// 在重定位中找到与该帧相似的关键帧
vector KeyFrameDatabase::DetectRelocalizationCandidates(Frame *F)
{
    list lKFsSharingWords;

    {
        unique_lock lock(mMutex);

        for(DBoW2::BowVector::const_iterator vit=F->mBowVec.begin(), vend=F->mBowVec.end(); vit != vend; vit++)
        {
            list &lKFs = mvInvertedFile[vit->first];

            for(list::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++;
            }
        }
    }
    if(lKFsSharingWords.empty())
        return vector();

    // Only compare against those keyframes that share enough words
    int maxCommonWords=0;
    for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
    {
        if((*lit)->mnRelocWords>maxCommonWords)
            maxCommonWords=(*lit)->mnRelocWords;
    }

    int minCommonWords = maxCommonWords*0.8f;

    list > lScoreAndMatch;

    int nscores=0;

    // Compute similarity score.
    for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
    {
        KeyFrame* pKFi = *lit;

        if(pKFi->mnRelocWords>minCommonWords)
        {
            nscores++;
            float si = mpVoc->score(F->mBowVec,pKFi->mBowVec);
            pKFi->mRelocScore=si;
            lScoreAndMatch.push_back(make_pair(si,pKFi));
        }
    }

    if(lScoreAndMatch.empty())
        return vector();

    list > lAccScoreAndMatch;
    float bestAccScore = 0;

    for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++)
    {
        KeyFrame* pKFi = it->second;
        vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);

        float bestScore = it->first; 
        float accScore = bestScore;  
        KeyFrame* pBestKF = pKFi;   
        for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++)
        {
            KeyFrame* pKF2 = *vit;
            if(pKF2->mnRelocQuery!=F->mnId)
                continue;

            accScore+=pKF2->mRelocScore;
            if(pKF2->mRelocScore>bestScore)
            {
                pBestKF=pKF2;
                bestScore = pKF2->mRelocScore;
            }

        }
        lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF));
        if(accScore>bestAccScore) 
            bestAccScore=accScore; 
    }

    // Return all those keyframes with a score higher than 0.75*bestScore
    float minScoreToRetain = 0.75f*bestAccScore;
    set spAlreadyAddedKF;
    vector vpRelocCandidates;
    vpRelocCandidates.reserve(lAccScoreAndMatch.size());
    for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++)
    {
        const float &si = it->first;
        if(si>minScoreToRetain)
        {
            KeyFrame* pKFi = it->second;
            if(!spAlreadyAddedKF.count(pKFi))
            {
                vpRelocCandidates.push_back(pKFi);
                spAlreadyAddedKF.insert(pKFi);
            }
        }
    }

    return vpRelocCandidates;
}

} //namespace ORB_SLAM

代码中详细注释了计算闭环候选帧的过程,由于计算重定位候选帧的过程几乎类似,因此没有注释,两者区别在于:计算闭环候选帧时参考的是关键帧,而重定位时参考的是普通帧,因此也就没有像闭环那样剔除关键帧的局部图中的帧。

你可能感兴趣的:(SLAM研究)