/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see .
*/
#include "MapDrawer.h"
#include "MapPoint.h"
#include "KeyFrame.h"
#include
#include
namespace ORB_SLAM3
{
MapDrawer::MapDrawer(Atlas* pAtlas, const string &strSettingPath, Settings* settings):mpAtlas(pAtlas)
{
if(settings){
newParameterLoader(settings);
}
else{
cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
bool is_correct = ParseViewerParamFile(fSettings);
if(!is_correct)
{
std::cerr << "**ERROR in the config file, the format is not correct**" << std::endl;
try
{
throw -1;
}
catch(exception &e)
{
}
}
}
}
void MapDrawer::newParameterLoader(Settings *settings) {
mKeyFrameSize = settings->keyFrameSize();
mKeyFrameLineWidth = settings->keyFrameLineWidth();
mGraphLineWidth = settings->graphLineWidth();
mPointSize = settings->pointSize();
mCameraSize = settings->cameraSize();
mCameraLineWidth = settings->cameraLineWidth();
}
bool MapDrawer::ParseViewerParamFile(cv::FileStorage &fSettings)
{
bool b_miss_params = false;
cv::FileNode node = fSettings["Viewer.KeyFrameSize"];
if(!node.empty())
{
mKeyFrameSize = node.real();
}
else
{
std::cerr << "*Viewer.KeyFrameSize parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
node = fSettings["Viewer.KeyFrameLineWidth"];
if(!node.empty())
{
mKeyFrameLineWidth = node.real();
}
else
{
std::cerr << "*Viewer.KeyFrameLineWidth parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
node = fSettings["Viewer.GraphLineWidth"];
if(!node.empty())
{
mGraphLineWidth = node.real();
}
else
{
std::cerr << "*Viewer.GraphLineWidth parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
node = fSettings["Viewer.PointSize"];
if(!node.empty())
{
mPointSize = node.real();
}
else
{
std::cerr << "*Viewer.PointSize parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
node = fSettings["Viewer.CameraSize"];
if(!node.empty())
{
mCameraSize = node.real();
}
else
{
std::cerr << "*Viewer.CameraSize parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
node = fSettings["Viewer.CameraLineWidth"];
if(!node.empty())
{
mCameraLineWidth = node.real();
}
else
{
std::cerr << "*Viewer.CameraLineWidth parameter doesn't exist or is not a real number*" << std::endl;
b_miss_params = true;
}
return !b_miss_params;
}
void MapDrawer::DrawMapPoints()
{
Map* pActiveMap = mpAtlas->GetCurrentMap();
if(!pActiveMap)
return;
const vector &vpMPs = pActiveMap->GetAllMapPoints();
const vector &vpRefMPs = pActiveMap->GetReferenceMapPoints();
set 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(); iisBad() || spRefMPs.count(vpMPs[i]))
continue;
Eigen::Matrix pos = vpMPs[i]->GetWorldPos();
glVertex3f(pos(0),pos(1),pos(2));
}
glEnd();
glPointSize(mPointSize);
glBegin(GL_POINTS);
glColor3f(1.0,0.0,0.0);
for(set::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++)
{
if((*sit)->isBad())
continue;
Eigen::Matrix pos = (*sit)->GetWorldPos();
glVertex3f(pos(0),pos(1),pos(2));
}
glEnd();
}
void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph, const bool bDrawOptLba)
{
const float &w = mKeyFrameSize;
const float h = w*0.75;
const float z = w*0.6;
Map* pActiveMap = mpAtlas->GetCurrentMap();
// DEBUG LBA
std::set sOptKFs = pActiveMap->msOptKFs;
std::set sFixedKFs = pActiveMap->msFixedKFs;
if(!pActiveMap)
return;
const vector vpKFs = pActiveMap->GetAllKeyFrames();
if(bDrawKF)
{
for(size_t i=0; iGetPoseInverse().matrix();
unsigned int index_color = pKF->mnOriginMapId;
glPushMatrix();
glMultMatrixf((GLfloat*)Twc.data());
if(!pKF->GetParent()) // It is the first KF in the map
{
glLineWidth(mKeyFrameLineWidth*5);
glColor3f(1.0f,0.0f,0.0f);
glBegin(GL_LINES);
}
else
{
//cout << "Child KF: " << vpKFs[i]->mnId << endl;
glLineWidth(mKeyFrameLineWidth);
if (bDrawOptLba) {
if(sOptKFs.find(pKF->mnId) != sOptKFs.end())
{
glColor3f(0.0f,1.0f,0.0f); // Green -> Opt KFs
}
else if(sFixedKFs.find(pKF->mnId) != sFixedKFs.end())
{
glColor3f(1.0f,0.0f,0.0f); // Red -> Fixed KFs
}
else
{
glColor3f(0.0f,0.0f,1.0f); // Basic color
}
}
else
{
glColor3f(0.0f,0.0f,1.0f); // Basic color
}
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);
// cout << "-----------------Draw graph-----------------" << endl;
for(size_t i=0; i vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100);
Eigen::Vector3f Ow = vpKFs[i]->GetCameraCenter();
if(!vCovKFs.empty())
{
for(vector::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++)
{
if((*vit)->mnIdmnId)
continue;
Eigen::Vector3f Ow2 = (*vit)->GetCameraCenter();
glVertex3f(Ow(0),Ow(1),Ow(2));
glVertex3f(Ow2(0),Ow2(1),Ow2(2));
}
}
// Spanning tree
KeyFrame* pParent = vpKFs[i]->GetParent();
if(pParent)
{
Eigen::Vector3f Owp = pParent->GetCameraCenter();
glVertex3f(Ow(0),Ow(1),Ow(2));
glVertex3f(Owp(0),Owp(1),Owp(2));
}
// Loops
set sLoopKFs = vpKFs[i]->GetLoopEdges();
for(set::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++)
{
if((*sit)->mnIdmnId)
continue;
Eigen::Vector3f Owl = (*sit)->GetCameraCenter();
glVertex3f(Ow(0),Ow(1),Ow(2));
glVertex3f(Owl(0),Owl(1),Owl(2));
}
}
glEnd();
}
if(bDrawInertialGraph && pActiveMap->isImuInitialized())
{
glLineWidth(mGraphLineWidth);
glColor4f(1.0f,0.0f,0.0f,0.6f);
glBegin(GL_LINES);
//Draw inertial links
for(size_t i=0; iGetCameraCenter();
KeyFrame* pNext = pKFi->mNextKF;
if(pNext)
{
Eigen::Vector3f Owp = pNext->GetCameraCenter();
glVertex3f(Ow(0),Ow(1),Ow(2));
glVertex3f(Owp(0),Owp(1),Owp(2));
}
}
glEnd();
}
vector