MapDrawer.cc 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464
  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 "MapDrawer.h"
  19. #include "MapPoint.h"
  20. #include "KeyFrame.h"
  21. #include <pangolin/pangolin.h>
  22. #include <mutex>
  23. namespace ORB_SLAM3
  24. {
  25. MapDrawer::MapDrawer(Atlas* pAtlas, const string &strSettingPath):mpAtlas(pAtlas)
  26. {
  27. cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
  28. mKeyFrameSize = fSettings["Viewer.KeyFrameSize"];
  29. mKeyFrameLineWidth = fSettings["Viewer.KeyFrameLineWidth"];
  30. mGraphLineWidth = fSettings["Viewer.GraphLineWidth"];
  31. mPointSize = fSettings["Viewer.PointSize"];
  32. mCameraSize = fSettings["Viewer.CameraSize"];
  33. mCameraLineWidth = fSettings["Viewer.CameraLineWidth"];
  34. }
  35. void MapDrawer::DrawMapPoints()
  36. {
  37. const vector<MapPoint*> &vpMPs = mpAtlas->GetAllMapPoints();
  38. const vector<MapPoint*> &vpRefMPs = mpAtlas->GetReferenceMapPoints();
  39. set<MapPoint*> spRefMPs(vpRefMPs.begin(), vpRefMPs.end());
  40. if(vpMPs.empty())
  41. return;
  42. glPointSize(mPointSize);
  43. glBegin(GL_POINTS);
  44. glColor3f(0.0,0.0,0.0);
  45. for(size_t i=0, iend=vpMPs.size(); i<iend;i++)
  46. {
  47. if(vpMPs[i]->isBad() || spRefMPs.count(vpMPs[i]))
  48. continue;
  49. cv::Mat pos = vpMPs[i]->GetWorldPos();
  50. glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));
  51. }
  52. glEnd();
  53. glPointSize(mPointSize);
  54. glBegin(GL_POINTS);
  55. glColor3f(1.0,0.0,0.0);
  56. for(set<MapPoint*>::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++)
  57. {
  58. if((*sit)->isBad())
  59. continue;
  60. cv::Mat pos = (*sit)->GetWorldPos();
  61. glVertex3f(pos.at<float>(0),pos.at<float>(1),pos.at<float>(2));
  62. }
  63. glEnd();
  64. }
  65. void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph)
  66. {
  67. const float &w = mKeyFrameSize;
  68. const float h = w*0.75;
  69. const float z = w*0.6;
  70. const vector<KeyFrame*> vpKFs = mpAtlas->GetAllKeyFrames();
  71. if(bDrawKF)
  72. {
  73. for(size_t i=0; i<vpKFs.size(); i++)
  74. {
  75. KeyFrame* pKF = vpKFs[i];
  76. cv::Mat Twc = pKF->GetPoseInverse().t();
  77. unsigned int index_color = pKF->mnOriginMapId;
  78. glPushMatrix();
  79. glMultMatrixf(Twc.ptr<GLfloat>(0));
  80. if(!pKF->GetParent()) // It is the first KF in the map
  81. {
  82. glLineWidth(mKeyFrameLineWidth*5);
  83. glColor3f(1.0f,0.0f,0.0f);
  84. glBegin(GL_LINES);
  85. //cout << "Initial KF: " << mpAtlas->GetCurrentMap()->GetOriginKF()->mnId << endl;
  86. //cout << "Parent KF: " << vpKFs[i]->mnId << endl;
  87. }
  88. else
  89. {
  90. glLineWidth(mKeyFrameLineWidth);
  91. //glColor3f(0.0f,0.0f,1.0f);
  92. glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]);
  93. glBegin(GL_LINES);
  94. }
  95. glVertex3f(0,0,0);
  96. glVertex3f(w,h,z);
  97. glVertex3f(0,0,0);
  98. glVertex3f(w,-h,z);
  99. glVertex3f(0,0,0);
  100. glVertex3f(-w,-h,z);
  101. glVertex3f(0,0,0);
  102. glVertex3f(-w,h,z);
  103. glVertex3f(w,h,z);
  104. glVertex3f(w,-h,z);
  105. glVertex3f(-w,h,z);
  106. glVertex3f(-w,-h,z);
  107. glVertex3f(-w,h,z);
  108. glVertex3f(w,h,z);
  109. glVertex3f(-w,-h,z);
  110. glVertex3f(w,-h,z);
  111. glEnd();
  112. glPopMatrix();
  113. //Draw lines with Loop and Merge candidates
  114. /*glLineWidth(mGraphLineWidth);
  115. glColor4f(1.0f,0.6f,0.0f,1.0f);
  116. glBegin(GL_LINES);
  117. cv::Mat Ow = pKF->GetCameraCenter();
  118. const vector<KeyFrame*> vpLoopCandKFs = pKF->mvpLoopCandKFs;
  119. if(!vpLoopCandKFs.empty())
  120. {
  121. for(vector<KeyFrame*>::const_iterator vit=vpLoopCandKFs.begin(), vend=vpLoopCandKFs.end(); vit!=vend; vit++)
  122. {
  123. cv::Mat Ow2 = (*vit)->GetCameraCenter();
  124. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  125. glVertex3f(Ow2.at<float>(0),Ow2.at<float>(1),Ow2.at<float>(2));
  126. }
  127. }
  128. const vector<KeyFrame*> vpMergeCandKFs = pKF->mvpMergeCandKFs;
  129. if(!vpMergeCandKFs.empty())
  130. {
  131. for(vector<KeyFrame*>::const_iterator vit=vpMergeCandKFs.begin(), vend=vpMergeCandKFs.end(); vit!=vend; vit++)
  132. {
  133. cv::Mat Ow2 = (*vit)->GetCameraCenter();
  134. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  135. glVertex3f(Ow2.at<float>(0),Ow2.at<float>(1),Ow2.at<float>(2));
  136. }
  137. }*/
  138. glEnd();
  139. }
  140. }
  141. if(bDrawGraph)
  142. {
  143. glLineWidth(mGraphLineWidth);
  144. glColor4f(0.0f,1.0f,0.0f,0.6f);
  145. glBegin(GL_LINES);
  146. // cout << "-----------------Draw graph-----------------" << endl;
  147. for(size_t i=0; i<vpKFs.size(); i++)
  148. {
  149. // Covisibility Graph
  150. const vector<KeyFrame*> vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100);
  151. cv::Mat Ow = vpKFs[i]->GetCameraCenter();
  152. if(!vCovKFs.empty())
  153. {
  154. for(vector<KeyFrame*>::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++)
  155. {
  156. if((*vit)->mnId<vpKFs[i]->mnId)
  157. continue;
  158. cv::Mat Ow2 = (*vit)->GetCameraCenter();
  159. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  160. glVertex3f(Ow2.at<float>(0),Ow2.at<float>(1),Ow2.at<float>(2));
  161. }
  162. }
  163. // Spanning tree
  164. KeyFrame* pParent = vpKFs[i]->GetParent();
  165. if(pParent)
  166. {
  167. cv::Mat Owp = pParent->GetCameraCenter();
  168. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  169. glVertex3f(Owp.at<float>(0),Owp.at<float>(1),Owp.at<float>(2));
  170. }
  171. // Loops
  172. set<KeyFrame*> sLoopKFs = vpKFs[i]->GetLoopEdges();
  173. for(set<KeyFrame*>::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++)
  174. {
  175. if((*sit)->mnId<vpKFs[i]->mnId)
  176. continue;
  177. cv::Mat Owl = (*sit)->GetCameraCenter();
  178. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  179. glVertex3f(Owl.at<float>(0),Owl.at<float>(1),Owl.at<float>(2));
  180. }
  181. }
  182. glEnd();
  183. }
  184. if(bDrawInertialGraph && mpAtlas->isImuInitialized())
  185. {
  186. glLineWidth(mGraphLineWidth);
  187. glColor4f(1.0f,0.0f,0.0f,0.6f);
  188. glBegin(GL_LINES);
  189. //Draw inertial links
  190. for(size_t i=0; i<vpKFs.size(); i++)
  191. {
  192. KeyFrame* pKFi = vpKFs[i];
  193. cv::Mat Ow = pKFi->GetCameraCenter();
  194. KeyFrame* pNext = pKFi->mNextKF;
  195. if(pNext)
  196. {
  197. cv::Mat Owp = pNext->GetCameraCenter();
  198. glVertex3f(Ow.at<float>(0),Ow.at<float>(1),Ow.at<float>(2));
  199. glVertex3f(Owp.at<float>(0),Owp.at<float>(1),Owp.at<float>(2));
  200. }
  201. }
  202. glEnd();
  203. }
  204. vector<Map*> vpMaps = mpAtlas->GetAllMaps();
  205. if(bDrawKF)
  206. {
  207. for(Map* pMap : vpMaps)
  208. {
  209. if(pMap == mpAtlas->GetCurrentMap())
  210. continue;
  211. vector<KeyFrame*> vpKFs = pMap->GetAllKeyFrames();
  212. for(size_t i=0; i<vpKFs.size(); i++)
  213. {
  214. KeyFrame* pKF = vpKFs[i];
  215. cv::Mat Twc = pKF->GetPoseInverse().t();
  216. unsigned int index_color = pKF->mnOriginMapId;
  217. glPushMatrix();
  218. glMultMatrixf(Twc.ptr<GLfloat>(0));
  219. if(!vpKFs[i]->GetParent()) // It is the first KF in the map
  220. {
  221. glLineWidth(mKeyFrameLineWidth*5);
  222. glColor3f(1.0f,0.0f,0.0f);
  223. glBegin(GL_LINES);
  224. }
  225. else
  226. {
  227. glLineWidth(mKeyFrameLineWidth);
  228. //glColor3f(0.0f,0.0f,1.0f);
  229. glColor3f(mfFrameColors[index_color][0],mfFrameColors[index_color][1],mfFrameColors[index_color][2]);
  230. glBegin(GL_LINES);
  231. }
  232. glVertex3f(0,0,0);
  233. glVertex3f(w,h,z);
  234. glVertex3f(0,0,0);
  235. glVertex3f(w,-h,z);
  236. glVertex3f(0,0,0);
  237. glVertex3f(-w,-h,z);
  238. glVertex3f(0,0,0);
  239. glVertex3f(-w,h,z);
  240. glVertex3f(w,h,z);
  241. glVertex3f(w,-h,z);
  242. glVertex3f(-w,h,z);
  243. glVertex3f(-w,-h,z);
  244. glVertex3f(-w,h,z);
  245. glVertex3f(w,h,z);
  246. glVertex3f(-w,-h,z);
  247. glVertex3f(w,-h,z);
  248. glEnd();
  249. glPopMatrix();
  250. }
  251. }
  252. }
  253. }
  254. void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc)
  255. {
  256. const float &w = mCameraSize;
  257. const float h = w*0.75;
  258. const float z = w*0.6;
  259. glPushMatrix();
  260. #ifdef HAVE_GLES
  261. glMultMatrixf(Twc.m);
  262. #else
  263. glMultMatrixd(Twc.m);
  264. #endif
  265. glLineWidth(mCameraLineWidth);
  266. glColor3f(0.0f,1.0f,0.0f);
  267. glBegin(GL_LINES);
  268. glVertex3f(0,0,0);
  269. glVertex3f(w,h,z);
  270. glVertex3f(0,0,0);
  271. glVertex3f(w,-h,z);
  272. glVertex3f(0,0,0);
  273. glVertex3f(-w,-h,z);
  274. glVertex3f(0,0,0);
  275. glVertex3f(-w,h,z);
  276. glVertex3f(w,h,z);
  277. glVertex3f(w,-h,z);
  278. glVertex3f(-w,h,z);
  279. glVertex3f(-w,-h,z);
  280. glVertex3f(-w,h,z);
  281. glVertex3f(w,h,z);
  282. glVertex3f(-w,-h,z);
  283. glVertex3f(w,-h,z);
  284. glEnd();
  285. glPopMatrix();
  286. }
  287. void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw)
  288. {
  289. unique_lock<mutex> lock(mMutexCamera);
  290. mCameraPose = Tcw.clone();
  291. }
  292. void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw)
  293. {
  294. if(!mCameraPose.empty())
  295. {
  296. cv::Mat Rwc(3,3,CV_32F);
  297. cv::Mat twc(3,1,CV_32F);
  298. {
  299. unique_lock<mutex> lock(mMutexCamera);
  300. Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t();
  301. twc = -Rwc*mCameraPose.rowRange(0,3).col(3);
  302. }
  303. M.m[0] = Rwc.at<float>(0,0);
  304. M.m[1] = Rwc.at<float>(1,0);
  305. M.m[2] = Rwc.at<float>(2,0);
  306. M.m[3] = 0.0;
  307. M.m[4] = Rwc.at<float>(0,1);
  308. M.m[5] = Rwc.at<float>(1,1);
  309. M.m[6] = Rwc.at<float>(2,1);
  310. M.m[7] = 0.0;
  311. M.m[8] = Rwc.at<float>(0,2);
  312. M.m[9] = Rwc.at<float>(1,2);
  313. M.m[10] = Rwc.at<float>(2,2);
  314. M.m[11] = 0.0;
  315. M.m[12] = twc.at<float>(0);
  316. M.m[13] = twc.at<float>(1);
  317. M.m[14] = twc.at<float>(2);
  318. M.m[15] = 1.0;
  319. MOw.SetIdentity();
  320. MOw.m[12] = twc.at<float>(0);
  321. MOw.m[13] = twc.at<float>(1);
  322. MOw.m[14] = twc.at<float>(2);
  323. }
  324. else
  325. {
  326. M.SetIdentity();
  327. MOw.SetIdentity();
  328. }
  329. }
  330. void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw, pangolin::OpenGlMatrix &MTwwp)
  331. {
  332. if(!mCameraPose.empty())
  333. {
  334. cv::Mat Rwc(3,3,CV_32F);
  335. cv::Mat twc(3,1,CV_32F);
  336. cv::Mat Rwwp(3,3,CV_32F);
  337. {
  338. unique_lock<mutex> lock(mMutexCamera);
  339. Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t();
  340. twc = -Rwc*mCameraPose.rowRange(0,3).col(3);
  341. }
  342. M.m[0] = Rwc.at<float>(0,0);
  343. M.m[1] = Rwc.at<float>(1,0);
  344. M.m[2] = Rwc.at<float>(2,0);
  345. M.m[3] = 0.0;
  346. M.m[4] = Rwc.at<float>(0,1);
  347. M.m[5] = Rwc.at<float>(1,1);
  348. M.m[6] = Rwc.at<float>(2,1);
  349. M.m[7] = 0.0;
  350. M.m[8] = Rwc.at<float>(0,2);
  351. M.m[9] = Rwc.at<float>(1,2);
  352. M.m[10] = Rwc.at<float>(2,2);
  353. M.m[11] = 0.0;
  354. M.m[12] = twc.at<float>(0);
  355. M.m[13] = twc.at<float>(1);
  356. M.m[14] = twc.at<float>(2);
  357. M.m[15] = 1.0;
  358. MOw.SetIdentity();
  359. MOw.m[12] = twc.at<float>(0);
  360. MOw.m[13] = twc.at<float>(1);
  361. MOw.m[14] = twc.at<float>(2);
  362. MTwwp.SetIdentity();
  363. MTwwp.m[0] = Rwwp.at<float>(0,0);
  364. MTwwp.m[1] = Rwwp.at<float>(1,0);
  365. MTwwp.m[2] = Rwwp.at<float>(2,0);
  366. MTwwp.m[4] = Rwwp.at<float>(0,1);
  367. MTwwp.m[5] = Rwwp.at<float>(1,1);
  368. MTwwp.m[6] = Rwwp.at<float>(2,1);
  369. MTwwp.m[8] = Rwwp.at<float>(0,2);
  370. MTwwp.m[9] = Rwwp.at<float>(1,2);
  371. MTwwp.m[10] = Rwwp.at<float>(2,2);
  372. MTwwp.m[12] = twc.at<float>(0);
  373. MTwwp.m[13] = twc.at<float>(1);
  374. MTwwp.m[14] = twc.at<float>(2);
  375. }
  376. else
  377. {
  378. M.SetIdentity();
  379. MOw.SetIdentity();
  380. MTwwp.SetIdentity();
  381. }
  382. }
  383. } //namespace ORB_SLAM