Frame.cc
Go to the documentation of this file.
1 
21 #include "Frame.h"
22 #include "Converter.h"
23 #include "ORBmatcher.h"
24 #include <thread>
25 
26 namespace ORB_SLAM2
27 {
28 
29 long unsigned int Frame::nNextId=0;
34 
36 {}
37 
38 //Copy Constructor
39 Frame::Frame(const Frame &frame)
41  mTimeStamp(frame.mTimeStamp), mK(frame.mK.clone()), mDistCoef(frame.mDistCoef.clone()),
42  mbf(frame.mbf), mb(frame.mb), mThDepth(frame.mThDepth), N(frame.N), mvKeys(frame.mvKeys),
44  mvDepth(frame.mvDepth), mBowVec(frame.mBowVec), mFeatVec(frame.mFeatVec),
45  mDescriptors(frame.mDescriptors.clone()), mDescriptorsRight(frame.mDescriptorsRight.clone()),
46  mvpMapPoints(frame.mvpMapPoints), mvbOutlier(frame.mvbOutlier), mnId(frame.mnId),
51 {
52  for(int i=0;i<FRAME_GRID_COLS;i++)
53  for(int j=0; j<FRAME_GRID_ROWS; j++)
54  mGrid[i][j]=frame.mGrid[i][j];
55 
56  if(!frame.mTcw.empty())
57  SetPose(frame.mTcw);
58 }
59 
60 
61 Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
62  :mpORBvocabulary(voc),mpORBextractorLeft(extractorLeft),mpORBextractorRight(extractorRight), mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth),
63  mpReferenceKF(static_cast<KeyFrame*>(NULL))
64 {
65  // Frame ID
66  mnId=nNextId++;
67 
68  // Scale Level Info
76 
77  // ORB extraction
78  thread threadLeft(&Frame::ExtractORB,this,0,imLeft);
79  thread threadRight(&Frame::ExtractORB,this,1,imRight);
80  threadLeft.join();
81  threadRight.join();
82 
83  N = mvKeys.size();
84 
85  if(mvKeys.empty())
86  return;
87 
89 
91 
92  mvpMapPoints = vector<MapPoint*>(N,static_cast<MapPoint*>(NULL));
93  mvbOutlier = vector<bool>(N,false);
94 
95 
96  // This is done only for the first Frame (or after a change in the calibration)
98  {
99  ComputeImageBounds(imLeft);
100 
101  mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/(mnMaxX-mnMinX);
102  mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/(mnMaxY-mnMinY);
103 
104  fx = K.at<float>(0,0);
105  fy = K.at<float>(1,1);
106  cx = K.at<float>(0,2);
107  cy = K.at<float>(1,2);
108  invfx = 1.0f/fx;
109  invfy = 1.0f/fy;
110 
111  mbInitialComputations=false;
112  }
113 
114  mb = mbf/fx;
115 
117 }
118 
119 Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
120  :mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast<ORBextractor*>(NULL)),
121  mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth)
122 {
123  // Frame ID
124  mnId=nNextId++;
125 
126  // Scale Level Info
134 
135  // ORB extraction
136  ExtractORB(0,imGray);
137 
138  N = mvKeys.size();
139 
140  if(mvKeys.empty())
141  return;
142 
144 
145  ComputeStereoFromRGBD(imDepth);
146 
147  mvpMapPoints = vector<MapPoint*>(N,static_cast<MapPoint*>(NULL));
148  mvbOutlier = vector<bool>(N,false);
149 
150  // This is done only for the first Frame (or after a change in the calibration)
152  {
153  ComputeImageBounds(imGray);
154 
155  mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/static_cast<float>(mnMaxX-mnMinX);
156  mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/static_cast<float>(mnMaxY-mnMinY);
157 
158  fx = K.at<float>(0,0);
159  fy = K.at<float>(1,1);
160  cx = K.at<float>(0,2);
161  cy = K.at<float>(1,2);
162  invfx = 1.0f/fx;
163  invfy = 1.0f/fy;
164 
165  mbInitialComputations=false;
166  }
167 
168  mb = mbf/fx;
169 
171 }
172 
173 
174 Frame::Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth)
175  :mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast<ORBextractor*>(NULL)),
176  mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth)
177 {
178  // Frame ID
179  mnId=nNextId++;
180 
181  // Scale Level Info
189 
190  // ORB extraction
191  ExtractORB(0,imGray);
192 
193  N = mvKeys.size();
194 
195  if(mvKeys.empty())
196  return;
197 
199 
200  // Set no stereo information
201  mvuRight = vector<float>(N,-1);
202  mvDepth = vector<float>(N,-1);
203 
204  mvpMapPoints = vector<MapPoint*>(N,static_cast<MapPoint*>(NULL));
205  mvbOutlier = vector<bool>(N,false);
206 
207  // This is done only for the first Frame (or after a change in the calibration)
209  {
210  ComputeImageBounds(imGray);
211 
212  mfGridElementWidthInv=static_cast<float>(FRAME_GRID_COLS)/static_cast<float>(mnMaxX-mnMinX);
213  mfGridElementHeightInv=static_cast<float>(FRAME_GRID_ROWS)/static_cast<float>(mnMaxY-mnMinY);
214 
215  fx = K.at<float>(0,0);
216  fy = K.at<float>(1,1);
217  cx = K.at<float>(0,2);
218  cy = K.at<float>(1,2);
219  invfx = 1.0f/fx;
220  invfy = 1.0f/fy;
221 
222  mbInitialComputations=false;
223  }
224 
225  mb = mbf/fx;
226 
228 }
229 
231 {
232  int nReserve = 0.5f*N/(FRAME_GRID_COLS*FRAME_GRID_ROWS);
233  for(unsigned int i=0; i<FRAME_GRID_COLS;i++)
234  for (unsigned int j=0; j<FRAME_GRID_ROWS;j++)
235  mGrid[i][j].reserve(nReserve);
236 
237  for(int i=0;i<N;i++)
238  {
239  const cv::KeyPoint &kp = mvKeysUn[i];
240 
241  int nGridPosX, nGridPosY;
242  if(PosInGrid(kp,nGridPosX,nGridPosY))
243  mGrid[nGridPosX][nGridPosY].push_back(i);
244  }
245 }
246 
247 void Frame::ExtractORB(int flag, const cv::Mat &im)
248 {
249  if(flag==0)
250  (*mpORBextractorLeft)(im,cv::Mat(),mvKeys,mDescriptors);
251  else
253 }
254 
255 void Frame::SetPose(cv::Mat Tcw)
256 {
257  mTcw = Tcw.clone();
259 }
260 
262 {
263  mRcw = mTcw.rowRange(0,3).colRange(0,3);
264  mRwc = mRcw.t();
265  mtcw = mTcw.rowRange(0,3).col(3);
266  mOw = -mRcw.t()*mtcw;
267 }
268 
269 bool Frame::isInFrustum(MapPoint *pMP, float viewingCosLimit)
270 {
271  pMP->mbTrackInView = false;
272 
273  // 3D in absolute coordinates
274  cv::Mat P = pMP->GetWorldPos();
275 
276  // 3D in camera coordinates
277  const cv::Mat Pc = mRcw*P+mtcw;
278  const float &PcX = Pc.at<float>(0);
279  const float &PcY= Pc.at<float>(1);
280  const float &PcZ = Pc.at<float>(2);
281 
282  // Check positive depth
283  if(PcZ<0.0f)
284  return false;
285 
286  // Project in image and check it is not outside
287  const float invz = 1.0f/PcZ;
288  const float u=fx*PcX*invz+cx;
289  const float v=fy*PcY*invz+cy;
290 
291  if(u<mnMinX || u>mnMaxX)
292  return false;
293  if(v<mnMinY || v>mnMaxY)
294  return false;
295 
296  // Check distance is in the scale invariance region of the MapPoint
297  const float maxDistance = pMP->GetMaxDistanceInvariance();
298  const float minDistance = pMP->GetMinDistanceInvariance();
299  const cv::Mat PO = P-mOw;
300  const float dist = cv::norm(PO);
301 
302  if(dist<minDistance || dist>maxDistance)
303  return false;
304 
305  // Check viewing angle
306  cv::Mat Pn = pMP->GetNormal();
307 
308  const float viewCos = PO.dot(Pn)/dist;
309 
310  if(viewCos<viewingCosLimit)
311  return false;
312 
313  // Predict scale in the image
314  const int nPredictedLevel = pMP->PredictScale(dist,this);
315 
316  // Data used by the tracking
317  pMP->mbTrackInView = true;
318  pMP->mTrackProjX = u;
319  pMP->mTrackProjXR = u - mbf*invz;
320  pMP->mTrackProjY = v;
321  pMP->mnTrackScaleLevel= nPredictedLevel;
322  pMP->mTrackViewCos = viewCos;
323 
324  return true;
325 }
326 
327 vector<size_t> Frame::GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel, const int maxLevel) const
328 {
329  vector<size_t> vIndices;
330  vIndices.reserve(N);
331 
332  const int nMinCellX = max(0,(int)floor((x-mnMinX-r)*mfGridElementWidthInv));
333  if(nMinCellX>=FRAME_GRID_COLS)
334  return vIndices;
335 
336  const int nMaxCellX = min((int)FRAME_GRID_COLS-1,(int)ceil((x-mnMinX+r)*mfGridElementWidthInv));
337  if(nMaxCellX<0)
338  return vIndices;
339 
340  const int nMinCellY = max(0,(int)floor((y-mnMinY-r)*mfGridElementHeightInv));
341  if(nMinCellY>=FRAME_GRID_ROWS)
342  return vIndices;
343 
344  const int nMaxCellY = min((int)FRAME_GRID_ROWS-1,(int)ceil((y-mnMinY+r)*mfGridElementHeightInv));
345  if(nMaxCellY<0)
346  return vIndices;
347 
348  const bool bCheckLevels = (minLevel>0) || (maxLevel>=0);
349 
350  for(int ix = nMinCellX; ix<=nMaxCellX; ix++)
351  {
352  for(int iy = nMinCellY; iy<=nMaxCellY; iy++)
353  {
354  const vector<size_t> vCell = mGrid[ix][iy];
355  if(vCell.empty())
356  continue;
357 
358  for(size_t j=0, jend=vCell.size(); j<jend; j++)
359  {
360  const cv::KeyPoint &kpUn = mvKeysUn[vCell[j]];
361  if(bCheckLevels)
362  {
363  if(kpUn.octave<minLevel)
364  continue;
365  if(maxLevel>=0)
366  if(kpUn.octave>maxLevel)
367  continue;
368  }
369 
370  const float distx = kpUn.pt.x-x;
371  const float disty = kpUn.pt.y-y;
372 
373  if(fabs(distx)<r && fabs(disty)<r)
374  vIndices.push_back(vCell[j]);
375  }
376  }
377  }
378 
379  return vIndices;
380 }
381 
382 bool Frame::PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY)
383 {
384  posX = round((kp.pt.x-mnMinX)*mfGridElementWidthInv);
385  posY = round((kp.pt.y-mnMinY)*mfGridElementHeightInv);
386 
387  //Keypoint's coordinates are undistorted, which could cause to go out of the image
388  if(posX<0 || posX>=FRAME_GRID_COLS || posY<0 || posY>=FRAME_GRID_ROWS)
389  return false;
390 
391  return true;
392 }
393 
394 
396 {
397  if(mBowVec.empty())
398  {
399  vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
400  mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4);
401  }
402 }
403 
405 {
406  if(mDistCoef.at<float>(0)==0.0)
407  {
409  return;
410  }
411 
412  // Fill matrix with points
413  cv::Mat mat(N,2,CV_32F);
414  for(int i=0; i<N; i++)
415  {
416  mat.at<float>(i,0)=mvKeys[i].pt.x;
417  mat.at<float>(i,1)=mvKeys[i].pt.y;
418  }
419 
420  // Undistort points
421  mat=mat.reshape(2);
422  cv::undistortPoints(mat,mat,mK,mDistCoef,cv::Mat(),mK);
423  mat=mat.reshape(1);
424 
425  // Fill undistorted keypoint vector
426  mvKeysUn.resize(N);
427  for(int i=0; i<N; i++)
428  {
429  cv::KeyPoint kp = mvKeys[i];
430  kp.pt.x=mat.at<float>(i,0);
431  kp.pt.y=mat.at<float>(i,1);
432  mvKeysUn[i]=kp;
433  }
434 }
435 
436 void Frame::ComputeImageBounds(const cv::Mat &imLeft)
437 {
438  if(mDistCoef.at<float>(0)!=0.0)
439  {
440  cv::Mat mat(4,2,CV_32F);
441  mat.at<float>(0,0)=0.0; mat.at<float>(0,1)=0.0;
442  mat.at<float>(1,0)=imLeft.cols; mat.at<float>(1,1)=0.0;
443  mat.at<float>(2,0)=0.0; mat.at<float>(2,1)=imLeft.rows;
444  mat.at<float>(3,0)=imLeft.cols; mat.at<float>(3,1)=imLeft.rows;
445 
446  // Undistort corners
447  mat=mat.reshape(2);
448  cv::undistortPoints(mat,mat,mK,mDistCoef,cv::Mat(),mK);
449  mat=mat.reshape(1);
450 
451  mnMinX = min(mat.at<float>(0,0),mat.at<float>(2,0));
452  mnMaxX = max(mat.at<float>(1,0),mat.at<float>(3,0));
453  mnMinY = min(mat.at<float>(0,1),mat.at<float>(1,1));
454  mnMaxY = max(mat.at<float>(2,1),mat.at<float>(3,1));
455 
456  }
457  else
458  {
459  mnMinX = 0.0f;
460  mnMaxX = imLeft.cols;
461  mnMinY = 0.0f;
462  mnMaxY = imLeft.rows;
463  }
464 }
465 
467 {
468  mvuRight = vector<float>(N,-1.0f);
469  mvDepth = vector<float>(N,-1.0f);
470 
471  const int thOrbDist = (ORBmatcher::TH_HIGH+ORBmatcher::TH_LOW)/2;
472 
473  const int nRows = mpORBextractorLeft->mvImagePyramid[0].rows;
474 
475  //Assign keypoints to row table
476  vector<vector<size_t> > vRowIndices(nRows,vector<size_t>());
477 
478  for(int i=0; i<nRows; i++)
479  vRowIndices[i].reserve(200);
480 
481  const int Nr = mvKeysRight.size();
482 
483  for(int iR=0; iR<Nr; iR++)
484  {
485  const cv::KeyPoint &kp = mvKeysRight[iR];
486  const float &kpY = kp.pt.y;
487  const float r = 2.0f*mvScaleFactors[mvKeysRight[iR].octave];
488  const int maxr = ceil(kpY+r);
489  const int minr = floor(kpY-r);
490 
491  for(int yi=minr;yi<=maxr;yi++)
492  vRowIndices[yi].push_back(iR);
493  }
494 
495  // Set limits for search
496  const float minZ = mb;
497  const float minD = 0;
498  const float maxD = mbf/minZ;
499 
500  // For each left keypoint search a match in the right image
501  vector<pair<int, int> > vDistIdx;
502  vDistIdx.reserve(N);
503 
504  for(int iL=0; iL<N; iL++)
505  {
506  const cv::KeyPoint &kpL = mvKeys[iL];
507  const int &levelL = kpL.octave;
508  const float &vL = kpL.pt.y;
509  const float &uL = kpL.pt.x;
510 
511  const vector<size_t> &vCandidates = vRowIndices[vL];
512 
513  if(vCandidates.empty())
514  continue;
515 
516  const float minU = uL-maxD;
517  const float maxU = uL-minD;
518 
519  if(maxU<0)
520  continue;
521 
522  int bestDist = ORBmatcher::TH_HIGH;
523  size_t bestIdxR = 0;
524 
525  const cv::Mat &dL = mDescriptors.row(iL);
526 
527  // Compare descriptor to right keypoints
528  for(size_t iC=0; iC<vCandidates.size(); iC++)
529  {
530  const size_t iR = vCandidates[iC];
531  const cv::KeyPoint &kpR = mvKeysRight[iR];
532 
533  if(kpR.octave<levelL-1 || kpR.octave>levelL+1)
534  continue;
535 
536  const float &uR = kpR.pt.x;
537 
538  if(uR>=minU && uR<=maxU)
539  {
540  const cv::Mat &dR = mDescriptorsRight.row(iR);
541  const int dist = ORBmatcher::DescriptorDistance(dL,dR);
542 
543  if(dist<bestDist)
544  {
545  bestDist = dist;
546  bestIdxR = iR;
547  }
548  }
549  }
550 
551  // Subpixel match by correlation
552  if(bestDist<thOrbDist)
553  {
554  // coordinates in image pyramid at keypoint scale
555  const float uR0 = mvKeysRight[bestIdxR].pt.x;
556  const float scaleFactor = mvInvScaleFactors[kpL.octave];
557  const float scaleduL = round(kpL.pt.x*scaleFactor);
558  const float scaledvL = round(kpL.pt.y*scaleFactor);
559  const float scaleduR0 = round(uR0*scaleFactor);
560 
561  // sliding window search
562  const int w = 5;
563  cv::Mat IL = mpORBextractorLeft->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduL-w,scaleduL+w+1);
564  IL.convertTo(IL,CV_32F);
565  IL = IL - IL.at<float>(w,w) *cv::Mat::ones(IL.rows,IL.cols,CV_32F);
566 
567  int bestDist = INT_MAX;
568  int bestincR = 0;
569  const int L = 5;
570  vector<float> vDists;
571  vDists.resize(2*L+1);
572 
573  const float iniu = scaleduR0+L-w;
574  const float endu = scaleduR0+L+w+1;
575  if(iniu<0 || endu >= mpORBextractorRight->mvImagePyramid[kpL.octave].cols)
576  continue;
577 
578  for(int incR=-L; incR<=+L; incR++)
579  {
580  cv::Mat IR = mpORBextractorRight->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduR0+incR-w,scaleduR0+incR+w+1);
581  IR.convertTo(IR,CV_32F);
582  IR = IR - IR.at<float>(w,w) *cv::Mat::ones(IR.rows,IR.cols,CV_32F);
583 
584  float dist = cv::norm(IL,IR,cv::NORM_L1);
585  if(dist<bestDist)
586  {
587  bestDist = dist;
588  bestincR = incR;
589  }
590 
591  vDists[L+incR] = dist;
592  }
593 
594  if(bestincR==-L || bestincR==L)
595  continue;
596 
597  // Sub-pixel match (Parabola fitting)
598  const float dist1 = vDists[L+bestincR-1];
599  const float dist2 = vDists[L+bestincR];
600  const float dist3 = vDists[L+bestincR+1];
601 
602  const float deltaR = (dist1-dist3)/(2.0f*(dist1+dist3-2.0f*dist2));
603 
604  if(deltaR<-1 || deltaR>1)
605  continue;
606 
607  // Re-scaled coordinate
608  float bestuR = mvScaleFactors[kpL.octave]*((float)scaleduR0+(float)bestincR+deltaR);
609 
610  float disparity = (uL-bestuR);
611 
612  if(disparity>=minD && disparity<maxD)
613  {
614  if(disparity<=0)
615  {
616  disparity=0.01;
617  bestuR = uL-0.01;
618  }
619  mvDepth[iL]=mbf/disparity;
620  mvuRight[iL] = bestuR;
621  vDistIdx.push_back(pair<int,int>(bestDist,iL));
622  }
623  }
624  }
625 
626  sort(vDistIdx.begin(),vDistIdx.end());
627  const float median = vDistIdx[vDistIdx.size()/2].first;
628  const float thDist = 1.5f*1.4f*median;
629 
630  for(int i=vDistIdx.size()-1;i>=0;i--)
631  {
632  if(vDistIdx[i].first<thDist)
633  break;
634  else
635  {
636  mvuRight[vDistIdx[i].second]=-1;
637  mvDepth[vDistIdx[i].second]=-1;
638  }
639  }
640 }
641 
642 
643 void Frame::ComputeStereoFromRGBD(const cv::Mat &imDepth)
644 {
645  mvuRight = vector<float>(N,-1);
646  mvDepth = vector<float>(N,-1);
647 
648  for(int i=0; i<N; i++)
649  {
650  const cv::KeyPoint &kp = mvKeys[i];
651  const cv::KeyPoint &kpU = mvKeysUn[i];
652 
653  const float &v = kp.pt.y;
654  const float &u = kp.pt.x;
655 
656  const float d = imDepth.at<float>(v,u);
657 
658  if(d>0)
659  {
660  mvDepth[i] = d;
661  mvuRight[i] = kpU.pt.x-mbf/d;
662  }
663  }
664 }
665 
666 cv::Mat Frame::UnprojectStereo(const int &i)
667 {
668  const float z = mvDepth[i];
669  if(z>0)
670  {
671  const float u = mvKeysUn[i].pt.x;
672  const float v = mvKeysUn[i].pt.y;
673  const float x = (u-cx)*z*invfx;
674  const float y = (v-cy)*z*invfy;
675  cv::Mat x3Dc = (cv::Mat_<float>(3,1) << x, y, z);
676  return mRwc*x3Dc+mOw;
677  }
678  else
679  return cv::Mat();
680 }
681 
682 } //namespace ORB_SLAM
d
float GetMinDistanceInvariance()
Definition: MapPoint.cc:373
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
void ComputeBoW()
Definition: Frame.cc:395
static float fy
Definition: Frame.h:114
void ComputeImageBounds(const cv::Mat &imLeft)
Definition: Frame.cc:436
bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY)
Definition: Frame.cc:382
f
std::vector< float > GetScaleSigmaSquares()
Definition: ORBextractor.h:77
cv::Mat mDistCoef
Definition: Frame.h:119
#define FRAME_GRID_COLS
Definition: Frame.h:38
static float cx
Definition: Frame.h:115
vector< float > mvInvScaleFactors
Definition: Frame.h:178
static float fx
Definition: Frame.h:113
void ComputeStereoFromRGBD(const cv::Mat &imDepth)
Definition: Frame.cc:643
static float invfx
Definition: Frame.h:117
std::vector< cv::Mat > mvImagePyramid
Definition: ORBextractor.h:85
static float cy
Definition: Frame.h:116
cv::Mat UnprojectStereo(const int &i)
Definition: Frame.cc:666
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
std::vector< bool > mvbOutlier
Definition: Frame.h:156
static const int TH_LOW
Definition: ORBmatcher.h:87
static const int TH_HIGH
Definition: ORBmatcher.h:88
void UpdatePoseMatrices()
Definition: Frame.cc:261
static float mfGridElementHeightInv
Definition: Frame.h:160
static float mnMinY
Definition: Frame.h:185
cv::Mat mDescriptorsRight
Definition: Frame.h:150
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
Definition: Frame.h:161
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
static float mfGridElementWidthInv
Definition: Frame.h:159
KeyFrame * mpReferenceKF
Definition: Frame.h:171
static float invfy
Definition: Frame.h:118
DBoW2::FeatureVector mFeatVec
Definition: Frame.h:147
cv::Mat mRwc
Definition: Frame.h:207
ORBVocabulary * mpORBvocabulary
Definition: Frame.h:103
std::vector< float > GetScaleFactors()
Definition: ORBextractor.h:69
float mfScaleFactor
Definition: Frame.h:175
virtual void transform(const std::vector< TDescriptor > &features, BowVector &v) const
std::vector< float > mvuRight
Definition: Frame.h:142
bool isInFrustum(MapPoint *pMP, float viewingCosLimit)
Definition: Frame.cc:269
vector< float > mvLevelSigma2
Definition: Frame.h:179
std::vector< float > mvDepth
Definition: Frame.h:143
int mnScaleLevels
Definition: Frame.h:174
std::vector< cv::KeyPoint > mvKeysRight
Definition: Frame.h:137
static bool mbInitialComputations
Definition: Frame.h:188
cv::Mat mTcw
Definition: Frame.h:164
static long unsigned int nNextId
Definition: Frame.h:167
#define FRAME_GRID_ROWS
Definition: Frame.h:37
Vector3d deltaR(const Matrix3d &R)
Definition: se3_ops.hpp:40
void AssignFeaturesToGrid()
Definition: Frame.cc:230
float mfLogScaleFactor
Definition: Frame.h:176
double mTimeStamp
Definition: Frame.h:109
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
Definition: ORBmatcher.cc:1647
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
Definition: Converter.cc:27
TFSIMD_FORCE_INLINE const tfScalar & x() const
float GetMaxDistanceInvariance()
Definition: MapPoint.cc:379
std::vector< cv::KeyPoint > mvKeys
Definition: Frame.h:137
vector< float > mvScaleFactors
Definition: Frame.h:177
static float mnMaxY
Definition: Frame.h:186
cv::Mat mK
Definition: Frame.h:112
cv::Mat GetNormal()
Definition: MapPoint.cc:86
cv::Mat mtcw
Definition: Frame.h:206
cv::Mat mOw
Definition: Frame.h:208
void ExtractORB(int flag, const cv::Mat &im)
Definition: Frame.cc:247
TFSIMD_FORCE_INLINE const tfScalar & z() const
cv::Mat mRcw
Definition: Frame.h:205
void ComputeStereoMatches()
Definition: Frame.cc:466
static float mnMinX
Definition: Frame.h:183
TFSIMD_FORCE_INLINE const tfScalar & w() const
vector< float > mvInvLevelSigma2
Definition: Frame.h:180
void UndistortKeyPoints()
Definition: Frame.cc:404
int min(int a, int b)
void SetPose(cv::Mat Tcw)
Definition: Frame.cc:255
long unsigned int mnId
Definition: Frame.h:168
static float mnMaxX
Definition: Frame.h:184
std::vector< float > GetInverseScaleFactors()
Definition: ORBextractor.h:73
cv::Mat mDescriptors
Definition: Frame.h:150
float mThDepth
Definition: Frame.h:129
ORBextractor * mpORBextractorRight
Definition: Frame.h:106
DBoW2::BowVector mBowVec
Definition: Frame.h:146
int PredictScale(const float &currentDist, KeyFrame *pKF)
Definition: MapPoint.cc:385
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
Definition: Frame.cc:327
ORBextractor * mpORBextractorLeft
Definition: Frame.h:106
std::vector< float > GetInverseScaleSigmaSquares()
Definition: ORBextractor.h:81


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