Viewer.cc 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #include "Viewer.h"
  19. #include <pangolin/pangolin.h>
  20. #include <mutex>
  21. namespace ORB_SLAM3
  22. {
  23. Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath):
  24. both(false), mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking),
  25. mbFinishRequested(false), mbFinished(true), mbStopped(true), mbStopRequested(false)
  26. {
  27. cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
  28. float fps = fSettings["Camera.fps"];
  29. if(fps<1)
  30. fps=30;
  31. mT = 1e3/fps;
  32. mImageWidth = fSettings["Camera.width"];
  33. mImageHeight = fSettings["Camera.height"];
  34. if(mImageWidth<1 || mImageHeight<1)
  35. {
  36. mImageWidth = 640;
  37. mImageHeight = 480;
  38. }
  39. mViewpointX = fSettings["Viewer.ViewpointX"];
  40. mViewpointY = fSettings["Viewer.ViewpointY"];
  41. mViewpointZ = fSettings["Viewer.ViewpointZ"];
  42. mViewpointF = fSettings["Viewer.ViewpointF"];
  43. mbStopTrack = false;
  44. }
  45. void Viewer::Run()
  46. {
  47. mbFinished = false;
  48. mbStopped = false;
  49. pangolin::CreateWindowAndBind("ORB-SLAM3: Map Viewer",1024,768);
  50. // 3D Mouse handler requires depth testing to be enabled
  51. glEnable(GL_DEPTH_TEST);
  52. // Issue specific OpenGl we might need
  53. glEnable (GL_BLEND);
  54. glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
  55. pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175));
  56. pangolin::Var<bool> menuFollowCamera("menu.Follow Camera",true,true);
  57. pangolin::Var<bool> menuCamView("menu.Camera View",false,false);
  58. pangolin::Var<bool> menuTopView("menu.Top View",false,false);
  59. // pangolin::Var<bool> menuSideView("menu.Side View",false,false);
  60. pangolin::Var<bool> menuShowPoints("menu.Show Points",true,true);
  61. pangolin::Var<bool> menuShowKeyFrames("menu.Show KeyFrames",true,true);
  62. pangolin::Var<bool> menuShowGraph("menu.Show Graph",false,true);
  63. pangolin::Var<bool> menuShowInertialGraph("menu.Show Inertial Graph",true,true);
  64. pangolin::Var<bool> menuLocalizationMode("menu.Localization Mode",false,true);
  65. pangolin::Var<bool> menuReset("menu.Reset",false,false);
  66. pangolin::Var<bool> menuStepByStep("menu.Step By Step",false,true); // false, true
  67. pangolin::Var<bool> menuStep("menu.Step",false,false);
  68. // Define Camera Render Object (for view / scene browsing)
  69. pangolin::OpenGlRenderState s_cam(
  70. pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000),
  71. pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)
  72. );
  73. // Add named OpenGL viewport to window and provide 3D Handler
  74. pangolin::View& d_cam = pangolin::CreateDisplay()
  75. .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f)
  76. .SetHandler(new pangolin::Handler3D(s_cam));
  77. pangolin::OpenGlMatrix Twc, Twr;
  78. Twc.SetIdentity();
  79. pangolin::OpenGlMatrix Ow; // Oriented with g in the z axis
  80. Ow.SetIdentity();
  81. pangolin::OpenGlMatrix Twwp; // Oriented with g in the z axis, but y and x from camera
  82. Twwp.SetIdentity();
  83. cv::namedWindow("ORB-SLAM3: Current Frame");
  84. bool bFollow = true;
  85. bool bLocalizationMode = false;
  86. bool bStepByStep = false;
  87. bool bCameraView = true;
  88. if(mpTracker->mSensor == mpSystem->MONOCULAR || mpTracker->mSensor == mpSystem->STEREO || mpTracker->mSensor == mpSystem->RGBD)
  89. {
  90. menuShowGraph = true;
  91. }
  92. while(1)
  93. {
  94. glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
  95. mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc,Ow,Twwp);
  96. if(mbStopTrack)
  97. {
  98. menuStepByStep = true;
  99. mbStopTrack = false;
  100. }
  101. if(menuFollowCamera && bFollow)
  102. {
  103. if(bCameraView)
  104. s_cam.Follow(Twc);
  105. else
  106. s_cam.Follow(Ow);
  107. }
  108. else if(menuFollowCamera && !bFollow)
  109. {
  110. if(bCameraView)
  111. {
  112. s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000));
  113. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
  114. s_cam.Follow(Twc);
  115. }
  116. else
  117. {
  118. s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,1000));
  119. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,10, 0,0,0,0.0,0.0, 1.0));
  120. s_cam.Follow(Ow);
  121. }
  122. bFollow = true;
  123. }
  124. else if(!menuFollowCamera && bFollow)
  125. {
  126. bFollow = false;
  127. }
  128. if(menuCamView)
  129. {
  130. menuCamView = false;
  131. bCameraView = true;
  132. s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,10000));
  133. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
  134. s_cam.Follow(Twc);
  135. }
  136. if(menuTopView && mpMapDrawer->mpAtlas->isImuInitialized())
  137. {
  138. menuTopView = false;
  139. bCameraView = false;
  140. /*s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,1000));
  141. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,10, 0,0,0,0.0,0.0, 1.0));*/
  142. s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,10000));
  143. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0,0.01,50, 0,0,0,0.0,0.0, 1.0));
  144. s_cam.Follow(Ow);
  145. }
  146. /*if(menuSideView && mpMapDrawer->mpAtlas->isImuInitialized())
  147. {
  148. s_cam.SetProjectionMatrix(pangolin::ProjectionMatrix(1024,768,3000,3000,512,389,0.1,10000));
  149. s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(0.0,0.1,30.0,0,0,0,0.0,0.0,1.0));
  150. s_cam.Follow(Twwp);
  151. }*/
  152. if(menuLocalizationMode && !bLocalizationMode)
  153. {
  154. mpSystem->ActivateLocalizationMode();
  155. bLocalizationMode = true;
  156. }
  157. else if(!menuLocalizationMode && bLocalizationMode)
  158. {
  159. mpSystem->DeactivateLocalizationMode();
  160. bLocalizationMode = false;
  161. }
  162. if(menuStepByStep && !bStepByStep)
  163. {
  164. mpTracker->SetStepByStep(true);
  165. bStepByStep = true;
  166. }
  167. else if(!menuStepByStep && bStepByStep)
  168. {
  169. mpTracker->SetStepByStep(false);
  170. bStepByStep = false;
  171. }
  172. if(menuStep)
  173. {
  174. mpTracker->mbStep = true;
  175. menuStep = false;
  176. }
  177. d_cam.Activate(s_cam);
  178. glClearColor(1.0f,1.0f,1.0f,1.0f);
  179. mpMapDrawer->DrawCurrentCamera(Twc);
  180. if(menuShowKeyFrames || menuShowGraph || menuShowInertialGraph)
  181. mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph, menuShowInertialGraph);
  182. if(menuShowPoints)
  183. mpMapDrawer->DrawMapPoints();
  184. pangolin::FinishFrame();
  185. cv::Mat toShow;
  186. cv::Mat im = mpFrameDrawer->DrawFrame(true);
  187. if(both){
  188. cv::Mat imRight = mpFrameDrawer->DrawRightFrame();
  189. cv::hconcat(im,imRight,toShow);
  190. }
  191. else{
  192. toShow = im;
  193. }
  194. cv::imshow("ORB-SLAM3: Current Frame",toShow);
  195. cv::waitKey(mT);
  196. if(menuReset)
  197. {
  198. menuShowGraph = true;
  199. menuShowInertialGraph = true;
  200. menuShowKeyFrames = true;
  201. menuShowPoints = true;
  202. menuLocalizationMode = false;
  203. if(bLocalizationMode)
  204. mpSystem->DeactivateLocalizationMode();
  205. bLocalizationMode = false;
  206. bFollow = true;
  207. menuFollowCamera = true;
  208. //mpSystem->Reset();
  209. mpSystem->ResetActiveMap();
  210. menuReset = false;
  211. }
  212. if(Stop())
  213. {
  214. while(isStopped())
  215. {
  216. usleep(3000);
  217. }
  218. }
  219. if(CheckFinish())
  220. break;
  221. }
  222. SetFinish();
  223. }
  224. void Viewer::RequestFinish()
  225. {
  226. unique_lock<mutex> lock(mMutexFinish);
  227. mbFinishRequested = true;
  228. }
  229. bool Viewer::CheckFinish()
  230. {
  231. unique_lock<mutex> lock(mMutexFinish);
  232. return mbFinishRequested;
  233. }
  234. void Viewer::SetFinish()
  235. {
  236. unique_lock<mutex> lock(mMutexFinish);
  237. mbFinished = true;
  238. }
  239. bool Viewer::isFinished()
  240. {
  241. unique_lock<mutex> lock(mMutexFinish);
  242. return mbFinished;
  243. }
  244. void Viewer::RequestStop()
  245. {
  246. unique_lock<mutex> lock(mMutexStop);
  247. if(!mbStopped)
  248. mbStopRequested = true;
  249. }
  250. bool Viewer::isStopped()
  251. {
  252. unique_lock<mutex> lock(mMutexStop);
  253. return mbStopped;
  254. }
  255. bool Viewer::Stop()
  256. {
  257. unique_lock<mutex> lock(mMutexStop);
  258. unique_lock<mutex> lock2(mMutexFinish);
  259. if(mbFinishRequested)
  260. return false;
  261. else if(mbStopRequested)
  262. {
  263. mbStopped = true;
  264. mbStopRequested = false;
  265. return true;
  266. }
  267. return false;
  268. }
  269. void Viewer::Release()
  270. {
  271. unique_lock<mutex> lock(mMutexStop);
  272. mbStopped = false;
  273. }
  274. void Viewer::SetTrackingPause()
  275. {
  276. mbStopTrack = true;
  277. }
  278. }