ORB_SLAM2是如何建立地图并且显示的?

文章目录

    • Map.cc
    • MapDrawer.cc

Map.cc

#include "Map.h"

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

#include 

namespace ORB_SLAM2
{
/**
 * @brief 地图
 * class Map
 */

//构造函数,地图点中最大关键帧id归0
//当前地图中具有最大ID的关键帧
    //long unsigned int mnMaxKFid;
Map::Map():mnMaxKFid(0)
{
}

/*
 * @brief Insert KeyFrame in the map
 * @param pKF KeyFrame
 */
//在地图中插入关键帧,同时更新关键帧的最大id

void Map::AddKeyFrame(KeyFrame *pKF)
{
    unique_lock<mutex> lock(mMutexMap);
    mspKeyFrames.insert(pKF);
    if(pKF->mnId>mnMaxKFid)
        mnMaxKFid=pKF->mnId;
}

/*
 * @brief Insert MapPoint in the map
 * @param pMP MapPoint
 *     std::set mspMapPoints; ///< MapPoints
    std::set mspKeyFrames; ///< Keyframs
 */
//向地图中插入地图点

void Map::AddMapPoint(MapPoint *pMP)
{
    unique_lock<mutex> lock(mMutexMap);
    mspMapPoints.insert(pMP);
}

/*
 * @brief Erase MapPoint from the map
 * @param pMP MapPoint
 */
//从地图中删除地图点,但是其实这个地图点所占用的内存空间并没有被释放
void Map::EraseMapPoint(MapPoint *pMP)
{
    unique_lock<mutex> lock(mMutexMap);
    mspMapPoints.erase(pMP);

    //下面是作者加入的注释. 实际上只是从std::set中删除了地图点的指针, 原先地图点
    //占用的内存区域并没有得到释放
    // TODO: This only erase the pointer.
    // Delete the MapPoint
}

/**
 * @brief Erase KeyFrame from the map
 * @param pKF KeyFrame
 */
    /**
      * @brief 从地图中删除关键帧
      * @detials 实际上这个函数中目前仅仅是删除了在std::set中保存的地图点的指针,并且删除后
      * 之前的地图点所占用的内存其实并没有得到释放
      * @param[in] pKF 关键帧
      *     ///类的成员函数在对类成员变量进行操作的时候,防止冲突的互斥量

      */
void Map::EraseKeyFrame(KeyFrame *pKF)
{
    unique_lock<mutex> lock(mMutexMap);
    //是的,根据值来删除地图点
    mspKeyFrames.erase(pKF);

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

/**
 * @brief 设置参考MapPoints,将用于DrawMapPoints函数画图
 * @param vpMPs Local MapPoints
 *      * @brief 设置参考地图点
     * @detials 一般是指,设置当前帧中的参考地图点; 这些点将用于DrawMapPoints函数画图
     * // 设置参考地图点用于绘图显示局部地图点(红色)
 */

void Map::SetReferenceMapPoints(const vector<MapPoint *> &vpMPs)
{
    unique_lock<mutex> lock(mMutexMap);
    mvpReferenceMapPoints = vpMPs;
}

//REVIEW 这个好像没有用到
void Map::InformNewBigChange()
{
    unique_lock<mutex> lock(mMutexMap);
    mnBigChangeIdx++;
}

int Map::GetLastBigChangeIdx()
{
    unique_lock<mutex> lock(mMutexMap);
    return mnBigChangeIdx;
}

//获取地图中的所有关键帧
vector<KeyFrame*> Map::GetAllKeyFrames()
{
    unique_lock<mutex> lock(mMutexMap);
    return vector<KeyFrame*>(mspKeyFrames.begin(),mspKeyFrames.end());
}

//获取地图中的所有地图点
vector<MapPoint*> Map::GetAllMapPoints()
{
    unique_lock<mutex> lock(mMutexMap);
    return vector<MapPoint*>(mspMapPoints.begin(),mspMapPoints.end());
}

//获得当前地图中的地图点个数

long unsigned int Map::MapPointsInMap()
{
    unique_lock<mutex> lock(mMutexMap);
    return mspMapPoints.size();
}

//获取地图中的关键帧数目
long unsigned int Map::KeyFramesInMap()
{
    unique_lock<mutex> lock(mMutexMap);
    return mspKeyFrames.size();
}

//获取参考地图点
vector<MapPoint*> Map::GetReferenceMapPoints()
{
    unique_lock<mutex> lock(mMutexMap);
    return mvpReferenceMapPoints;
}

//获取地图中最大的关键帧id

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

//清空地图中的数据

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

    for(set<KeyFrame*>::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

MapDrawer.cc

#include"Map.h"
#include"MapPoint.h"
#include"KeyFrame.h"
#include
#include
#include "MapDrawer.h"
#include "MapPoint.h"
#include "KeyFrame.h"
#include 
#include 

namespace ORB_SLAM2
{

//构造函数
    /**
       * @brief 构造函数
       *
       * @param[in] pMap              地图句柄
       * @param[in] strSettingPath    配置文件的路径
       *
       * private:

    //绘制这些部件的参数
    ///关键帧-大小
    float mKeyFrameSize;
    ///关键帧-线宽
    float mKeyFrameLineWidth;
    ///共视图的线宽
    float mGraphLineWidth;
    ///地图点的大小
    float mPointSize;
    ///绘制的相机的大小
    float mCameraSize;
    ///绘制相机的线宽
    float mCameraLineWidth;

    ///相机位置
    cv::Mat mCameraPose;

    ///线程互斥量
    std::mutex mMutexCamera;
       */
MapDrawer::MapDrawer(Map* pMap, const string &strSettingPath):mpMap(pMap)
{
    //从配置文件中读取设置的
    cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);

    mKeyFrameSize = fSettings["Viewer.KeyFrameSize"];
    mKeyFrameLineWidth = fSettings["Viewer.KeyFrameLineWidth"];
    mGraphLineWidth = fSettings["Viewer.GraphLineWidth"];
    mPointSize = fSettings["Viewer.PointSize"];
    mCameraSize = fSettings["Viewer.CameraSize"];
    mCameraLineWidth = fSettings["Viewer.CameraLineWidth"];

}

//关于gl相关的函数,可直接google, 并加上msdn关键词  绘制地图点
void MapDrawer::DrawMapPoints()
{
    //取出所有的地图点
    const vector<MapPoint*> &vpMPs = mpMap->GetAllMapPoints();
    //取出mvpReferenceMapPoints,也即局部地图d点
    const vector<MapPoint*> &vpRefMPs = mpMap->GetReferenceMapPoints();

    //将vpRefMPs从vector容器类型转化为set容器类型,便于使用set::count快速统计 - 我觉得称之为"重新构造"可能更加合适一些
    //补充, set::count用于返回集合中为某个值的元素的个数
    set<MapPoint*> spRefMPs(vpRefMPs.begin(), vpRefMPs.end());

    if(vpMPs.empty())
        return;

    // for AllMapPoints
    //显示所有的地图点(不包括局部地图点),大小为2个像素,黑色
    glPointSize(mPointSize);
    glBegin(GL_POINTS);
    glColor3f(0.0,0.0,0.0);         //黑色

    for(size_t i=0, iend=vpMPs.size(); i<iend;i++)
    {
        // 不包括ReferenceMapPoints(局部地图点)
        if(vpMPs[i]->isBad() || spRefMPs.count(vpMPs[i]))
            continue;
        cv::Mat pos = vpMPs[i]->GetWorldPos();
        glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));
    }
    glEnd();

    // for ReferenceMapPoints
    //显示局部地图点,大小为2个像素,红色
    glPointSize(mPointSize);
    glBegin(GL_POINTS);
    glColor3f(1.0,0.0,0.0);

    for(set<MapPoint*>::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++)
    {
        if((*sit)->isBad())
            continue;
        cv::Mat pos = (*sit)->GetWorldPos();
        glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));

    }
    glEnd();
}

//关于gl相关的函数,可直接google, 并加上msdn关键词
/**
     * @brief 绘制关键帧
     *
     * @param[in] bDrawKF       是否绘制关键帧
     * @param[in] bDrawGraph    是否绘制共视图
     */
void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph)
{
    //历史关键帧图标:宽度占总宽度比例为0.05
    const float &w = mKeyFrameSize;
    const float h = w*0.75;
    const float z = w*0.6;

    // step 1:取出所有的关键帧
    const vector<KeyFrame*> vpKFs = mpMap->GetAllKeyFrames();

    // step 2:显示所有关键帧图标
    //通过显示界面选择是否显示历史关键帧图标
    if(bDrawKF)
    {
        for(size_t i=0; i<vpKFs.size(); i++)
        {
            KeyFrame* pKF = vpKFs[i];
            //NOTICE 转置, OpenGL中的矩阵为列优先存储
            cv::Mat Twc = pKF->GetPoseInverse().t();

            glPushMatrix();

            //(由于使用了glPushMatrix函数,因此当前帧矩阵为世界坐标系下的单位矩阵)
            //因为OpenGL中的矩阵为列优先存储,因此实际为Tcw,即相机在世界坐标下的位姿
            //NOTICE 竟然还可以这样写,牛逼牛逼
            glMultMatrixf(Twc.ptr<GLfloat>(0));

            //设置绘制图形时线的宽度
            glLineWidth(mKeyFrameLineWidth);
            //设置当前颜色为蓝色(关键帧图标显示为蓝色)
            glColor3f(0.0f,0.0f,1.0f);
            //用线将下面的顶点两两相连
            glBegin(GL_LINES);
            glVertex3f(0,0,0);
            glVertex3f(w,h,z);
            glVertex3f(0,0,0);
            glVertex3f(w,-h,z);
            glVertex3f(0,0,0);
            glVertex3f(-w,-h,z);
            glVertex3f(0,0,0);
            glVertex3f(-w,h,z);

            glVertex3f(w,h,z);
            glVertex3f(w,-h,z);

            glVertex3f(-w,h,z);
            glVertex3f(-w,-h,z);

            glVertex3f(-w,h,z);
            glVertex3f(w,h,z);

            glVertex3f(-w,-h,z);
            glVertex3f(w,-h,z);
            glEnd();

            glPopMatrix();
        }
    }

    // step 3:显示所有关键帧的Essential Graph (本征图)
    /**
     * 共视图中存储了所有关键帧的共视关系
     * 本征图中对边进行了优化,保存了所有节点,只存储了具有较多共视点的边,用于进行优化
     * 生成树则进一步进行了优化,保存了所有节点,但是值保存具有最多共视地图点的关键帧的边
     * 
     */
    //通过显示界面选择是否显示关键帧连接关系
    if(bDrawGraph)
    {
        //设置绘制图形时线的宽度
        glLineWidth(mGraphLineWidth);
        //设置共视图连接线为绿色,透明度为0.6f
        glColor4f(0.0f,1.0f,0.0f,0.6f);
        glBegin(GL_LINES);  //绘制线条的时候,默认是按照添加顺序,每两个点之间绘制一条直线

        for(size_t i=0; i<vpKFs.size(); i++)
        {
            // Covisibility Graph (共视图)
            // step 3.1 共视程度比较高的共视关键帧用线连接
            //遍历每一个关键帧,得到它们共视程度比较高的关键帧
            const vector<KeyFrame*> vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100);
            //遍历每一个关键帧,得到它在世界坐标系下的相机坐标
            cv::Mat Ow = vpKFs[i]->GetCameraCenter();
            if(!vCovKFs.empty())
            {
                for(vector<KeyFrame*>::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++)
                {
                    //单向绘制
                    if((*vit)->mnId<vpKFs[i]->mnId)
                        continue;
                    cv::Mat Ow2 = (*vit)->GetCameraCenter();
                    glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
                    glVertex3f(Ow2.at<float>(0),Ow2.at<float>(1),Ow2.at<float>(2));
                }
            }

            // Spanning tree
            // step 3.2 连接最小生成树 (PS: 我觉得这里并不是权值最小,而是其中的边对于其他的图来讲是最少的)
            //TODO 这个部分的理论知识还不是很了解
            KeyFrame* pParent = vpKFs[i]->GetParent();
            if(pParent)
            {
                cv::Mat Owp = pParent->GetCameraCenter();
                glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
                glVertex3f(Owp.at<float>(0),Owp.at<float>(1),Owp.at<float>(2));
            }

            // Loops
            // step 3.3 连接闭环时形成的连接关系
            //TODO 这个部分也不是非常明白
            set<KeyFrame*> sLoopKFs = vpKFs[i]->GetLoopEdges();
            for(set<KeyFrame*>::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++)
            {
                if((*sit)->mnId<vpKFs[i]->mnId)
                    continue;
                cv::Mat Owl = (*sit)->GetCameraCenter();
                glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
                glVertex3f(Owl.at<float>(0),Owl.at<float>(1),Owl.at<float>(2));
            }
        }

        glEnd();
    }
}

//关于gl相关的函数,可直接google, 并加上msdn关键词
    /**
      * @brief 绘制当前相机
      *
      * @param[in] Twc 相机的位姿矩阵
      */
void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc)
{
    //相机模型大小:宽度占总宽度比例为0.08
    const float &w = mCameraSize;
    const float h = w*0.75;
    const float z = w*0.6;

    //百度搜索:glPushMatrix 百度百科
    glPushMatrix();

    //将4*4的矩阵Twc.m右乘一个当前矩阵
    //(由于使用了glPushMatrix函数,因此当前帧矩阵为世界坐标系下的单位矩阵)
    //因为OpenGL中的矩阵为列优先存储,因此实际为Tcw,即相机在世界坐标下的位姿
    //一个是整型,一个是浮点数类型
#ifdef HAVE_GLES
        glMultMatrixf(Twc.m);
#else
        glMultMatrixd(Twc.m);
#endif

    //设置绘制图形时线的宽度
    glLineWidth(mCameraLineWidth);
    //设置当前颜色为绿色(相机图标显示为绿色)
    glColor3f(0.0f,1.0f,0.0f);
    //用线将下面的顶点两两相连
    glBegin(GL_LINES);
    glVertex3f(0,0,0);
    glVertex3f(w,h,z);
    glVertex3f(0,0,0);
    glVertex3f(w,-h,z);
    glVertex3f(0,0,0);
    glVertex3f(-w,-h,z);
    glVertex3f(0,0,0);
    glVertex3f(-w,h,z);

    glVertex3f(w,h,z);
    glVertex3f(w,-h,z);

    glVertex3f(-w,h,z);
    glVertex3f(-w,-h,z);

    glVertex3f(-w,h,z);
    glVertex3f(w,h,z);

    glVertex3f(-w,-h,z);
    glVertex3f(w,-h,z);
    glEnd();

    glPopMatrix();
}

//设置当前帧相机的位姿, 设置这个函数是因为要处理多线程的操作
    /**
       * @brief 设置当前帧的相机位姿
       *
       * @param[in] Tcw 位姿矩阵
       */
void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw)
{
    unique_lock<mutex> lock(mMutexCamera);
    mCameraPose = Tcw.clone();
}

// 将相机位姿mCameraPose由Mat类型转化为OpenGlMatrix类型

void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M)
{
    if(!mCameraPose.empty())
    {
        cv::Mat Rwc(3,3,CV_32F);
        cv::Mat twc(3,1,CV_32F);
        {
            unique_lock<mutex> lock(mMutexCamera);
            Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t();
            twc = -Rwc*mCameraPose.rowRange(0,3).col(3);
        }

        M.m[0] = Rwc.at<float>(0,0);
        M.m[1] = Rwc.at<float>(1,0);
        M.m[2] = Rwc.at<float>(2,0);
        M.m[3]  = 0.0;

        M.m[4] = Rwc.at<float>(0,1);
        M.m[5] = Rwc.at<float>(1,1);
        M.m[6] = Rwc.at<float>(2,1);
        M.m[7]  = 0.0;

        M.m[8] = Rwc.at<float>(0,2);
        M.m[9] = Rwc.at<float>(1,2);
        M.m[10] = Rwc.at<float>(2,2);
        M.m[11]  = 0.0;

        M.m[12] = twc.at<float>(0);
        M.m[13] = twc.at<float>(1);
        M.m[14] = twc.at<float>(2);
        M.m[15]  = 1.0;
    }
    else
        M.SetIdentity();
}

} //namespace ORB_SLAM

你可能感兴趣的:(ORB_SLAM2源码解读,自动驾驶)