123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331 |
- #include "Viewer.h"
- #include <pangolin/pangolin.h>
- #include <mutex>
- namespace ORB_SLAM3
- {
- Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath):
- both(false), mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking),
- mbFinishRequested(false), mbFinished(true), mbStopped(true), mbStopRequested(false)
- {
- cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
- float fps = fSettings["Camera.fps"];
- if(fps<1)
- fps=30;
- mT = 1e3/fps;
- mImageWidth = fSettings["Camera.width"];
- mImageHeight = fSettings["Camera.height"];
- if(mImageWidth<1 || mImageHeight<1)
- {
- mImageWidth = 640;
- mImageHeight = 480;
- }
- mViewpointX = fSettings["Viewer.ViewpointX"];
- mViewpointY = fSettings["Viewer.ViewpointY"];
- mViewpointZ = fSettings["Viewer.ViewpointZ"];
- mViewpointF = fSettings["Viewer.ViewpointF"];
- mbStopTrack = false;
- }
- void Viewer::Run()
- {
- mbFinished = false;
- mbStopped = false;
- pangolin::CreateWindowAndBind("ORB-SLAM3: Map Viewer",1024,768);
-
- glEnable(GL_DEPTH_TEST);
-
- glEnable (GL_BLEND);
- glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
- pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175));
- pangolin::Var<bool> menuFollowCamera("menu.Follow Camera",true,true);
- pangolin::Var<bool> menuCamView("menu.Camera View",false,false);
- pangolin::Var<bool> menuTopView("menu.Top View",false,false);
-
- pangolin::Var<bool> menuShowPoints("menu.Show Points",true,true);
- pangolin::Var<bool> menuShowKeyFrames("menu.Show KeyFrames",true,true);
- pangolin::Var<bool> menuShowGraph("menu.Show Graph",false,true);
- pangolin::Var<bool> menuShowInertialGraph("menu.Show Inertial Graph",true,true);
- pangolin::Var<bool> menuLocalizationMode("menu.Localization Mode",false,true);
- pangolin::Var<bool> menuReset("menu.Reset",false,false);
- pangolin::Var<bool> menuStepByStep("menu.Step By Step",false,true);
- pangolin::Var<bool> menuStep("menu.Step",false,false);
-
- pangolin::OpenGlRenderState s_cam(
- pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000),
- pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)
- );
-
- pangolin::View& d_cam = pangolin::CreateDisplay()
- .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f)
- .SetHandler(new pangolin::Handler3D(s_cam));
- pangolin::OpenGlMatrix Twc, Twr;
- Twc.SetIdentity();
- pangolin::OpenGlMatrix Ow;
- Ow.SetIdentity();
- pangolin::OpenGlMatrix Twwp;
- Twwp.SetIdentity();
- cv::namedWindow("ORB-SLAM3: Current Frame");
- bool bFollow = true;
- bool bLocalizationMode = false;
- bool bStepByStep = false;
- bool bCameraView = true;
- if(mpTracker->mSensor == mpSystem->MONOCULAR || mpTracker->mSensor == mpSystem->STEREO || mpTracker->mSensor == mpSystem->RGBD)
- {
- menuShowGraph = true;
- }
- while(1)
- {
- glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
- mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc,Ow,Twwp);
- if(mbStopTrack)
- {
- menuStepByStep = true;
- mbStopTrack = false;
- }
- if(menuFollowCamera && bFollow)
- {
- if(bCameraView)
- s_cam.Follow(Twc);
- else
- s_cam.Follow(Ow);
- }
- else if(menuFollowCamera && !bFollow)
- {
- if(bCameraView)
- {
- s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000));
- s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
- s_cam.Follow(Twc);
- }
- else
- {
- s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,1000));
- s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,10, 0,0,0,0.0,0.0, 1.0));
- s_cam.Follow(Ow);
- }
- bFollow = true;
- }
- else if(!menuFollowCamera && bFollow)
- {
- bFollow = false;
- }
- if(menuCamView)
- {
- menuCamView = false;
- bCameraView = true;
- s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,10000));
- s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
- s_cam.Follow(Twc);
- }
- if(menuTopView && mpMapDrawer->mpAtlas->isImuInitialized())
- {
- menuTopView = false;
- bCameraView = false;
-
- s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,10000));
- s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,50, 0,0,0,0.0,0.0, 1.0));
- s_cam.Follow(Ow);
- }
-
- if(menuLocalizationMode && !bLocalizationMode)
- {
- mpSystem->ActivateLocalizationMode();
- bLocalizationMode = true;
- }
- else if(!menuLocalizationMode && bLocalizationMode)
- {
- mpSystem->DeactivateLocalizationMode();
- bLocalizationMode = false;
- }
- if(menuStepByStep && !bStepByStep)
- {
- mpTracker->SetStepByStep(true);
- bStepByStep = true;
- }
- else if(!menuStepByStep && bStepByStep)
- {
- mpTracker->SetStepByStep(false);
- bStepByStep = false;
- }
- if(menuStep)
- {
- mpTracker->mbStep = true;
- menuStep = false;
- }
- d_cam.Activate(s_cam);
- glClearColor(1.0f,1.0f,1.0f,1.0f);
- mpMapDrawer->DrawCurrentCamera(Twc);
- if(menuShowKeyFrames || menuShowGraph || menuShowInertialGraph)
- mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph, menuShowInertialGraph);
- if(menuShowPoints)
- mpMapDrawer->DrawMapPoints();
- pangolin::FinishFrame();
- cv::Mat toShow;
- cv::Mat im = mpFrameDrawer->DrawFrame(true);
- if(both){
- cv::Mat imRight = mpFrameDrawer->DrawRightFrame();
- cv::hconcat(im,imRight,toShow);
- }
- else{
- toShow = im;
- }
- cv::imshow("ORB-SLAM3: Current Frame",toShow);
- cv::waitKey(mT);
- if(menuReset)
- {
- menuShowGraph = true;
- menuShowInertialGraph = true;
- menuShowKeyFrames = true;
- menuShowPoints = true;
- menuLocalizationMode = false;
- if(bLocalizationMode)
- mpSystem->DeactivateLocalizationMode();
- bLocalizationMode = false;
- bFollow = true;
- menuFollowCamera = true;
-
- mpSystem->ResetActiveMap();
- menuReset = false;
- }
- if(Stop())
- {
- while(isStopped())
- {
- usleep(3000);
- }
- }
- if(CheckFinish())
- break;
- }
- SetFinish();
- }
- void Viewer::RequestFinish()
- {
- unique_lock<mutex> lock(mMutexFinish);
- mbFinishRequested = true;
- }
- bool Viewer::CheckFinish()
- {
- unique_lock<mutex> lock(mMutexFinish);
- return mbFinishRequested;
- }
- void Viewer::SetFinish()
- {
- unique_lock<mutex> lock(mMutexFinish);
- mbFinished = true;
- }
- bool Viewer::isFinished()
- {
- unique_lock<mutex> lock(mMutexFinish);
- return mbFinished;
- }
- void Viewer::RequestStop()
- {
- unique_lock<mutex> lock(mMutexStop);
- if(!mbStopped)
- mbStopRequested = true;
- }
- bool Viewer::isStopped()
- {
- unique_lock<mutex> lock(mMutexStop);
- return mbStopped;
- }
- bool Viewer::Stop()
- {
- unique_lock<mutex> lock(mMutexStop);
- unique_lock<mutex> lock2(mMutexFinish);
- if(mbFinishRequested)
- return false;
- else if(mbStopRequested)
- {
- mbStopped = true;
- mbStopRequested = false;
- return true;
- }
- return false;
- }
- void Viewer::Release()
- {
- unique_lock<mutex> lock(mMutexStop);
- mbStopped = false;
- }
- void Viewer::SetTrackingPause()
- {
- mbStopTrack = true;
- }
- }
|