Skip to content

Commit

Permalink
Do not instantiate viewers when not asked to use GUI
Browse files Browse the repository at this point in the history
  • Loading branch information
joydeep-b committed Nov 4, 2016
1 parent 6b2df80 commit 411e6af
Show file tree
Hide file tree
Showing 4 changed files with 59 additions and 32 deletions.
2 changes: 2 additions & 0 deletions include/System.h
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,8 @@ class System
std::mutex mMutexMode;
bool mbActivateLocalizationMode;
bool mbDeactivateLocalizationMode;

const bool enable_gui;
};

}// namespace ORB_SLAM
Expand Down
8 changes: 5 additions & 3 deletions include/Tracking.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class LoopClosing;
class System;

class Tracking
{
{

public:
Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap,
Expand Down Expand Up @@ -169,10 +169,10 @@ class Tracking
KeyFrame* mpReferenceKF;
std::vector<KeyFrame*> mvpLocalKeyFrames;
std::vector<MapPoint*> mvpLocalMapPoints;

// System
System* mpSystem;

//Drawers
Viewer* mpViewer;
FrameDrawer* mpFrameDrawer;
Expand Down Expand Up @@ -214,6 +214,8 @@ class Tracking
bool mbRGB;

list<MapPoint*> mlpTemporalPoints;

bool enable_gui;
};

} //namespace ORB_SLAM
Expand Down
52 changes: 32 additions & 20 deletions src/System.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,18 @@
namespace ORB_SLAM2
{

System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor,
const bool bUseViewer):mSensor(sensor),mbReset(false),mbActivateLocalizationMode(false),
mbDeactivateLocalizationMode(false)
{
System::System(const string &strVocFile,
const string &strSettingsFile,
const eSensor sensor,
const bool bUseViewer) :
mSensor(sensor),
mpViewer(nullptr),
mpFrameDrawer(nullptr),
mpMapDrawer(nullptr),
mbReset(false),
mbActivateLocalizationMode(false),
mbDeactivateLocalizationMode(false),
enable_gui(bUseViewer) {
// Output welcome message
cout << endl <<
"ORB-SLAM2 Copyright (C) 2014-2016 Raul Mur-Artal, University of Zaragoza." << endl <<
Expand Down Expand Up @@ -77,9 +85,11 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS
//Create the Map
mpMap = new Map();

//Create Drawers. These are used by the Viewer
mpFrameDrawer = new FrameDrawer(mpMap);
mpMapDrawer = new MapDrawer(mpMap, strSettingsFile);
if (enable_gui) {
//Create Drawers. These are used by the Viewer
mpFrameDrawer = new FrameDrawer(mpMap);
mpMapDrawer = new MapDrawer(mpMap, strSettingsFile);
}

//Initialize the Tracking thread
//(it will live in the main thread of execution, the one that called this constructor)
Expand All @@ -94,12 +104,14 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS
mpLoopCloser = new LoopClosing(mpMap, mpKeyFrameDatabase, mpVocabulary, mSensor!=MONOCULAR);
mptLoopClosing = new thread(&ORB_SLAM2::LoopClosing::Run, mpLoopCloser);

//Initialize the Viewer thread and launch
mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile);
if(bUseViewer)
mptViewer = new thread(&Viewer::Run, mpViewer);
if (enable_gui) {
//Initialize the Viewer thread and launch
mpViewer =
new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile);
mptViewer = new thread(&Viewer::Run, mpViewer);
mpTracker->SetViewer(mpViewer);
}

mpTracker->SetViewer(mpViewer);

//Set pointers between threads
mpTracker->SetLocalMapper(mpLocalMapper);
Expand All @@ -118,7 +130,7 @@ cv::Mat System::TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const
{
cerr << "ERROR: you called TrackStereo but input sensor was not set to STEREO." << endl;
exit(-1);
}
}

// Check mode change
{
Expand Down Expand Up @@ -163,7 +175,7 @@ cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const doub
{
cerr << "ERROR: you called TrackRGBD but input sensor was not set to RGBD." << endl;
exit(-1);
}
}

// Check mode change
{
Expand Down Expand Up @@ -269,16 +281,16 @@ void System::Shutdown()
{
mpLocalMapper->RequestFinish();
mpLoopCloser->RequestFinish();
mpViewer->RequestFinish();
if (enable_gui) mpViewer->RequestFinish();

// Wait until all thread have effectively stopped
while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() ||
!mpViewer->isFinished() || mpLoopCloser->isRunningGBA())
{
while(!mpLocalMapper->isFinished() ||
!mpLoopCloser->isFinished() ||
!(enable_gui && mpViewer->isFinished()) ||
mpLoopCloser->isRunningGBA()) {
usleep(5000);
}

pangolin::BindToContext("ORB-SLAM2: Map Viewer");
if (enable_gui) pangolin::BindToContext("ORB-SLAM2: Map Viewer");
}

void System::SaveTrajectoryTUM(const string &filename)
Expand Down
29 changes: 20 additions & 9 deletions src/Tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,11 @@ namespace ORB_SLAM2
Tracking::Tracking(System *pSys, ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor):
mState(NO_IMAGES_YET), mSensor(sensor), mbOnlyTracking(false), mbVO(false), mpORBVocabulary(pVoc),
mpKeyFrameDB(pKFDB), mpInitializer(static_cast<Initializer*>(NULL)), mpSystem(pSys),
mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap), mnLastRelocFrameId(0)
{
mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap),
mnLastRelocFrameId(0), enable_gui(true) {
if (!mpFrameDrawer || !mpMapDrawer) {
enable_gui = false;
}
// Load camera parameters from settings file

cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
Expand Down Expand Up @@ -283,7 +286,7 @@ void Tracking::Track()
else
MonocularInitialization();

mpFrameDrawer->Update(this);
if (enable_gui) mpFrameDrawer->Update(this);

if(mState!=OK)
return;
Expand Down Expand Up @@ -414,8 +417,10 @@ void Tracking::Track()
else
mState=LOST;

// Update drawer
mpFrameDrawer->Update(this);
if (enable_gui) {
// Update drawer
mpFrameDrawer->Update(this);
}

// If tracking were good, check if we insert a keyframe
if(bOK)
Expand All @@ -431,7 +436,9 @@ void Tracking::Track()
else
mVelocity = cv::Mat();

mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
if (enable_gui) {
mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
}

// Clean VO matches
for(int i=0; i<mCurrentFrame.N; i++)
Expand Down Expand Up @@ -554,7 +561,9 @@ void Tracking::StereoInitialization()

mpMap->mvpKeyFrameOrigins.push_back(pKFini);

mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
if (enable_gui) {
mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
}

mState=OK;
}
Expand Down Expand Up @@ -729,7 +738,9 @@ void Tracking::CreateInitialMapMonocular()

mpMap->SetReferenceMapPoints(mvpLocalMapPoints);

mpMapDrawer->SetCurrentCameraPose(pKFcur->GetPose());
if (enable_gui) {
mpMapDrawer->SetCurrentCameraPose(pKFcur->GetPose());
}

mpMap->mvpKeyFrameOrigins.push_back(pKFini);

Expand Down Expand Up @@ -916,7 +927,7 @@ bool Tracking::TrackWithMotionModel()
else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0)
nmatchesMap++;
}
}
}

if(mbOnlyTracking)
{
Expand Down

0 comments on commit 411e6af

Please sign in to comment.