123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464 |
- #include "MapDrawer.h"
- #include "MapPoint.h"
- #include "KeyFrame.h"
- #include <pangolin/pangolin.h>
- #include <mutex>
- namespace ORB_SLAM3
- {
- MapDrawer::MapDrawer(Atlas* pAtlas, const string &strSettingPath):mpAtlas(pAtlas)
- {
- 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"];
- }
- void MapDrawer::DrawMapPoints()
- {
- const vector<MapPoint*> &vpMPs = mpAtlas->GetAllMapPoints();
- const vector<MapPoint*> &vpRefMPs = mpAtlas->GetReferenceMapPoints();
- set<MapPoint*> spRefMPs(vpRefMPs.begin(), vpRefMPs.end());
- if(vpMPs.empty())
- return;
- glPointSize(mPointSize);
- glBegin(GL_POINTS);
- glColor3f(0.0,0.0,0.0);
- for(size_t i=0, iend=vpMPs.size(); i<iend;i++)
- {
- 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();
- 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();
- }
- void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph)
- {
- const float &w = mKeyFrameSize;
- const float h = w*0.75;
- const float z = w*0.6;
- const vector<KeyFrame*> vpKFs = mpAtlas->GetAllKeyFrames();
- if(bDrawKF)
- {
- for(size_t i=0; i<vpKFs.size(); i++)
- {
- KeyFrame* pKF = vpKFs[i];
- cv::Mat Twc = pKF->GetPoseInverse().t();
- unsigned int index_color = pKF->mnOriginMapId;
- glPushMatrix();
- glMultMatrixf(Twc.ptr<GLfloat>(0));
- if(!pKF->GetParent())
- {
- glLineWidth(mKeyFrameLineWidth*5);
- glColor3f(1.0f,0.0f,0.0f);
- glBegin(GL_LINES);
-
-
- }
- else
- {
- glLineWidth(mKeyFrameLineWidth);
-
- glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]);
- 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();
-
-
- glEnd();
- }
- }
- if(bDrawGraph)
- {
- glLineWidth(mGraphLineWidth);
- glColor4f(0.0f,1.0f,0.0f,0.6f);
- glBegin(GL_LINES);
-
- for(size_t i=0; i<vpKFs.size(); i++)
- {
-
- 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));
- }
- }
-
- 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));
- }
-
- 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();
- }
- if(bDrawInertialGraph && mpAtlas->isImuInitialized())
- {
- glLineWidth(mGraphLineWidth);
- glColor4f(1.0f,0.0f,0.0f,0.6f);
- glBegin(GL_LINES);
-
- for(size_t i=0; i<vpKFs.size(); i++)
- {
- KeyFrame* pKFi = vpKFs[i];
- cv::Mat Ow = pKFi->GetCameraCenter();
- KeyFrame* pNext = pKFi->mNextKF;
- if(pNext)
- {
- cv::Mat Owp = pNext->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));
- }
- }
- glEnd();
- }
- vector<Map*> vpMaps = mpAtlas->GetAllMaps();
- if(bDrawKF)
- {
- for(Map* pMap : vpMaps)
- {
- if(pMap == mpAtlas->GetCurrentMap())
- continue;
- vector<KeyFrame*> vpKFs = pMap->GetAllKeyFrames();
- for(size_t i=0; i<vpKFs.size(); i++)
- {
- KeyFrame* pKF = vpKFs[i];
- cv::Mat Twc = pKF->GetPoseInverse().t();
- unsigned int index_color = pKF->mnOriginMapId;
- glPushMatrix();
- glMultMatrixf(Twc.ptr<GLfloat>(0));
- if(!vpKFs[i]->GetParent())
- {
- glLineWidth(mKeyFrameLineWidth*5);
- glColor3f(1.0f,0.0f,0.0f);
- glBegin(GL_LINES);
- }
- else
- {
- glLineWidth(mKeyFrameLineWidth);
-
- glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]);
- 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();
- }
- }
- }
- }
- void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc)
- {
- const float &w = mCameraSize;
- const float h = w*0.75;
- const float z = w*0.6;
- glPushMatrix();
- #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();
- }
- void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw)
- {
- unique_lock<mutex> lock(mMutexCamera);
- mCameraPose = Tcw.clone();
- }
- void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw)
- {
- 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;
- MOw.SetIdentity();
- MOw.m[12] = twc.at<float>(0);
- MOw.m[13] = twc.at<float>(1);
- MOw.m[14] = twc.at<float>(2);
- }
- else
- {
- M.SetIdentity();
- MOw.SetIdentity();
- }
- }
- void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw, pangolin::OpenGlMatrix &MTwwp)
- {
- if(!mCameraPose.empty())
- {
- cv::Mat Rwc(3,3,CV_32F);
- cv::Mat twc(3,1,CV_32F);
- cv::Mat Rwwp(3,3,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;
- MOw.SetIdentity();
- MOw.m[12] = twc.at<float>(0);
- MOw.m[13] = twc.at<float>(1);
- MOw.m[14] = twc.at<float>(2);
- MTwwp.SetIdentity();
- MTwwp.m[0] = Rwwp.at<float>(0,0);
- MTwwp.m[1] = Rwwp.at<float>(1,0);
- MTwwp.m[2] = Rwwp.at<float>(2,0);
- MTwwp.m[4] = Rwwp.at<float>(0,1);
- MTwwp.m[5] = Rwwp.at<float>(1,1);
- MTwwp.m[6] = Rwwp.at<float>(2,1);
- MTwwp.m[8] = Rwwp.at<float>(0,2);
- MTwwp.m[9] = Rwwp.at<float>(1,2);
- MTwwp.m[10] = Rwwp.at<float>(2,2);
- MTwwp.m[12] = twc.at<float>(0);
- MTwwp.m[13] = twc.at<float>(1);
- MTwwp.m[14] = twc.at<float>(2);
- }
- else
- {
- M.SetIdentity();
- MOw.SetIdentity();
- MTwwp.SetIdentity();
- }
- }
- }
|