forked from raulmur/ORB_SLAM2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
MapDrawer.h
64 lines (51 loc) · 1.64 KB
/
MapDrawer.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <https://github.com/raulmur/ORB_SLAM2>
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MAPDRAWER_H
#define MAPDRAWER_H
#include"Map.h"
#include"MapPoint.h"
#include"KeyFrame.h"
#include<pangolin/pangolin.h>
#include<mutex>
namespace ORB_SLAM2
{
class MapDrawer
{
public:
MapDrawer(Map* pMap, const string &strSettingPath);
Map* mpMap;
void DrawMapPoints();
void DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph);
void DrawCurrentCamera(pangolin::OpenGlMatrix &Twc);
void SetCurrentCameraPose(const cv::Mat &Tcw);
void SetReferenceKeyFrame(KeyFrame *pKF);
void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M);
private:
float mKeyFrameSize;
float mKeyFrameLineWidth;
float mGraphLineWidth;
float mPointSize;
float mCameraSize;
float mCameraLineWidth;
cv::Mat mCameraPose;
std::mutex mMutexCamera;
};
} //namespace ORB_SLAM
#endif // MAPDRAWER_H