MapDrawer.h 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * 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.
  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. #ifndef MAPDRAWER_H
  19. #define MAPDRAWER_H
  20. #include"Atlas.h"
  21. #include"MapPoint.h"
  22. #include"KeyFrame.h"
  23. #include "Settings.h"
  24. #include<pangolin/pangolin.h>
  25. #include<mutex>
  26. namespace ORB_SLAM3
  27. {
  28. class Settings;
  29. class MapDrawer
  30. {
  31. public:
  32. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  33. MapDrawer(Atlas* pAtlas, const string &strSettingPath, Settings* settings);
  34. void newParameterLoader(Settings* settings);
  35. Atlas* mpAtlas;
  36. void DrawMapPoints();
  37. void DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph, const bool bDrawInertialGraph, const bool bDrawOptLba);
  38. void DrawCurrentCamera(pangolin::OpenGlMatrix &Twc);
  39. void SetCurrentCameraPose(const Sophus::SE3f &Tcw);
  40. void SetReferenceKeyFrame(KeyFrame *pKF);
  41. void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M, pangolin::OpenGlMatrix &MOw);
  42. private:
  43. bool ParseViewerParamFile(cv::FileStorage &fSettings);
  44. float mKeyFrameSize;
  45. float mKeyFrameLineWidth;
  46. float mGraphLineWidth;
  47. float mPointSize;
  48. float mCameraSize;
  49. float mCameraLineWidth;
  50. Sophus::SE3f mCameraPose;
  51. std::mutex mMutexCamera;
  52. float mfFrameColors[6][3] = {{0.0f, 0.0f, 1.0f},
  53. {0.8f, 0.4f, 1.0f},
  54. {1.0f, 0.2f, 0.4f},
  55. {0.6f, 0.0f, 1.0f},
  56. {1.0f, 1.0f, 0.0f},
  57. {0.0f, 1.0f, 1.0f}};
  58. };
  59. } //namespace ORB_SLAM
  60. #endif // MAPDRAWER_H