ORBmatcher.cc
Go to the documentation of this file.
1 
21 #include "ORBmatcher.h"
22 
23 #include<limits.h>
24 
25 #include<opencv2/core/core.hpp>
26 #include<opencv2/features2d/features2d.hpp>
27 
29 
30 #include<stdint-gcc.h>
31 
32 using namespace std;
33 
34 namespace ORB_SLAM2
35 {
36 
37 const int ORBmatcher::TH_HIGH = 100;
38 const int ORBmatcher::TH_LOW = 50;
39 const int ORBmatcher::HISTO_LENGTH = 30;
40 
41 ORBmatcher::ORBmatcher(float nnratio, bool checkOri): mfNNratio(nnratio), mbCheckOrientation(checkOri)
42 {
43 }
44 
45 int ORBmatcher::SearchByProjection(Frame &F, const vector<MapPoint*> &vpMapPoints, const float th)
46 {
47  int nmatches=0;
48 
49  const bool bFactor = th!=1.0;
50 
51  for(size_t iMP=0; iMP<vpMapPoints.size(); iMP++)
52  {
53  MapPoint* pMP = vpMapPoints[iMP];
54  if(!pMP->mbTrackInView)
55  continue;
56 
57  if(pMP->isBad())
58  continue;
59 
60  const int &nPredictedLevel = pMP->mnTrackScaleLevel;
61 
62  // The size of the window will depend on the viewing direction
63  float r = RadiusByViewingCos(pMP->mTrackViewCos);
64 
65  if(bFactor)
66  r*=th;
67 
68  const vector<size_t> vIndices =
69  F.GetFeaturesInArea(pMP->mTrackProjX,pMP->mTrackProjY,r*F.mvScaleFactors[nPredictedLevel],nPredictedLevel-1,nPredictedLevel);
70 
71  if(vIndices.empty())
72  continue;
73 
74  const cv::Mat MPdescriptor = pMP->GetDescriptor();
75 
76  int bestDist=256;
77  int bestLevel= -1;
78  int bestDist2=256;
79  int bestLevel2 = -1;
80  int bestIdx =-1 ;
81 
82  // Get best and second matches with near keypoints
83  for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
84  {
85  const size_t idx = *vit;
86 
87  if(F.mvpMapPoints[idx])
88  if(F.mvpMapPoints[idx]->Observations()>0)
89  continue;
90 
91  if(F.mvuRight[idx]>0)
92  {
93  const float er = fabs(pMP->mTrackProjXR-F.mvuRight[idx]);
94  if(er>r*F.mvScaleFactors[nPredictedLevel])
95  continue;
96  }
97 
98  const cv::Mat &d = F.mDescriptors.row(idx);
99 
100  const int dist = DescriptorDistance(MPdescriptor,d);
101 
102  if(dist<bestDist)
103  {
104  bestDist2=bestDist;
105  bestDist=dist;
106  bestLevel2 = bestLevel;
107  bestLevel = F.mvKeysUn[idx].octave;
108  bestIdx=idx;
109  }
110  else if(dist<bestDist2)
111  {
112  bestLevel2 = F.mvKeysUn[idx].octave;
113  bestDist2=dist;
114  }
115  }
116 
117  // Apply ratio to second match (only if best and second are in the same scale level)
118  if(bestDist<=TH_HIGH)
119  {
120  if(bestLevel==bestLevel2 && bestDist>mfNNratio*bestDist2)
121  continue;
122 
123  F.mvpMapPoints[bestIdx]=pMP;
124  nmatches++;
125  }
126  }
127 
128  return nmatches;
129 }
130 
131 float ORBmatcher::RadiusByViewingCos(const float &viewCos)
132 {
133  if(viewCos>0.998)
134  return 2.5;
135  else
136  return 4.0;
137 }
138 
139 
140 bool ORBmatcher::CheckDistEpipolarLine(const cv::KeyPoint &kp1,const cv::KeyPoint &kp2,const cv::Mat &F12,const KeyFrame* pKF2)
141 {
142  // Epipolar line in second image l = x1'F12 = [a b c]
143  const float a = kp1.pt.x*F12.at<float>(0,0)+kp1.pt.y*F12.at<float>(1,0)+F12.at<float>(2,0);
144  const float b = kp1.pt.x*F12.at<float>(0,1)+kp1.pt.y*F12.at<float>(1,1)+F12.at<float>(2,1);
145  const float c = kp1.pt.x*F12.at<float>(0,2)+kp1.pt.y*F12.at<float>(1,2)+F12.at<float>(2,2);
146 
147  const float num = a*kp2.pt.x+b*kp2.pt.y+c;
148 
149  const float den = a*a+b*b;
150 
151  if(den==0)
152  return false;
153 
154  const float dsqr = num*num/den;
155 
156  return dsqr<3.84*pKF2->mvLevelSigma2[kp2.octave];
157 }
158 
159 int ORBmatcher::SearchByBoW(KeyFrame* pKF,Frame &F, vector<MapPoint*> &vpMapPointMatches)
160 {
161  const vector<MapPoint*> vpMapPointsKF = pKF->GetMapPointMatches();
162 
163  vpMapPointMatches = vector<MapPoint*>(F.N,static_cast<MapPoint*>(NULL));
164 
165  const DBoW2::FeatureVector &vFeatVecKF = pKF->mFeatVec;
166 
167  int nmatches=0;
168 
169  vector<int> rotHist[HISTO_LENGTH];
170  for(int i=0;i<HISTO_LENGTH;i++)
171  rotHist[i].reserve(500);
172  const float factor = 1.0f/HISTO_LENGTH;
173 
174  // We perform the matching over ORB that belong to the same vocabulary node (at a certain level)
175  DBoW2::FeatureVector::const_iterator KFit = vFeatVecKF.begin();
176  DBoW2::FeatureVector::const_iterator Fit = F.mFeatVec.begin();
177  DBoW2::FeatureVector::const_iterator KFend = vFeatVecKF.end();
178  DBoW2::FeatureVector::const_iterator Fend = F.mFeatVec.end();
179 
180  while(KFit != KFend && Fit != Fend)
181  {
182  if(KFit->first == Fit->first)
183  {
184  const vector<unsigned int> vIndicesKF = KFit->second;
185  const vector<unsigned int> vIndicesF = Fit->second;
186 
187  for(size_t iKF=0; iKF<vIndicesKF.size(); iKF++)
188  {
189  const unsigned int realIdxKF = vIndicesKF[iKF];
190 
191  MapPoint* pMP = vpMapPointsKF[realIdxKF];
192 
193  if(!pMP)
194  continue;
195 
196  if(pMP->isBad())
197  continue;
198 
199  const cv::Mat &dKF= pKF->mDescriptors.row(realIdxKF);
200 
201  int bestDist1=256;
202  int bestIdxF =-1 ;
203  int bestDist2=256;
204 
205  for(size_t iF=0; iF<vIndicesF.size(); iF++)
206  {
207  const unsigned int realIdxF = vIndicesF[iF];
208 
209  if(vpMapPointMatches[realIdxF])
210  continue;
211 
212  const cv::Mat &dF = F.mDescriptors.row(realIdxF);
213 
214  const int dist = DescriptorDistance(dKF,dF);
215 
216  if(dist<bestDist1)
217  {
218  bestDist2=bestDist1;
219  bestDist1=dist;
220  bestIdxF=realIdxF;
221  }
222  else if(dist<bestDist2)
223  {
224  bestDist2=dist;
225  }
226  }
227 
228  if(bestDist1<=TH_LOW)
229  {
230  if(static_cast<float>(bestDist1)<mfNNratio*static_cast<float>(bestDist2))
231  {
232  vpMapPointMatches[bestIdxF]=pMP;
233 
234  const cv::KeyPoint &kp = pKF->mvKeysUn[realIdxKF];
235 
237  {
238  float rot = kp.angle-F.mvKeys[bestIdxF].angle;
239  if(rot<0.0)
240  rot+=360.0f;
241  int bin = round(rot*factor);
242  if(bin==HISTO_LENGTH)
243  bin=0;
244  assert(bin>=0 && bin<HISTO_LENGTH);
245  rotHist[bin].push_back(bestIdxF);
246  }
247  nmatches++;
248  }
249  }
250 
251  }
252 
253  KFit++;
254  Fit++;
255  }
256  else if(KFit->first < Fit->first)
257  {
258  KFit = vFeatVecKF.lower_bound(Fit->first);
259  }
260  else
261  {
262  Fit = F.mFeatVec.lower_bound(KFit->first);
263  }
264  }
265 
266 
268  {
269  int ind1=-1;
270  int ind2=-1;
271  int ind3=-1;
272 
273  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
274 
275  for(int i=0; i<HISTO_LENGTH; i++)
276  {
277  if(i==ind1 || i==ind2 || i==ind3)
278  continue;
279  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
280  {
281  vpMapPointMatches[rotHist[i][j]]=static_cast<MapPoint*>(NULL);
282  nmatches--;
283  }
284  }
285  }
286 
287  return nmatches;
288 }
289 
290 int ORBmatcher::SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const vector<MapPoint*> &vpPoints, vector<MapPoint*> &vpMatched, int th)
291 {
292  // Get Calibration Parameters for later projection
293  const float &fx = pKF->fx;
294  const float &fy = pKF->fy;
295  const float &cx = pKF->cx;
296  const float &cy = pKF->cy;
297 
298  // Decompose Scw
299  cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3);
300  const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0)));
301  cv::Mat Rcw = sRcw/scw;
302  cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw;
303  cv::Mat Ow = -Rcw.t()*tcw;
304 
305  // Set of MapPoints already found in the KeyFrame
306  set<MapPoint*> spAlreadyFound(vpMatched.begin(), vpMatched.end());
307  spAlreadyFound.erase(static_cast<MapPoint*>(NULL));
308 
309  int nmatches=0;
310 
311  // For each Candidate MapPoint Project and Match
312  for(int iMP=0, iendMP=vpPoints.size(); iMP<iendMP; iMP++)
313  {
314  MapPoint* pMP = vpPoints[iMP];
315 
316  // Discard Bad MapPoints and already found
317  if(pMP->isBad() || spAlreadyFound.count(pMP))
318  continue;
319 
320  // Get 3D Coords.
321  cv::Mat p3Dw = pMP->GetWorldPos();
322 
323  // Transform into Camera Coords.
324  cv::Mat p3Dc = Rcw*p3Dw+tcw;
325 
326  // Depth must be positive
327  if(p3Dc.at<float>(2)<0.0)
328  continue;
329 
330  // Project into Image
331  const float invz = 1/p3Dc.at<float>(2);
332  const float x = p3Dc.at<float>(0)*invz;
333  const float y = p3Dc.at<float>(1)*invz;
334 
335  const float u = fx*x+cx;
336  const float v = fy*y+cy;
337 
338  // Point must be inside the image
339  if(!pKF->IsInImage(u,v))
340  continue;
341 
342  // Depth must be inside the scale invariance region of the point
343  const float maxDistance = pMP->GetMaxDistanceInvariance();
344  const float minDistance = pMP->GetMinDistanceInvariance();
345  cv::Mat PO = p3Dw-Ow;
346  const float dist = cv::norm(PO);
347 
348  if(dist<minDistance || dist>maxDistance)
349  continue;
350 
351  // Viewing angle must be less than 60 deg
352  cv::Mat Pn = pMP->GetNormal();
353 
354  if(PO.dot(Pn)<0.5*dist)
355  continue;
356 
357  int nPredictedLevel = pMP->PredictScale(dist,pKF);
358 
359  // Search in a radius
360  const float radius = th*pKF->mvScaleFactors[nPredictedLevel];
361 
362  const vector<size_t> vIndices = pKF->GetFeaturesInArea(u,v,radius);
363 
364  if(vIndices.empty())
365  continue;
366 
367  // Match to the most similar keypoint in the radius
368  const cv::Mat dMP = pMP->GetDescriptor();
369 
370  int bestDist = 256;
371  int bestIdx = -1;
372  for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
373  {
374  const size_t idx = *vit;
375  if(vpMatched[idx])
376  continue;
377 
378  const int &kpLevel= pKF->mvKeysUn[idx].octave;
379 
380  if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
381  continue;
382 
383  const cv::Mat &dKF = pKF->mDescriptors.row(idx);
384 
385  const int dist = DescriptorDistance(dMP,dKF);
386 
387  if(dist<bestDist)
388  {
389  bestDist = dist;
390  bestIdx = idx;
391  }
392  }
393 
394  if(bestDist<=TH_LOW)
395  {
396  vpMatched[bestIdx]=pMP;
397  nmatches++;
398  }
399 
400  }
401 
402  return nmatches;
403 }
404 
405 int ORBmatcher::SearchForInitialization(Frame &F1, Frame &F2, vector<cv::Point2f> &vbPrevMatched, vector<int> &vnMatches12, int windowSize)
406 {
407  int nmatches=0;
408  vnMatches12 = vector<int>(F1.mvKeysUn.size(),-1);
409 
410  vector<int> rotHist[HISTO_LENGTH];
411  for(int i=0;i<HISTO_LENGTH;i++)
412  rotHist[i].reserve(500);
413  const float factor = 1.0f/HISTO_LENGTH;
414 
415  vector<int> vMatchedDistance(F2.mvKeysUn.size(),INT_MAX);
416  vector<int> vnMatches21(F2.mvKeysUn.size(),-1);
417 
418  for(size_t i1=0, iend1=F1.mvKeysUn.size(); i1<iend1; i1++)
419  {
420  cv::KeyPoint kp1 = F1.mvKeysUn[i1];
421  int level1 = kp1.octave;
422  if(level1>0)
423  continue;
424 
425  vector<size_t> vIndices2 = F2.GetFeaturesInArea(vbPrevMatched[i1].x,vbPrevMatched[i1].y, windowSize,level1,level1);
426 
427  if(vIndices2.empty())
428  continue;
429 
430  cv::Mat d1 = F1.mDescriptors.row(i1);
431 
432  int bestDist = INT_MAX;
433  int bestDist2 = INT_MAX;
434  int bestIdx2 = -1;
435 
436  for(vector<size_t>::iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++)
437  {
438  size_t i2 = *vit;
439 
440  cv::Mat d2 = F2.mDescriptors.row(i2);
441 
442  int dist = DescriptorDistance(d1,d2);
443 
444  if(vMatchedDistance[i2]<=dist)
445  continue;
446 
447  if(dist<bestDist)
448  {
449  bestDist2=bestDist;
450  bestDist=dist;
451  bestIdx2=i2;
452  }
453  else if(dist<bestDist2)
454  {
455  bestDist2=dist;
456  }
457  }
458 
459  if(bestDist<=TH_LOW)
460  {
461  if(bestDist<(float)bestDist2*mfNNratio)
462  {
463  if(vnMatches21[bestIdx2]>=0)
464  {
465  vnMatches12[vnMatches21[bestIdx2]]=-1;
466  nmatches--;
467  }
468  vnMatches12[i1]=bestIdx2;
469  vnMatches21[bestIdx2]=i1;
470  vMatchedDistance[bestIdx2]=bestDist;
471  nmatches++;
472 
474  {
475  float rot = F1.mvKeysUn[i1].angle-F2.mvKeysUn[bestIdx2].angle;
476  if(rot<0.0)
477  rot+=360.0f;
478  int bin = round(rot*factor);
479  if(bin==HISTO_LENGTH)
480  bin=0;
481  assert(bin>=0 && bin<HISTO_LENGTH);
482  rotHist[bin].push_back(i1);
483  }
484  }
485  }
486 
487  }
488 
490  {
491  int ind1=-1;
492  int ind2=-1;
493  int ind3=-1;
494 
495  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
496 
497  for(int i=0; i<HISTO_LENGTH; i++)
498  {
499  if(i==ind1 || i==ind2 || i==ind3)
500  continue;
501  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
502  {
503  int idx1 = rotHist[i][j];
504  if(vnMatches12[idx1]>=0)
505  {
506  vnMatches12[idx1]=-1;
507  nmatches--;
508  }
509  }
510  }
511 
512  }
513 
514  //Update prev matched
515  for(size_t i1=0, iend1=vnMatches12.size(); i1<iend1; i1++)
516  if(vnMatches12[i1]>=0)
517  vbPrevMatched[i1]=F2.mvKeysUn[vnMatches12[i1]].pt;
518 
519  return nmatches;
520 }
521 
522 int ORBmatcher::SearchByBoW(KeyFrame *pKF1, KeyFrame *pKF2, vector<MapPoint *> &vpMatches12)
523 {
524  const vector<cv::KeyPoint> &vKeysUn1 = pKF1->mvKeysUn;
525  const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec;
526  const vector<MapPoint*> vpMapPoints1 = pKF1->GetMapPointMatches();
527  const cv::Mat &Descriptors1 = pKF1->mDescriptors;
528 
529  const vector<cv::KeyPoint> &vKeysUn2 = pKF2->mvKeysUn;
530  const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec;
531  const vector<MapPoint*> vpMapPoints2 = pKF2->GetMapPointMatches();
532  const cv::Mat &Descriptors2 = pKF2->mDescriptors;
533 
534  vpMatches12 = vector<MapPoint*>(vpMapPoints1.size(),static_cast<MapPoint*>(NULL));
535  vector<bool> vbMatched2(vpMapPoints2.size(),false);
536 
537  vector<int> rotHist[HISTO_LENGTH];
538  for(int i=0;i<HISTO_LENGTH;i++)
539  rotHist[i].reserve(500);
540 
541  const float factor = 1.0f/HISTO_LENGTH;
542 
543  int nmatches = 0;
544 
545  DBoW2::FeatureVector::const_iterator f1it = vFeatVec1.begin();
546  DBoW2::FeatureVector::const_iterator f2it = vFeatVec2.begin();
547  DBoW2::FeatureVector::const_iterator f1end = vFeatVec1.end();
548  DBoW2::FeatureVector::const_iterator f2end = vFeatVec2.end();
549 
550  while(f1it != f1end && f2it != f2end)
551  {
552  if(f1it->first == f2it->first)
553  {
554  for(size_t i1=0, iend1=f1it->second.size(); i1<iend1; i1++)
555  {
556  const size_t idx1 = f1it->second[i1];
557 
558  MapPoint* pMP1 = vpMapPoints1[idx1];
559  if(!pMP1)
560  continue;
561  if(pMP1->isBad())
562  continue;
563 
564  const cv::Mat &d1 = Descriptors1.row(idx1);
565 
566  int bestDist1=256;
567  int bestIdx2 =-1 ;
568  int bestDist2=256;
569 
570  for(size_t i2=0, iend2=f2it->second.size(); i2<iend2; i2++)
571  {
572  const size_t idx2 = f2it->second[i2];
573 
574  MapPoint* pMP2 = vpMapPoints2[idx2];
575 
576  if(vbMatched2[idx2] || !pMP2)
577  continue;
578 
579  if(pMP2->isBad())
580  continue;
581 
582  const cv::Mat &d2 = Descriptors2.row(idx2);
583 
584  int dist = DescriptorDistance(d1,d2);
585 
586  if(dist<bestDist1)
587  {
588  bestDist2=bestDist1;
589  bestDist1=dist;
590  bestIdx2=idx2;
591  }
592  else if(dist<bestDist2)
593  {
594  bestDist2=dist;
595  }
596  }
597 
598  if(bestDist1<TH_LOW)
599  {
600  if(static_cast<float>(bestDist1)<mfNNratio*static_cast<float>(bestDist2))
601  {
602  vpMatches12[idx1]=vpMapPoints2[bestIdx2];
603  vbMatched2[bestIdx2]=true;
604 
606  {
607  float rot = vKeysUn1[idx1].angle-vKeysUn2[bestIdx2].angle;
608  if(rot<0.0)
609  rot+=360.0f;
610  int bin = round(rot*factor);
611  if(bin==HISTO_LENGTH)
612  bin=0;
613  assert(bin>=0 && bin<HISTO_LENGTH);
614  rotHist[bin].push_back(idx1);
615  }
616  nmatches++;
617  }
618  }
619  }
620 
621  f1it++;
622  f2it++;
623  }
624  else if(f1it->first < f2it->first)
625  {
626  f1it = vFeatVec1.lower_bound(f2it->first);
627  }
628  else
629  {
630  f2it = vFeatVec2.lower_bound(f1it->first);
631  }
632  }
633 
635  {
636  int ind1=-1;
637  int ind2=-1;
638  int ind3=-1;
639 
640  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
641 
642  for(int i=0; i<HISTO_LENGTH; i++)
643  {
644  if(i==ind1 || i==ind2 || i==ind3)
645  continue;
646  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
647  {
648  vpMatches12[rotHist[i][j]]=static_cast<MapPoint*>(NULL);
649  nmatches--;
650  }
651  }
652  }
653 
654  return nmatches;
655 }
656 
658  vector<pair<size_t, size_t> > &vMatchedPairs, const bool bOnlyStereo)
659 {
660  const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec;
661  const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec;
662 
663  //Compute epipole in second image
664  cv::Mat Cw = pKF1->GetCameraCenter();
665  cv::Mat R2w = pKF2->GetRotation();
666  cv::Mat t2w = pKF2->GetTranslation();
667  cv::Mat C2 = R2w*Cw+t2w;
668  const float invz = 1.0f/C2.at<float>(2);
669  const float ex =pKF2->fx*C2.at<float>(0)*invz+pKF2->cx;
670  const float ey =pKF2->fy*C2.at<float>(1)*invz+pKF2->cy;
671 
672  // Find matches between not tracked keypoints
673  // Matching speed-up by ORB Vocabulary
674  // Compare only ORB that share the same node
675 
676  int nmatches=0;
677  vector<bool> vbMatched2(pKF2->N,false);
678  vector<int> vMatches12(pKF1->N,-1);
679 
680  vector<int> rotHist[HISTO_LENGTH];
681  for(int i=0;i<HISTO_LENGTH;i++)
682  rotHist[i].reserve(500);
683 
684  const float factor = 1.0f/HISTO_LENGTH;
685 
686  DBoW2::FeatureVector::const_iterator f1it = vFeatVec1.begin();
687  DBoW2::FeatureVector::const_iterator f2it = vFeatVec2.begin();
688  DBoW2::FeatureVector::const_iterator f1end = vFeatVec1.end();
689  DBoW2::FeatureVector::const_iterator f2end = vFeatVec2.end();
690 
691  while(f1it!=f1end && f2it!=f2end)
692  {
693  if(f1it->first == f2it->first)
694  {
695  for(size_t i1=0, iend1=f1it->second.size(); i1<iend1; i1++)
696  {
697  const size_t idx1 = f1it->second[i1];
698 
699  MapPoint* pMP1 = pKF1->GetMapPoint(idx1);
700 
701  // If there is already a MapPoint skip
702  if(pMP1)
703  continue;
704 
705  const bool bStereo1 = pKF1->mvuRight[idx1]>=0;
706 
707  if(bOnlyStereo)
708  if(!bStereo1)
709  continue;
710 
711  const cv::KeyPoint &kp1 = pKF1->mvKeysUn[idx1];
712 
713  const cv::Mat &d1 = pKF1->mDescriptors.row(idx1);
714 
715  int bestDist = TH_LOW;
716  int bestIdx2 = -1;
717 
718  for(size_t i2=0, iend2=f2it->second.size(); i2<iend2; i2++)
719  {
720  size_t idx2 = f2it->second[i2];
721 
722  MapPoint* pMP2 = pKF2->GetMapPoint(idx2);
723 
724  // If we have already matched or there is a MapPoint skip
725  if(vbMatched2[idx2] || pMP2)
726  continue;
727 
728  const bool bStereo2 = pKF2->mvuRight[idx2]>=0;
729 
730  if(bOnlyStereo)
731  if(!bStereo2)
732  continue;
733 
734  const cv::Mat &d2 = pKF2->mDescriptors.row(idx2);
735 
736  const int dist = DescriptorDistance(d1,d2);
737 
738  if(dist>TH_LOW || dist>bestDist)
739  continue;
740 
741  const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2];
742 
743  if(!bStereo1 && !bStereo2)
744  {
745  const float distex = ex-kp2.pt.x;
746  const float distey = ey-kp2.pt.y;
747  if(distex*distex+distey*distey<100*pKF2->mvScaleFactors[kp2.octave])
748  continue;
749  }
750 
751  if(CheckDistEpipolarLine(kp1,kp2,F12,pKF2))
752  {
753  bestIdx2 = idx2;
754  bestDist = dist;
755  }
756  }
757 
758  if(bestIdx2>=0)
759  {
760  const cv::KeyPoint &kp2 = pKF2->mvKeysUn[bestIdx2];
761  vMatches12[idx1]=bestIdx2;
762  nmatches++;
763 
765  {
766  float rot = kp1.angle-kp2.angle;
767  if(rot<0.0)
768  rot+=360.0f;
769  int bin = round(rot*factor);
770  if(bin==HISTO_LENGTH)
771  bin=0;
772  assert(bin>=0 && bin<HISTO_LENGTH);
773  rotHist[bin].push_back(idx1);
774  }
775  }
776  }
777 
778  f1it++;
779  f2it++;
780  }
781  else if(f1it->first < f2it->first)
782  {
783  f1it = vFeatVec1.lower_bound(f2it->first);
784  }
785  else
786  {
787  f2it = vFeatVec2.lower_bound(f1it->first);
788  }
789  }
790 
792  {
793  int ind1=-1;
794  int ind2=-1;
795  int ind3=-1;
796 
797  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
798 
799  for(int i=0; i<HISTO_LENGTH; i++)
800  {
801  if(i==ind1 || i==ind2 || i==ind3)
802  continue;
803  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
804  {
805  vMatches12[rotHist[i][j]]=-1;
806  nmatches--;
807  }
808  }
809 
810  }
811 
812  vMatchedPairs.clear();
813  vMatchedPairs.reserve(nmatches);
814 
815  for(size_t i=0, iend=vMatches12.size(); i<iend; i++)
816  {
817  if(vMatches12[i]<0)
818  continue;
819  vMatchedPairs.push_back(make_pair(i,vMatches12[i]));
820  }
821 
822  return nmatches;
823 }
824 
825 int ORBmatcher::Fuse(KeyFrame *pKF, const vector<MapPoint *> &vpMapPoints, const float th)
826 {
827  cv::Mat Rcw = pKF->GetRotation();
828  cv::Mat tcw = pKF->GetTranslation();
829 
830  const float &fx = pKF->fx;
831  const float &fy = pKF->fy;
832  const float &cx = pKF->cx;
833  const float &cy = pKF->cy;
834  const float &bf = pKF->mbf;
835 
836  cv::Mat Ow = pKF->GetCameraCenter();
837 
838  int nFused=0;
839 
840  const int nMPs = vpMapPoints.size();
841 
842  for(int i=0; i<nMPs; i++)
843  {
844  MapPoint* pMP = vpMapPoints[i];
845 
846  if(!pMP)
847  continue;
848 
849  if(pMP->isBad() || pMP->IsInKeyFrame(pKF))
850  continue;
851 
852  cv::Mat p3Dw = pMP->GetWorldPos();
853  cv::Mat p3Dc = Rcw*p3Dw + tcw;
854 
855  // Depth must be positive
856  if(p3Dc.at<float>(2)<0.0f)
857  continue;
858 
859  const float invz = 1/p3Dc.at<float>(2);
860  const float x = p3Dc.at<float>(0)*invz;
861  const float y = p3Dc.at<float>(1)*invz;
862 
863  const float u = fx*x+cx;
864  const float v = fy*y+cy;
865 
866  // Point must be inside the image
867  if(!pKF->IsInImage(u,v))
868  continue;
869 
870  const float ur = u-bf*invz;
871 
872  const float maxDistance = pMP->GetMaxDistanceInvariance();
873  const float minDistance = pMP->GetMinDistanceInvariance();
874  cv::Mat PO = p3Dw-Ow;
875  const float dist3D = cv::norm(PO);
876 
877  // Depth must be inside the scale pyramid of the image
878  if(dist3D<minDistance || dist3D>maxDistance )
879  continue;
880 
881  // Viewing angle must be less than 60 deg
882  cv::Mat Pn = pMP->GetNormal();
883 
884  if(PO.dot(Pn)<0.5*dist3D)
885  continue;
886 
887  int nPredictedLevel = pMP->PredictScale(dist3D,pKF);
888 
889  // Search in a radius
890  const float radius = th*pKF->mvScaleFactors[nPredictedLevel];
891 
892  const vector<size_t> vIndices = pKF->GetFeaturesInArea(u,v,radius);
893 
894  if(vIndices.empty())
895  continue;
896 
897  // Match to the most similar keypoint in the radius
898 
899  const cv::Mat dMP = pMP->GetDescriptor();
900 
901  int bestDist = 256;
902  int bestIdx = -1;
903  for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
904  {
905  const size_t idx = *vit;
906 
907  const cv::KeyPoint &kp = pKF->mvKeysUn[idx];
908 
909  const int &kpLevel= kp.octave;
910 
911  if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
912  continue;
913 
914  if(pKF->mvuRight[idx]>=0)
915  {
916  // Check reprojection error in stereo
917  const float &kpx = kp.pt.x;
918  const float &kpy = kp.pt.y;
919  const float &kpr = pKF->mvuRight[idx];
920  const float ex = u-kpx;
921  const float ey = v-kpy;
922  const float er = ur-kpr;
923  const float e2 = ex*ex+ey*ey+er*er;
924 
925  if(e2*pKF->mvInvLevelSigma2[kpLevel]>7.8)
926  continue;
927  }
928  else
929  {
930  const float &kpx = kp.pt.x;
931  const float &kpy = kp.pt.y;
932  const float ex = u-kpx;
933  const float ey = v-kpy;
934  const float e2 = ex*ex+ey*ey;
935 
936  if(e2*pKF->mvInvLevelSigma2[kpLevel]>5.99)
937  continue;
938  }
939 
940  const cv::Mat &dKF = pKF->mDescriptors.row(idx);
941 
942  const int dist = DescriptorDistance(dMP,dKF);
943 
944  if(dist<bestDist)
945  {
946  bestDist = dist;
947  bestIdx = idx;
948  }
949  }
950 
951  // If there is already a MapPoint replace otherwise add new measurement
952  if(bestDist<=TH_LOW)
953  {
954  MapPoint* pMPinKF = pKF->GetMapPoint(bestIdx);
955  if(pMPinKF)
956  {
957  if(!pMPinKF->isBad())
958  {
959  if(pMPinKF->Observations()>pMP->Observations())
960  pMP->Replace(pMPinKF);
961  else
962  pMPinKF->Replace(pMP);
963  }
964  }
965  else
966  {
967  pMP->AddObservation(pKF,bestIdx);
968  pKF->AddMapPoint(pMP,bestIdx);
969  }
970  nFused++;
971  }
972  }
973 
974  return nFused;
975 }
976 
977 int ORBmatcher::Fuse(KeyFrame *pKF, cv::Mat Scw, const vector<MapPoint *> &vpPoints, float th, vector<MapPoint *> &vpReplacePoint)
978 {
979  // Get Calibration Parameters for later projection
980  const float &fx = pKF->fx;
981  const float &fy = pKF->fy;
982  const float &cx = pKF->cx;
983  const float &cy = pKF->cy;
984 
985  // Decompose Scw
986  cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3);
987  const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0)));
988  cv::Mat Rcw = sRcw/scw;
989  cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw;
990  cv::Mat Ow = -Rcw.t()*tcw;
991 
992  // Set of MapPoints already found in the KeyFrame
993  const set<MapPoint*> spAlreadyFound = pKF->GetMapPoints();
994 
995  int nFused=0;
996 
997  const int nPoints = vpPoints.size();
998 
999  // For each candidate MapPoint project and match
1000  for(int iMP=0; iMP<nPoints; iMP++)
1001  {
1002  MapPoint* pMP = vpPoints[iMP];
1003 
1004  // Discard Bad MapPoints and already found
1005  if(pMP->isBad() || spAlreadyFound.count(pMP))
1006  continue;
1007 
1008  // Get 3D Coords.
1009  cv::Mat p3Dw = pMP->GetWorldPos();
1010 
1011  // Transform into Camera Coords.
1012  cv::Mat p3Dc = Rcw*p3Dw+tcw;
1013 
1014  // Depth must be positive
1015  if(p3Dc.at<float>(2)<0.0f)
1016  continue;
1017 
1018  // Project into Image
1019  const float invz = 1.0/p3Dc.at<float>(2);
1020  const float x = p3Dc.at<float>(0)*invz;
1021  const float y = p3Dc.at<float>(1)*invz;
1022 
1023  const float u = fx*x+cx;
1024  const float v = fy*y+cy;
1025 
1026  // Point must be inside the image
1027  if(!pKF->IsInImage(u,v))
1028  continue;
1029 
1030  // Depth must be inside the scale pyramid of the image
1031  const float maxDistance = pMP->GetMaxDistanceInvariance();
1032  const float minDistance = pMP->GetMinDistanceInvariance();
1033  cv::Mat PO = p3Dw-Ow;
1034  const float dist3D = cv::norm(PO);
1035 
1036  if(dist3D<minDistance || dist3D>maxDistance)
1037  continue;
1038 
1039  // Viewing angle must be less than 60 deg
1040  cv::Mat Pn = pMP->GetNormal();
1041 
1042  if(PO.dot(Pn)<0.5*dist3D)
1043  continue;
1044 
1045  // Compute predicted scale level
1046  const int nPredictedLevel = pMP->PredictScale(dist3D,pKF);
1047 
1048  // Search in a radius
1049  const float radius = th*pKF->mvScaleFactors[nPredictedLevel];
1050 
1051  const vector<size_t> vIndices = pKF->GetFeaturesInArea(u,v,radius);
1052 
1053  if(vIndices.empty())
1054  continue;
1055 
1056  // Match to the most similar keypoint in the radius
1057 
1058  const cv::Mat dMP = pMP->GetDescriptor();
1059 
1060  int bestDist = INT_MAX;
1061  int bestIdx = -1;
1062  for(vector<size_t>::const_iterator vit=vIndices.begin(); vit!=vIndices.end(); vit++)
1063  {
1064  const size_t idx = *vit;
1065  const int &kpLevel = pKF->mvKeysUn[idx].octave;
1066 
1067  if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
1068  continue;
1069 
1070  const cv::Mat &dKF = pKF->mDescriptors.row(idx);
1071 
1072  int dist = DescriptorDistance(dMP,dKF);
1073 
1074  if(dist<bestDist)
1075  {
1076  bestDist = dist;
1077  bestIdx = idx;
1078  }
1079  }
1080 
1081  // If there is already a MapPoint replace otherwise add new measurement
1082  if(bestDist<=TH_LOW)
1083  {
1084  MapPoint* pMPinKF = pKF->GetMapPoint(bestIdx);
1085  if(pMPinKF)
1086  {
1087  if(!pMPinKF->isBad())
1088  vpReplacePoint[iMP] = pMPinKF;
1089  }
1090  else
1091  {
1092  pMP->AddObservation(pKF,bestIdx);
1093  pKF->AddMapPoint(pMP,bestIdx);
1094  }
1095  nFused++;
1096  }
1097  }
1098 
1099  return nFused;
1100 }
1101 
1102 int ORBmatcher::SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, vector<MapPoint*> &vpMatches12,
1103  const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
1104 {
1105  const float &fx = pKF1->fx;
1106  const float &fy = pKF1->fy;
1107  const float &cx = pKF1->cx;
1108  const float &cy = pKF1->cy;
1109 
1110  // Camera 1 from world
1111  cv::Mat R1w = pKF1->GetRotation();
1112  cv::Mat t1w = pKF1->GetTranslation();
1113 
1114  //Camera 2 from world
1115  cv::Mat R2w = pKF2->GetRotation();
1116  cv::Mat t2w = pKF2->GetTranslation();
1117 
1118  //Transformation between cameras
1119  cv::Mat sR12 = s12*R12;
1120  cv::Mat sR21 = (1.0/s12)*R12.t();
1121  cv::Mat t21 = -sR21*t12;
1122 
1123  const vector<MapPoint*> vpMapPoints1 = pKF1->GetMapPointMatches();
1124  const int N1 = vpMapPoints1.size();
1125 
1126  const vector<MapPoint*> vpMapPoints2 = pKF2->GetMapPointMatches();
1127  const int N2 = vpMapPoints2.size();
1128 
1129  vector<bool> vbAlreadyMatched1(N1,false);
1130  vector<bool> vbAlreadyMatched2(N2,false);
1131 
1132  for(int i=0; i<N1; i++)
1133  {
1134  MapPoint* pMP = vpMatches12[i];
1135  if(pMP)
1136  {
1137  vbAlreadyMatched1[i]=true;
1138  int idx2 = pMP->GetIndexInKeyFrame(pKF2);
1139  if(idx2>=0 && idx2<N2)
1140  vbAlreadyMatched2[idx2]=true;
1141  }
1142  }
1143 
1144  vector<int> vnMatch1(N1,-1);
1145  vector<int> vnMatch2(N2,-1);
1146 
1147  // Transform from KF1 to KF2 and search
1148  for(int i1=0; i1<N1; i1++)
1149  {
1150  MapPoint* pMP = vpMapPoints1[i1];
1151 
1152  if(!pMP || vbAlreadyMatched1[i1])
1153  continue;
1154 
1155  if(pMP->isBad())
1156  continue;
1157 
1158  cv::Mat p3Dw = pMP->GetWorldPos();
1159  cv::Mat p3Dc1 = R1w*p3Dw + t1w;
1160  cv::Mat p3Dc2 = sR21*p3Dc1 + t21;
1161 
1162  // Depth must be positive
1163  if(p3Dc2.at<float>(2)<0.0)
1164  continue;
1165 
1166  const float invz = 1.0/p3Dc2.at<float>(2);
1167  const float x = p3Dc2.at<float>(0)*invz;
1168  const float y = p3Dc2.at<float>(1)*invz;
1169 
1170  const float u = fx*x+cx;
1171  const float v = fy*y+cy;
1172 
1173  // Point must be inside the image
1174  if(!pKF2->IsInImage(u,v))
1175  continue;
1176 
1177  const float maxDistance = pMP->GetMaxDistanceInvariance();
1178  const float minDistance = pMP->GetMinDistanceInvariance();
1179  const float dist3D = cv::norm(p3Dc2);
1180 
1181  // Depth must be inside the scale invariance region
1182  if(dist3D<minDistance || dist3D>maxDistance )
1183  continue;
1184 
1185  // Compute predicted octave
1186  const int nPredictedLevel = pMP->PredictScale(dist3D,pKF2);
1187 
1188  // Search in a radius
1189  const float radius = th*pKF2->mvScaleFactors[nPredictedLevel];
1190 
1191  const vector<size_t> vIndices = pKF2->GetFeaturesInArea(u,v,radius);
1192 
1193  if(vIndices.empty())
1194  continue;
1195 
1196  // Match to the most similar keypoint in the radius
1197  const cv::Mat dMP = pMP->GetDescriptor();
1198 
1199  int bestDist = INT_MAX;
1200  int bestIdx = -1;
1201  for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
1202  {
1203  const size_t idx = *vit;
1204 
1205  const cv::KeyPoint &kp = pKF2->mvKeysUn[idx];
1206 
1207  if(kp.octave<nPredictedLevel-1 || kp.octave>nPredictedLevel)
1208  continue;
1209 
1210  const cv::Mat &dKF = pKF2->mDescriptors.row(idx);
1211 
1212  const int dist = DescriptorDistance(dMP,dKF);
1213 
1214  if(dist<bestDist)
1215  {
1216  bestDist = dist;
1217  bestIdx = idx;
1218  }
1219  }
1220 
1221  if(bestDist<=TH_HIGH)
1222  {
1223  vnMatch1[i1]=bestIdx;
1224  }
1225  }
1226 
1227  // Transform from KF2 to KF2 and search
1228  for(int i2=0; i2<N2; i2++)
1229  {
1230  MapPoint* pMP = vpMapPoints2[i2];
1231 
1232  if(!pMP || vbAlreadyMatched2[i2])
1233  continue;
1234 
1235  if(pMP->isBad())
1236  continue;
1237 
1238  cv::Mat p3Dw = pMP->GetWorldPos();
1239  cv::Mat p3Dc2 = R2w*p3Dw + t2w;
1240  cv::Mat p3Dc1 = sR12*p3Dc2 + t12;
1241 
1242  // Depth must be positive
1243  if(p3Dc1.at<float>(2)<0.0)
1244  continue;
1245 
1246  const float invz = 1.0/p3Dc1.at<float>(2);
1247  const float x = p3Dc1.at<float>(0)*invz;
1248  const float y = p3Dc1.at<float>(1)*invz;
1249 
1250  const float u = fx*x+cx;
1251  const float v = fy*y+cy;
1252 
1253  // Point must be inside the image
1254  if(!pKF1->IsInImage(u,v))
1255  continue;
1256 
1257  const float maxDistance = pMP->GetMaxDistanceInvariance();
1258  const float minDistance = pMP->GetMinDistanceInvariance();
1259  const float dist3D = cv::norm(p3Dc1);
1260 
1261  // Depth must be inside the scale pyramid of the image
1262  if(dist3D<minDistance || dist3D>maxDistance)
1263  continue;
1264 
1265  // Compute predicted octave
1266  const int nPredictedLevel = pMP->PredictScale(dist3D,pKF1);
1267 
1268  // Search in a radius of 2.5*sigma(ScaleLevel)
1269  const float radius = th*pKF1->mvScaleFactors[nPredictedLevel];
1270 
1271  const vector<size_t> vIndices = pKF1->GetFeaturesInArea(u,v,radius);
1272 
1273  if(vIndices.empty())
1274  continue;
1275 
1276  // Match to the most similar keypoint in the radius
1277  const cv::Mat dMP = pMP->GetDescriptor();
1278 
1279  int bestDist = INT_MAX;
1280  int bestIdx = -1;
1281  for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
1282  {
1283  const size_t idx = *vit;
1284 
1285  const cv::KeyPoint &kp = pKF1->mvKeysUn[idx];
1286 
1287  if(kp.octave<nPredictedLevel-1 || kp.octave>nPredictedLevel)
1288  continue;
1289 
1290  const cv::Mat &dKF = pKF1->mDescriptors.row(idx);
1291 
1292  const int dist = DescriptorDistance(dMP,dKF);
1293 
1294  if(dist<bestDist)
1295  {
1296  bestDist = dist;
1297  bestIdx = idx;
1298  }
1299  }
1300 
1301  if(bestDist<=TH_HIGH)
1302  {
1303  vnMatch2[i2]=bestIdx;
1304  }
1305  }
1306 
1307  // Check agreement
1308  int nFound = 0;
1309 
1310  for(int i1=0; i1<N1; i1++)
1311  {
1312  int idx2 = vnMatch1[i1];
1313 
1314  if(idx2>=0)
1315  {
1316  int idx1 = vnMatch2[idx2];
1317  if(idx1==i1)
1318  {
1319  vpMatches12[i1] = vpMapPoints2[idx2];
1320  nFound++;
1321  }
1322  }
1323  }
1324 
1325  return nFound;
1326 }
1327 
1328 int ORBmatcher::SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono)
1329 {
1330  int nmatches = 0;
1331 
1332  // Rotation Histogram (to check rotation consistency)
1333  vector<int> rotHist[HISTO_LENGTH];
1334  for(int i=0;i<HISTO_LENGTH;i++)
1335  rotHist[i].reserve(500);
1336  const float factor = 1.0f/HISTO_LENGTH;
1337 
1338  const cv::Mat Rcw = CurrentFrame.mTcw.rowRange(0,3).colRange(0,3);
1339  const cv::Mat tcw = CurrentFrame.mTcw.rowRange(0,3).col(3);
1340 
1341  const cv::Mat twc = -Rcw.t()*tcw;
1342 
1343  const cv::Mat Rlw = LastFrame.mTcw.rowRange(0,3).colRange(0,3);
1344  const cv::Mat tlw = LastFrame.mTcw.rowRange(0,3).col(3);
1345 
1346  const cv::Mat tlc = Rlw*twc+tlw;
1347 
1348  const bool bForward = tlc.at<float>(2)>CurrentFrame.mb && !bMono;
1349  const bool bBackward = -tlc.at<float>(2)>CurrentFrame.mb && !bMono;
1350 
1351  for(int i=0; i<LastFrame.N; i++)
1352  {
1353  MapPoint* pMP = LastFrame.mvpMapPoints[i];
1354 
1355  if(pMP)
1356  {
1357  if(!LastFrame.mvbOutlier[i])
1358  {
1359  // Project
1360  cv::Mat x3Dw = pMP->GetWorldPos();
1361  cv::Mat x3Dc = Rcw*x3Dw+tcw;
1362 
1363  const float xc = x3Dc.at<float>(0);
1364  const float yc = x3Dc.at<float>(1);
1365  const float invzc = 1.0/x3Dc.at<float>(2);
1366 
1367  if(invzc<0)
1368  continue;
1369 
1370  float u = CurrentFrame.fx*xc*invzc+CurrentFrame.cx;
1371  float v = CurrentFrame.fy*yc*invzc+CurrentFrame.cy;
1372 
1373  if(u<CurrentFrame.mnMinX || u>CurrentFrame.mnMaxX)
1374  continue;
1375  if(v<CurrentFrame.mnMinY || v>CurrentFrame.mnMaxY)
1376  continue;
1377 
1378  int nLastOctave = LastFrame.mvKeys[i].octave;
1379 
1380  // Search in a window. Size depends on scale
1381  float radius = th*CurrentFrame.mvScaleFactors[nLastOctave];
1382 
1383  vector<size_t> vIndices2;
1384 
1385  if(bForward)
1386  vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, nLastOctave);
1387  else if(bBackward)
1388  vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, 0, nLastOctave);
1389  else
1390  vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, nLastOctave-1, nLastOctave+1);
1391 
1392  if(vIndices2.empty())
1393  continue;
1394 
1395  const cv::Mat dMP = pMP->GetDescriptor();
1396 
1397  int bestDist = 256;
1398  int bestIdx2 = -1;
1399 
1400  for(vector<size_t>::const_iterator vit=vIndices2.begin(), vend=vIndices2.end(); vit!=vend; vit++)
1401  {
1402  const size_t i2 = *vit;
1403  if(CurrentFrame.mvpMapPoints[i2])
1404  if(CurrentFrame.mvpMapPoints[i2]->Observations()>0)
1405  continue;
1406 
1407  if(CurrentFrame.mvuRight[i2]>0)
1408  {
1409  const float ur = u - CurrentFrame.mbf*invzc;
1410  const float er = fabs(ur - CurrentFrame.mvuRight[i2]);
1411  if(er>radius)
1412  continue;
1413  }
1414 
1415  const cv::Mat &d = CurrentFrame.mDescriptors.row(i2);
1416 
1417  const int dist = DescriptorDistance(dMP,d);
1418 
1419  if(dist<bestDist)
1420  {
1421  bestDist=dist;
1422  bestIdx2=i2;
1423  }
1424  }
1425 
1426  if(bestDist<=TH_HIGH)
1427  {
1428  CurrentFrame.mvpMapPoints[bestIdx2]=pMP;
1429  nmatches++;
1430 
1431  if(mbCheckOrientation)
1432  {
1433  float rot = LastFrame.mvKeysUn[i].angle-CurrentFrame.mvKeysUn[bestIdx2].angle;
1434  if(rot<0.0)
1435  rot+=360.0f;
1436  int bin = round(rot*factor);
1437  if(bin==HISTO_LENGTH)
1438  bin=0;
1439  assert(bin>=0 && bin<HISTO_LENGTH);
1440  rotHist[bin].push_back(bestIdx2);
1441  }
1442  }
1443  }
1444  }
1445  }
1446 
1447  //Apply rotation consistency
1448  if(mbCheckOrientation)
1449  {
1450  int ind1=-1;
1451  int ind2=-1;
1452  int ind3=-1;
1453 
1454  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
1455 
1456  for(int i=0; i<HISTO_LENGTH; i++)
1457  {
1458  if(i!=ind1 && i!=ind2 && i!=ind3)
1459  {
1460  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
1461  {
1462  CurrentFrame.mvpMapPoints[rotHist[i][j]]=static_cast<MapPoint*>(NULL);
1463  nmatches--;
1464  }
1465  }
1466  }
1467  }
1468 
1469  return nmatches;
1470 }
1471 
1472 int ORBmatcher::SearchByProjection(Frame &CurrentFrame, KeyFrame *pKF, const set<MapPoint*> &sAlreadyFound, const float th , const int ORBdist)
1473 {
1474  int nmatches = 0;
1475 
1476  const cv::Mat Rcw = CurrentFrame.mTcw.rowRange(0,3).colRange(0,3);
1477  const cv::Mat tcw = CurrentFrame.mTcw.rowRange(0,3).col(3);
1478  const cv::Mat Ow = -Rcw.t()*tcw;
1479 
1480  // Rotation Histogram (to check rotation consistency)
1481  vector<int> rotHist[HISTO_LENGTH];
1482  for(int i=0;i<HISTO_LENGTH;i++)
1483  rotHist[i].reserve(500);
1484  const float factor = 1.0f/HISTO_LENGTH;
1485 
1486  const vector<MapPoint*> vpMPs = pKF->GetMapPointMatches();
1487 
1488  for(size_t i=0, iend=vpMPs.size(); i<iend; i++)
1489  {
1490  MapPoint* pMP = vpMPs[i];
1491 
1492  if(pMP)
1493  {
1494  if(!pMP->isBad() && !sAlreadyFound.count(pMP))
1495  {
1496  //Project
1497  cv::Mat x3Dw = pMP->GetWorldPos();
1498  cv::Mat x3Dc = Rcw*x3Dw+tcw;
1499 
1500  const float xc = x3Dc.at<float>(0);
1501  const float yc = x3Dc.at<float>(1);
1502  const float invzc = 1.0/x3Dc.at<float>(2);
1503 
1504  const float u = CurrentFrame.fx*xc*invzc+CurrentFrame.cx;
1505  const float v = CurrentFrame.fy*yc*invzc+CurrentFrame.cy;
1506 
1507  if(u<CurrentFrame.mnMinX || u>CurrentFrame.mnMaxX)
1508  continue;
1509  if(v<CurrentFrame.mnMinY || v>CurrentFrame.mnMaxY)
1510  continue;
1511 
1512  // Compute predicted scale level
1513  cv::Mat PO = x3Dw-Ow;
1514  float dist3D = cv::norm(PO);
1515 
1516  const float maxDistance = pMP->GetMaxDistanceInvariance();
1517  const float minDistance = pMP->GetMinDistanceInvariance();
1518 
1519  // Depth must be inside the scale pyramid of the image
1520  if(dist3D<minDistance || dist3D>maxDistance)
1521  continue;
1522 
1523  int nPredictedLevel = pMP->PredictScale(dist3D,&CurrentFrame);
1524 
1525  // Search in a window
1526  const float radius = th*CurrentFrame.mvScaleFactors[nPredictedLevel];
1527 
1528  const vector<size_t> vIndices2 = CurrentFrame.GetFeaturesInArea(u, v, radius, nPredictedLevel-1, nPredictedLevel+1);
1529 
1530  if(vIndices2.empty())
1531  continue;
1532 
1533  const cv::Mat dMP = pMP->GetDescriptor();
1534 
1535  int bestDist = 256;
1536  int bestIdx2 = -1;
1537 
1538  for(vector<size_t>::const_iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++)
1539  {
1540  const size_t i2 = *vit;
1541  if(CurrentFrame.mvpMapPoints[i2])
1542  continue;
1543 
1544  const cv::Mat &d = CurrentFrame.mDescriptors.row(i2);
1545 
1546  const int dist = DescriptorDistance(dMP,d);
1547 
1548  if(dist<bestDist)
1549  {
1550  bestDist=dist;
1551  bestIdx2=i2;
1552  }
1553  }
1554 
1555  if(bestDist<=ORBdist)
1556  {
1557  CurrentFrame.mvpMapPoints[bestIdx2]=pMP;
1558  nmatches++;
1559 
1560  if(mbCheckOrientation)
1561  {
1562  float rot = pKF->mvKeysUn[i].angle-CurrentFrame.mvKeysUn[bestIdx2].angle;
1563  if(rot<0.0)
1564  rot+=360.0f;
1565  int bin = round(rot*factor);
1566  if(bin==HISTO_LENGTH)
1567  bin=0;
1568  assert(bin>=0 && bin<HISTO_LENGTH);
1569  rotHist[bin].push_back(bestIdx2);
1570  }
1571  }
1572 
1573  }
1574  }
1575  }
1576 
1577  if(mbCheckOrientation)
1578  {
1579  int ind1=-1;
1580  int ind2=-1;
1581  int ind3=-1;
1582 
1583  ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3);
1584 
1585  for(int i=0; i<HISTO_LENGTH; i++)
1586  {
1587  if(i!=ind1 && i!=ind2 && i!=ind3)
1588  {
1589  for(size_t j=0, jend=rotHist[i].size(); j<jend; j++)
1590  {
1591  CurrentFrame.mvpMapPoints[rotHist[i][j]]=NULL;
1592  nmatches--;
1593  }
1594  }
1595  }
1596  }
1597 
1598  return nmatches;
1599 }
1600 
1601 void ORBmatcher::ComputeThreeMaxima(vector<int>* histo, const int L, int &ind1, int &ind2, int &ind3)
1602 {
1603  int max1=0;
1604  int max2=0;
1605  int max3=0;
1606 
1607  for(int i=0; i<L; i++)
1608  {
1609  const int s = histo[i].size();
1610  if(s>max1)
1611  {
1612  max3=max2;
1613  max2=max1;
1614  max1=s;
1615  ind3=ind2;
1616  ind2=ind1;
1617  ind1=i;
1618  }
1619  else if(s>max2)
1620  {
1621  max3=max2;
1622  max2=s;
1623  ind3=ind2;
1624  ind2=i;
1625  }
1626  else if(s>max3)
1627  {
1628  max3=s;
1629  ind3=i;
1630  }
1631  }
1632 
1633  if(max2<0.1f*(float)max1)
1634  {
1635  ind2=-1;
1636  ind3=-1;
1637  }
1638  else if(max3<0.1f*(float)max1)
1639  {
1640  ind3=-1;
1641  }
1642 }
1643 
1644 
1645 // Bit set count operation from
1646 // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel
1647 int ORBmatcher::DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
1648 {
1649  const int *pa = a.ptr<int32_t>();
1650  const int *pb = b.ptr<int32_t>();
1651 
1652  int dist=0;
1653 
1654  for(int i=0; i<8; i++, pa++, pb++)
1655  {
1656  unsigned int v = *pa ^ *pb;
1657  v = v - ((v >> 1) & 0x55555555);
1658  v = (v & 0x33333333) + ((v >> 2) & 0x33333333);
1659  dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24;
1660  }
1661 
1662  return dist;
1663 }
1664 
1665 } //namespace ORB_SLAM
d
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
float GetMinDistanceInvariance()
Definition: MapPoint.cc:373
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
static float fy
Definition: Frame.h:114
cv::Mat GetCameraCenter()
Definition: KeyFrame.cc:98
const std::vector< float > mvScaleFactors
Definition: KeyFrame.h:181
const float mbf
Definition: KeyFrame.h:158
f
int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
void AddMapPoint(MapPoint *pMP, const size_t &idx)
Definition: KeyFrame.cc:210
int SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
Definition: ORBmatcher.cc:1102
static float cx
Definition: Frame.h:115
const std::vector< float > mvLevelSigma2
Definition: KeyFrame.h:182
static float fx
Definition: Frame.h:113
XmlRpcServer s
int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
Definition: ORBmatcher.cc:657
static float cy
Definition: Frame.h:116
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
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 AddObservation(KeyFrame *pKF, size_t idx)
Definition: MapPoint.cc:98
std::vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r) const
Definition: KeyFrame.cc:569
bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF)
Definition: ORBmatcher.cc:140
TFSIMD_FORCE_INLINE const tfScalar & y() const
cv::Mat GetDescriptor()
Definition: MapPoint.cc:309
float RadiusByViewingCos(const float &viewCos)
Definition: ORBmatcher.cc:131
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
DBoW2::FeatureVector mFeatVec
Definition: Frame.h:147
const float cx
Definition: KeyFrame.h:158
const std::vector< float > mvInvLevelSigma2
Definition: KeyFrame.h:183
std::vector< float > mvuRight
Definition: Frame.h:142
const float fx
Definition: KeyFrame.h:158
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
cv::Mat mTcw
Definition: Frame.h:164
void Replace(MapPoint *pMP)
Definition: MapPoint.cc:177
bool IsInImage(const float &x, const float &y) const
Definition: KeyFrame.cc:610
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
Definition: ORBmatcher.cc:1647
TFSIMD_FORCE_INLINE const tfScalar & x() const
int SearchByProjection(Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
float GetMaxDistanceInvariance()
Definition: MapPoint.cc:379
std::vector< cv::KeyPoint > mvKeys
Definition: Frame.h:137
vector< float > mvScaleFactors
Definition: Frame.h:177
MapPoint * GetMapPoint(const size_t &idx)
Definition: KeyFrame.cc:283
Vector of nodes with indexes of local features.
Definition: FeatureVector.h:21
static float mnMaxY
Definition: Frame.h:186
cv::Mat GetNormal()
Definition: MapPoint.cc:86
const float cy
Definition: KeyFrame.h:158
int SearchForInitialization(Frame &F1, Frame &F2, std::vector< cv::Point2f > &vbPrevMatched, std::vector< int > &vnMatches12, int windowSize=10)
Definition: ORBmatcher.cc:405
static const int HISTO_LENGTH
Definition: ORBmatcher.h:89
DBoW2::FeatureVector mFeatVec
Definition: KeyFrame.h:172
const float fy
Definition: KeyFrame.h:158
const std::vector< float > mvuRight
Definition: KeyFrame.h:166
int GetIndexInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:315
std::set< MapPoint * > GetMapPoints()
Definition: KeyFrame.cc:235
static float mnMaxX
Definition: Frame.h:184
cv::Mat mDescriptors
Definition: Frame.h:150
void ComputeThreeMaxima(std::vector< int > *histo, const int L, int &ind1, int &ind2, int &ind3)
Definition: ORBmatcher.cc:1601
const cv::Mat mDescriptors
Definition: KeyFrame.h:168
bool IsInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:324
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
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)
Definition: ORBmatcher.cc:825


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