25 #include<opencv2/core/core.hpp> 26 #include<opencv2/features2d/features2d.hpp> 30 #include<stdint-gcc.h> 37 const int ORBmatcher::TH_HIGH = 100;
38 const int ORBmatcher::TH_LOW = 50;
39 const int ORBmatcher::HISTO_LENGTH = 30;
41 ORBmatcher::ORBmatcher(
float nnratio,
bool checkOri): mfNNratio(nnratio), mbCheckOrientation(checkOri)
49 const bool bFactor = th!=1.0;
51 for(
size_t iMP=0; iMP<vpMapPoints.size(); iMP++)
68 const vector<size_t> vIndices =
83 for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
85 const size_t idx = *vit;
106 bestLevel2 = bestLevel;
110 else if(dist<bestDist2)
112 bestLevel2 = F.
mvKeysUn[idx].octave;
120 if(bestLevel==bestLevel2 && bestDist>
mfNNratio*bestDist2)
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);
147 const float num = a*kp2.pt.x+b*kp2.pt.y+c;
149 const float den = a*a+b*b;
154 const float dsqr = num*num/den;
163 vpMapPointMatches = vector<MapPoint*>(F.
N,
static_cast<MapPoint*
>(NULL));
171 rotHist[i].reserve(500);
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();
180 while(KFit != KFend && Fit != Fend)
182 if(KFit->first == Fit->first)
184 const vector<unsigned int> vIndicesKF = KFit->second;
185 const vector<unsigned int> vIndicesF = Fit->second;
187 for(
size_t iKF=0; iKF<vIndicesKF.size(); iKF++)
189 const unsigned int realIdxKF = vIndicesKF[iKF];
191 MapPoint* pMP = vpMapPointsKF[realIdxKF];
205 for(
size_t iF=0; iF<vIndicesF.size(); iF++)
207 const unsigned int realIdxF = vIndicesF[iF];
209 if(vpMapPointMatches[realIdxF])
222 else if(dist<bestDist2)
230 if(static_cast<float>(bestDist1)<
mfNNratio*static_cast<float>(bestDist2))
232 vpMapPointMatches[bestIdxF]=pMP;
234 const cv::KeyPoint &kp = pKF->
mvKeysUn[realIdxKF];
238 float rot = kp.angle-F.
mvKeys[bestIdxF].angle;
241 int bin = round(rot*factor);
242 if(bin==HISTO_LENGTH)
244 assert(bin>=0 && bin<HISTO_LENGTH);
245 rotHist[bin].push_back(bestIdxF);
256 else if(KFit->first < Fit->first)
258 KFit = vFeatVecKF.lower_bound(Fit->first);
262 Fit = F.
mFeatVec.lower_bound(KFit->first);
277 if(i==ind1 || i==ind2 || i==ind3)
279 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
281 vpMapPointMatches[rotHist[i][j]]=
static_cast<MapPoint*
>(NULL);
293 const float &fx = pKF->
fx;
294 const float &fy = pKF->
fy;
295 const float &cx = pKF->
cx;
296 const float &cy = pKF->
cy;
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;
306 set<MapPoint*> spAlreadyFound(vpMatched.begin(), vpMatched.end());
307 spAlreadyFound.erase(static_cast<MapPoint*>(NULL));
312 for(
int iMP=0, iendMP=vpPoints.size(); iMP<iendMP; iMP++)
317 if(pMP->
isBad() || spAlreadyFound.count(pMP))
324 cv::Mat p3Dc = Rcw*p3Dw+tcw;
327 if(p3Dc.at<
float>(2)<0.0)
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;
335 const float u = fx*x+cx;
336 const float v = fy*y+cy;
345 cv::Mat PO = p3Dw-Ow;
346 const float dist = cv::norm(PO);
348 if(dist<minDistance || dist>maxDistance)
354 if(PO.dot(Pn)<0.5*dist)
372 for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
374 const size_t idx = *vit;
378 const int &kpLevel= pKF->
mvKeysUn[idx].octave;
380 if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
396 vpMatched[bestIdx]=pMP;
408 vnMatches12 = vector<int>(F1.
mvKeysUn.size(),-1);
412 rotHist[i].reserve(500);
415 vector<int> vMatchedDistance(F2.
mvKeysUn.size(),INT_MAX);
416 vector<int> vnMatches21(F2.
mvKeysUn.size(),-1);
418 for(
size_t i1=0, iend1=F1.
mvKeysUn.size(); i1<iend1; i1++)
421 int level1 = kp1.octave;
425 vector<size_t> vIndices2 = F2.
GetFeaturesInArea(vbPrevMatched[i1].
x,vbPrevMatched[i1].
y, windowSize,level1,level1);
427 if(vIndices2.empty())
432 int bestDist = INT_MAX;
433 int bestDist2 = INT_MAX;
436 for(vector<size_t>::iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++)
444 if(vMatchedDistance[i2]<=dist)
453 else if(dist<bestDist2)
463 if(vnMatches21[bestIdx2]>=0)
465 vnMatches12[vnMatches21[bestIdx2]]=-1;
468 vnMatches12[i1]=bestIdx2;
469 vnMatches21[bestIdx2]=i1;
470 vMatchedDistance[bestIdx2]=bestDist;
478 int bin = round(rot*factor);
479 if(bin==HISTO_LENGTH)
481 assert(bin>=0 && bin<HISTO_LENGTH);
482 rotHist[bin].push_back(i1);
499 if(i==ind1 || i==ind2 || i==ind3)
501 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
503 int idx1 = rotHist[i][j];
504 if(vnMatches12[idx1]>=0)
506 vnMatches12[idx1]=-1;
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;
524 const vector<cv::KeyPoint> &vKeysUn1 = pKF1->
mvKeysUn;
529 const vector<cv::KeyPoint> &vKeysUn2 = pKF2->
mvKeysUn;
534 vpMatches12 = vector<MapPoint*>(vpMapPoints1.size(),
static_cast<MapPoint*
>(NULL));
535 vector<bool> vbMatched2(vpMapPoints2.size(),
false);
539 rotHist[i].reserve(500);
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();
550 while(f1it != f1end && f2it != f2end)
552 if(f1it->first == f2it->first)
554 for(
size_t i1=0, iend1=f1it->second.size(); i1<iend1; i1++)
556 const size_t idx1 = f1it->second[i1];
558 MapPoint* pMP1 = vpMapPoints1[idx1];
564 const cv::Mat &d1 = Descriptors1.row(idx1);
570 for(
size_t i2=0, iend2=f2it->second.size(); i2<iend2; i2++)
572 const size_t idx2 = f2it->second[i2];
574 MapPoint* pMP2 = vpMapPoints2[idx2];
576 if(vbMatched2[idx2] || !pMP2)
582 const cv::Mat &d2 = Descriptors2.row(idx2);
592 else if(dist<bestDist2)
600 if(static_cast<float>(bestDist1)<
mfNNratio*static_cast<float>(bestDist2))
602 vpMatches12[idx1]=vpMapPoints2[bestIdx2];
603 vbMatched2[bestIdx2]=
true;
607 float rot = vKeysUn1[idx1].angle-vKeysUn2[bestIdx2].angle;
610 int bin = round(rot*factor);
611 if(bin==HISTO_LENGTH)
613 assert(bin>=0 && bin<HISTO_LENGTH);
614 rotHist[bin].push_back(idx1);
624 else if(f1it->first < f2it->first)
626 f1it = vFeatVec1.lower_bound(f2it->first);
630 f2it = vFeatVec2.lower_bound(f1it->first);
644 if(i==ind1 || i==ind2 || i==ind3)
646 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
648 vpMatches12[rotHist[i][j]]=
static_cast<MapPoint*
>(NULL);
658 vector<pair<size_t, size_t> > &vMatchedPairs,
const bool bOnlyStereo)
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;
677 vector<bool> vbMatched2(pKF2->
N,
false);
678 vector<int> vMatches12(pKF1->
N,-1);
682 rotHist[i].reserve(500);
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();
691 while(f1it!=f1end && f2it!=f2end)
693 if(f1it->first == f2it->first)
695 for(
size_t i1=0, iend1=f1it->second.size(); i1<iend1; i1++)
697 const size_t idx1 = f1it->second[i1];
705 const bool bStereo1 = pKF1->
mvuRight[idx1]>=0;
711 const cv::KeyPoint &kp1 = pKF1->
mvKeysUn[idx1];
718 for(
size_t i2=0, iend2=f2it->second.size(); i2<iend2; i2++)
720 size_t idx2 = f2it->second[i2];
725 if(vbMatched2[idx2] || pMP2)
728 const bool bStereo2 = pKF2->
mvuRight[idx2]>=0;
738 if(dist>
TH_LOW || dist>bestDist)
741 const cv::KeyPoint &kp2 = pKF2->
mvKeysUn[idx2];
743 if(!bStereo1 && !bStereo2)
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])
760 const cv::KeyPoint &kp2 = pKF2->
mvKeysUn[bestIdx2];
761 vMatches12[idx1]=bestIdx2;
766 float rot = kp1.angle-kp2.angle;
769 int bin = round(rot*factor);
770 if(bin==HISTO_LENGTH)
772 assert(bin>=0 && bin<HISTO_LENGTH);
773 rotHist[bin].push_back(idx1);
781 else if(f1it->first < f2it->first)
783 f1it = vFeatVec1.lower_bound(f2it->first);
787 f2it = vFeatVec2.lower_bound(f1it->first);
801 if(i==ind1 || i==ind2 || i==ind3)
803 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
805 vMatches12[rotHist[i][j]]=-1;
812 vMatchedPairs.clear();
813 vMatchedPairs.reserve(nmatches);
815 for(
size_t i=0, iend=vMatches12.size(); i<iend; i++)
819 vMatchedPairs.push_back(make_pair(i,vMatches12[i]));
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;
840 const int nMPs = vpMapPoints.size();
842 for(
int i=0; i<nMPs; i++)
853 cv::Mat p3Dc = Rcw*p3Dw + tcw;
856 if(p3Dc.at<
float>(2)<0.0f)
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;
863 const float u = fx*x+cx;
864 const float v = fy*y+cy;
870 const float ur = u-bf*invz;
874 cv::Mat PO = p3Dw-Ow;
875 const float dist3D = cv::norm(PO);
878 if(dist3D<minDistance || dist3D>maxDistance )
884 if(PO.dot(Pn)<0.5*dist3D)
903 for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
905 const size_t idx = *vit;
907 const cv::KeyPoint &kp = pKF->
mvKeysUn[idx];
909 const int &kpLevel= kp.octave;
911 if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
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;
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;
957 if(!pMPinKF->
isBad())
977 int ORBmatcher::Fuse(
KeyFrame *pKF, cv::Mat Scw,
const vector<MapPoint *> &vpPoints,
float th, vector<MapPoint *> &vpReplacePoint)
980 const float &fx = pKF->
fx;
981 const float &fy = pKF->
fy;
982 const float &cx = pKF->
cx;
983 const float &cy = pKF->
cy;
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;
993 const set<MapPoint*> spAlreadyFound = pKF->
GetMapPoints();
997 const int nPoints = vpPoints.size();
1000 for(
int iMP=0; iMP<nPoints; iMP++)
1005 if(pMP->
isBad() || spAlreadyFound.count(pMP))
1012 cv::Mat p3Dc = Rcw*p3Dw+tcw;
1015 if(p3Dc.at<
float>(2)<0.0f)
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;
1023 const float u = fx*x+cx;
1024 const float v = fy*y+cy;
1033 cv::Mat PO = p3Dw-Ow;
1034 const float dist3D = cv::norm(PO);
1036 if(dist3D<minDistance || dist3D>maxDistance)
1042 if(PO.dot(Pn)<0.5*dist3D)
1046 const int nPredictedLevel = pMP->
PredictScale(dist3D,pKF);
1053 if(vIndices.empty())
1060 int bestDist = INT_MAX;
1062 for(vector<size_t>::const_iterator vit=vIndices.begin(); vit!=vIndices.end(); vit++)
1064 const size_t idx = *vit;
1065 const int &kpLevel = pKF->
mvKeysUn[idx].octave;
1067 if(kpLevel<nPredictedLevel-1 || kpLevel>nPredictedLevel)
1087 if(!pMPinKF->
isBad())
1088 vpReplacePoint[iMP] = pMPinKF;
1103 const float &s12,
const cv::Mat &R12,
const cv::Mat &t12,
const float th)
1105 const float &fx = pKF1->
fx;
1106 const float &fy = pKF1->
fy;
1107 const float &cx = pKF1->
cx;
1108 const float &cy = pKF1->
cy;
1119 cv::Mat sR12 = s12*R12;
1120 cv::Mat sR21 = (1.0/s12)*R12.t();
1121 cv::Mat t21 = -sR21*t12;
1124 const int N1 = vpMapPoints1.size();
1127 const int N2 = vpMapPoints2.size();
1129 vector<bool> vbAlreadyMatched1(N1,
false);
1130 vector<bool> vbAlreadyMatched2(N2,
false);
1132 for(
int i=0; i<N1; i++)
1137 vbAlreadyMatched1[i]=
true;
1139 if(idx2>=0 && idx2<N2)
1140 vbAlreadyMatched2[idx2]=
true;
1144 vector<int> vnMatch1(N1,-1);
1145 vector<int> vnMatch2(N2,-1);
1148 for(
int i1=0; i1<N1; i1++)
1152 if(!pMP || vbAlreadyMatched1[i1])
1159 cv::Mat p3Dc1 = R1w*p3Dw + t1w;
1160 cv::Mat p3Dc2 = sR21*p3Dc1 + t21;
1163 if(p3Dc2.at<
float>(2)<0.0)
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;
1170 const float u = fx*x+cx;
1171 const float v = fy*y+cy;
1179 const float dist3D = cv::norm(p3Dc2);
1182 if(dist3D<minDistance || dist3D>maxDistance )
1186 const int nPredictedLevel = pMP->
PredictScale(dist3D,pKF2);
1193 if(vIndices.empty())
1199 int bestDist = INT_MAX;
1201 for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
1203 const size_t idx = *vit;
1205 const cv::KeyPoint &kp = pKF2->
mvKeysUn[idx];
1207 if(kp.octave<nPredictedLevel-1 || kp.octave>nPredictedLevel)
1223 vnMatch1[i1]=bestIdx;
1228 for(
int i2=0; i2<N2; i2++)
1232 if(!pMP || vbAlreadyMatched2[i2])
1239 cv::Mat p3Dc2 = R2w*p3Dw + t2w;
1240 cv::Mat p3Dc1 = sR12*p3Dc2 + t12;
1243 if(p3Dc1.at<
float>(2)<0.0)
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;
1250 const float u = fx*x+cx;
1251 const float v = fy*y+cy;
1259 const float dist3D = cv::norm(p3Dc1);
1262 if(dist3D<minDistance || dist3D>maxDistance)
1266 const int nPredictedLevel = pMP->
PredictScale(dist3D,pKF1);
1273 if(vIndices.empty())
1279 int bestDist = INT_MAX;
1281 for(vector<size_t>::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++)
1283 const size_t idx = *vit;
1285 const cv::KeyPoint &kp = pKF1->
mvKeysUn[idx];
1287 if(kp.octave<nPredictedLevel-1 || kp.octave>nPredictedLevel)
1303 vnMatch2[i2]=bestIdx;
1310 for(
int i1=0; i1<N1; i1++)
1312 int idx2 = vnMatch1[i1];
1316 int idx1 = vnMatch2[idx2];
1319 vpMatches12[i1] = vpMapPoints2[idx2];
1335 rotHist[i].reserve(500);
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);
1341 const cv::Mat twc = -Rcw.t()*tcw;
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);
1346 const cv::Mat tlc = Rlw*twc+tlw;
1348 const bool bForward = tlc.at<
float>(2)>CurrentFrame.
mb && !bMono;
1349 const bool bBackward = -tlc.at<
float>(2)>CurrentFrame.
mb && !bMono;
1351 for(
int i=0; i<LastFrame.
N; i++)
1361 cv::Mat x3Dc = Rcw*x3Dw+tcw;
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);
1370 float u = CurrentFrame.
fx*xc*invzc+CurrentFrame.
cx;
1371 float v = CurrentFrame.
fy*yc*invzc+CurrentFrame.
cy;
1373 if(u<CurrentFrame.mnMinX || u>CurrentFrame.
mnMaxX)
1375 if(v<CurrentFrame.mnMinY || v>CurrentFrame.
mnMaxY)
1378 int nLastOctave = LastFrame.
mvKeys[i].octave;
1383 vector<size_t> vIndices2;
1390 vIndices2 = CurrentFrame.
GetFeaturesInArea(u,v, radius, nLastOctave-1, nLastOctave+1);
1392 if(vIndices2.empty())
1400 for(vector<size_t>::const_iterator vit=vIndices2.begin(), vend=vIndices2.end(); vit!=vend; vit++)
1402 const size_t i2 = *vit;
1409 const float ur = u - CurrentFrame.
mbf*invzc;
1410 const float er = fabs(ur - CurrentFrame.
mvuRight[i2]);
1433 float rot = LastFrame.
mvKeysUn[i].angle-CurrentFrame.
mvKeysUn[bestIdx2].angle;
1436 int bin = round(rot*factor);
1437 if(bin==HISTO_LENGTH)
1439 assert(bin>=0 && bin<HISTO_LENGTH);
1440 rotHist[bin].push_back(bestIdx2);
1458 if(i!=ind1 && i!=ind2 && i!=ind3)
1460 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
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;
1483 rotHist[i].reserve(500);
1488 for(
size_t i=0, iend=vpMPs.size(); i<iend; i++)
1494 if(!pMP->
isBad() && !sAlreadyFound.count(pMP))
1498 cv::Mat x3Dc = Rcw*x3Dw+tcw;
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);
1504 const float u = CurrentFrame.
fx*xc*invzc+CurrentFrame.
cx;
1505 const float v = CurrentFrame.
fy*yc*invzc+CurrentFrame.
cy;
1507 if(u<CurrentFrame.mnMinX || u>CurrentFrame.
mnMaxX)
1509 if(v<CurrentFrame.mnMinY || v>CurrentFrame.
mnMaxY)
1513 cv::Mat PO = x3Dw-Ow;
1514 float dist3D = cv::norm(PO);
1520 if(dist3D<minDistance || dist3D>maxDistance)
1523 int nPredictedLevel = pMP->
PredictScale(dist3D,&CurrentFrame);
1526 const float radius = th*CurrentFrame.
mvScaleFactors[nPredictedLevel];
1528 const vector<size_t> vIndices2 = CurrentFrame.
GetFeaturesInArea(u, v, radius, nPredictedLevel-1, nPredictedLevel+1);
1530 if(vIndices2.empty())
1538 for(vector<size_t>::const_iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++)
1540 const size_t i2 = *vit;
1555 if(bestDist<=ORBdist)
1565 int bin = round(rot*factor);
1566 if(bin==HISTO_LENGTH)
1568 assert(bin>=0 && bin<HISTO_LENGTH);
1569 rotHist[bin].push_back(bestIdx2);
1587 if(i!=ind1 && i!=ind2 && i!=ind3)
1589 for(
size_t j=0, jend=rotHist[i].size(); j<jend; j++)
1607 for(
int i=0; i<L; i++)
1609 const int s = histo[i].size();
1633 if(max2<0.1
f*(
float)max1)
1638 else if(max3<0.1
f*(
float)max1)
1649 const int *pa = a.ptr<int32_t>();
1650 const int *pb = b.ptr<int32_t>();
1654 for(
int i=0; i<8; i++, pa++, pb++)
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;
float GetMinDistanceInvariance()
std::vector< MapPoint * > mvpMapPoints
const std::vector< cv::KeyPoint > mvKeysUn
cv::Mat GetCameraCenter()
const std::vector< float > mvScaleFactors
int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector< MapPoint * > &vpMapPointMatches)
void AddMapPoint(MapPoint *pMP, const size_t &idx)
int SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th)
const std::vector< float > mvLevelSigma2
int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
std::vector< MapPoint * > GetMapPointMatches()
std::vector< bool > mvbOutlier
void AddObservation(KeyFrame *pKF, size_t idx)
std::vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r) const
bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF)
TFSIMD_FORCE_INLINE const tfScalar & y() const
float RadiusByViewingCos(const float &viewCos)
std::vector< cv::KeyPoint > mvKeysUn
DBoW2::FeatureVector mFeatVec
const std::vector< float > mvInvLevelSigma2
std::vector< float > mvuRight
void Replace(MapPoint *pMP)
bool IsInImage(const float &x, const float &y) const
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
TFSIMD_FORCE_INLINE const tfScalar & x() const
int SearchByProjection(Frame &F, const std::vector< MapPoint * > &vpMapPoints, const float th=3)
float GetMaxDistanceInvariance()
std::vector< cv::KeyPoint > mvKeys
vector< float > mvScaleFactors
MapPoint * GetMapPoint(const size_t &idx)
Vector of nodes with indexes of local features.
int SearchForInitialization(Frame &F1, Frame &F2, std::vector< cv::Point2f > &vbPrevMatched, std::vector< int > &vnMatches12, int windowSize=10)
static const int HISTO_LENGTH
DBoW2::FeatureVector mFeatVec
const std::vector< float > mvuRight
int GetIndexInKeyFrame(KeyFrame *pKF)
std::set< MapPoint * > GetMapPoints()
void ComputeThreeMaxima(std::vector< int > *histo, const int L, int &ind1, int &ind2, int &ind3)
const cv::Mat mDescriptors
bool IsInKeyFrame(KeyFrame *pKF)
int PredictScale(const float ¤tDist, KeyFrame *pKF)
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)