FrameDrawer.cc
Go to the documentation of this file.
1 
21 #include "FrameDrawer.h"
22 #include "Tracking.h"
23 
24 #include <opencv2/core/core.hpp>
25 #include <opencv2/highgui/highgui.hpp>
26 
27 #include<mutex>
28 
29 namespace ORB_SLAM2
30 {
31 
32 FrameDrawer::FrameDrawer(Map* pMap):mpMap(pMap)
33 {
35  mIm = cv::Mat(480,640,CV_8UC3, cv::Scalar(0,0,0));
36 }
37 
39 {
40  cv::Mat im;
41  vector<cv::KeyPoint> vIniKeys; // Initialization: KeyPoints in reference frame
42  vector<int> vMatches; // Initialization: correspondeces with reference keypoints
43  vector<cv::KeyPoint> vCurrentKeys; // KeyPoints in current frame
44  vector<bool> vbVO, vbMap; // Tracked MapPoints in current frame
45  int state; // Tracking state
46 
47  //Copy variables within scoped mutex
48  {
49  unique_lock<mutex> lock(mMutex);
50  state=mState;
53 
54  mIm.copyTo(im);
55 
57  {
58  vCurrentKeys = mvCurrentKeys;
59  vIniKeys = mvIniKeys;
60  vMatches = mvIniMatches;
61  }
62  else if(mState==Tracking::OK)
63  {
64  vCurrentKeys = mvCurrentKeys;
65  vbVO = mvbVO;
66  vbMap = mvbMap;
67  }
68  else if(mState==Tracking::LOST)
69  {
70  vCurrentKeys = mvCurrentKeys;
71  }
72  } // destroy scoped mutex -> release mutex
73 
74  if(im.channels()<3) //this should be always true
75  cvtColor(im,im,CV_GRAY2BGR);
76 
77  //Draw
78  if(state==Tracking::NOT_INITIALIZED) //INITIALIZING
79  {
80  for(unsigned int i=0; i<vMatches.size(); i++)
81  {
82  if(vMatches[i]>=0)
83  {
84  cv::line(im,vIniKeys[i].pt,vCurrentKeys[vMatches[i]].pt,
85  cv::Scalar(0,255,0));
86  }
87  }
88  }
89  else if(state==Tracking::OK) //TRACKING
90  {
91  mnTracked=0;
92  mnTrackedVO=0;
93  const float r = 5;
94  const int n = vCurrentKeys.size();
95  for(int i=0;i<n;i++)
96  {
97  if(vbVO[i] || vbMap[i])
98  {
99  cv::Point2f pt1,pt2;
100  pt1.x=vCurrentKeys[i].pt.x-r;
101  pt1.y=vCurrentKeys[i].pt.y-r;
102  pt2.x=vCurrentKeys[i].pt.x+r;
103  pt2.y=vCurrentKeys[i].pt.y+r;
104 
105  // This is a match to a MapPoint in the map
106  if(vbMap[i])
107  {
108  cv::rectangle(im,pt1,pt2,cv::Scalar(0,255,0));
109  cv::circle(im,vCurrentKeys[i].pt,2,cv::Scalar(0,255,0),-1);
110  mnTracked++;
111  }
112  else // This is match to a "visual odometry" MapPoint created in the last frame
113  {
114  cv::rectangle(im,pt1,pt2,cv::Scalar(255,0,0));
115  cv::circle(im,vCurrentKeys[i].pt,2,cv::Scalar(255,0,0),-1);
116  mnTrackedVO++;
117  }
118  }
119  }
120  }
121 
122  cv::Mat imWithInfo;
123  DrawTextInfo(im,state, imWithInfo);
124 
125  return imWithInfo;
126 }
127 
128 
129 void FrameDrawer::DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText)
130 {
131  stringstream s;
132  if(nState==Tracking::NO_IMAGES_YET)
133  s << " WAITING FOR IMAGES";
134  else if(nState==Tracking::NOT_INITIALIZED)
135  s << " TRYING TO INITIALIZE ";
136  else if(nState==Tracking::OK)
137  {
138  if(!mbOnlyTracking)
139  s << "SLAM MODE | ";
140  else
141  s << "LOCALIZATION | ";
142  int nKFs = mpMap->KeyFramesInMap();
143  int nMPs = mpMap->MapPointsInMap();
144  s << "KFs: " << nKFs << ", MPs: " << nMPs << ", Matches: " << mnTracked;
145  if(mnTrackedVO>0)
146  s << ", + VO matches: " << mnTrackedVO;
147  }
148  else if(nState==Tracking::LOST)
149  {
150  s << " TRACK LOST. TRYING TO RELOCALIZE ";
151  }
152  else if(nState==Tracking::SYSTEM_NOT_READY)
153  {
154  s << " LOADING ORB VOCABULARY. PLEASE WAIT...";
155  }
156 
157  int baseline=0;
158  cv::Size textSize = cv::getTextSize(s.str(),cv::FONT_HERSHEY_PLAIN,1,1,&baseline);
159 
160  imText = cv::Mat(im.rows+textSize.height+10,im.cols,im.type());
161  im.copyTo(imText.rowRange(0,im.rows).colRange(0,im.cols));
162  imText.rowRange(im.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type());
163  cv::putText(imText,s.str(),cv::Point(5,imText.rows-5),cv::FONT_HERSHEY_PLAIN,1,cv::Scalar(255,255,255),1,8);
164 
165 }
166 
168 {
169  unique_lock<mutex> lock(mMutex);
170  pTracker->mImGray.copyTo(mIm);
172  N = mvCurrentKeys.size();
173  mvbVO = vector<bool>(N,false);
174  mvbMap = vector<bool>(N,false);
175  mbOnlyTracking = pTracker->mbOnlyTracking;
176 
177 
179  {
180  mvIniKeys=pTracker->mInitialFrame.mvKeys;
181  mvIniMatches=pTracker->mvIniMatches;
182  }
183  else if(pTracker->mLastProcessedState==Tracking::OK)
184  {
185  for(int i=0;i<N;i++)
186  {
187  MapPoint* pMP = pTracker->mCurrentFrame.mvpMapPoints[i];
188  if(pMP)
189  {
190  if(!pTracker->mCurrentFrame.mvbOutlier[i])
191  {
192  if(pMP->Observations()>0)
193  mvbMap[i]=true;
194  else
195  mvbVO[i]=true;
196  }
197  }
198  }
199  }
200  mState=static_cast<int>(pTracker->mLastProcessedState);
201 }
202 
203 } //namespace ORB_SLAM
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
vector< cv::KeyPoint > mvIniKeys
Definition: FrameDrawer.h:61
std::vector< int > mvIniMatches
Definition: Tracking.h:113
XmlRpcServer s
vector< bool > mvbMap
Definition: FrameDrawer.h:58
std::vector< bool > mvbOutlier
Definition: Frame.h:156
long unsigned KeyFramesInMap()
Definition: Map.cc:100
vector< cv::KeyPoint > mvCurrentKeys
Definition: FrameDrawer.h:57
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
long unsigned int MapPointsInMap()
Definition: Map.cc:94
vector< int > mvIniMatches
Definition: FrameDrawer.h:62
std::vector< cv::KeyPoint > mvKeys
Definition: Frame.h:137
vector< bool > mvbVO
Definition: FrameDrawer.h:58
eTrackingState mLastProcessedState
Definition: Tracking.h:102
void Update(Tracking *pTracker)
Definition: FrameDrawer.cc:167
void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText)
Definition: FrameDrawer.cc:129


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05