57 #include <opencv2/core/core.hpp> 58 #include <opencv2/highgui/highgui.hpp> 59 #include <opencv2/features2d/features2d.hpp> 60 #include <opencv2/imgproc/imgproc.hpp> 77 static float IC_Angle(
const Mat& image, Point2f pt,
const vector<int> & u_max)
79 int m_01 = 0, m_10 = 0;
81 const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));
85 m_10 += u * center[u];
88 int step = (int)image.step1();
94 for (
int u = -d; u <= d; ++u)
96 int val_plus = center[u + v*step], val_minus = center[u - v*step];
97 v_sum += (val_plus - val_minus);
98 m_10 += u * (val_plus + val_minus);
103 return fastAtan2((
float)m_01, (
float)m_10);
109 const Mat& img,
const Point* pattern,
112 float angle = (float)kpt.angle*factorPI;
113 float a = (
float)cos(angle), b = (float)sin(angle);
115 const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
116 const int step = (int)img.step;
119 center[cvRound(pattern[idx].
x*b + pattern[idx].
y*a)*step + \
120 cvRound(pattern[idx].
x*a - pattern[idx].
y*b)]
123 for (
int i = 0; i < 32; ++i, pattern += 16)
129 val |= (t0 < t1) << 1;
131 val |= (t0 < t1) << 2;
133 val |= (t0 < t1) << 3;
135 val |= (t0 < t1) << 4;
137 val |= (t0 < t1) << 5;
139 val |= (t0 < t1) << 6;
141 val |= (t0 < t1) << 7;
143 desc[i] = (uchar)val;
410 ORBextractor::ORBextractor(
int _nfeatures,
float _scaleFactor,
int _nlevels,
411 int _iniThFAST,
int _minThFAST):
412 nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
413 iniThFAST(_iniThFAST), minThFAST(_minThFAST)
437 float nDesiredFeaturesPerScale =
nfeatures*(1 - factor)/(1 - (
float)pow((
double)factor, (
double)nlevels));
440 for(
int level = 0; level < nlevels-1; level++ )
444 nDesiredFeaturesPerScale *= factor;
448 const int npoints = 512;
449 const Point* pattern0 = (
const Point*)bit_pattern_31_;
450 std::copy(pattern0, pattern0 + npoints, std::back_inserter(
pattern));
454 umax.resize(HALF_PATCH_SIZE + 1);
456 int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.
f) / 2 + 1);
457 int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.
f) / 2);
459 for (v = 0; v <= vmax; ++v)
460 umax[v] = cvRound(sqrt(hp2 - v * v));
463 for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
474 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
475 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
477 keypoint->angle =
IC_Angle(image, keypoint->pt, umax);
483 const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
484 const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);
488 n1.
UR = cv::Point2i(UL.x+halfX,UL.y);
489 n1.
BL = cv::Point2i(UL.x,UL.y+halfY);
490 n1.
BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
491 n1.
vKeys.reserve(vKeys.size());
496 n2.
BR = cv::Point2i(UR.x,UL.y+halfY);
497 n2.
vKeys.reserve(vKeys.size());
502 n3.
BR = cv::Point2i(n1.
BR.x,BL.y);
503 n3.
vKeys.reserve(vKeys.size());
509 n4.
vKeys.reserve(vKeys.size());
512 for(
size_t i=0;i<vKeys.size();i++)
514 const cv::KeyPoint &kp = vKeys[i];
518 n1.
vKeys.push_back(kp);
520 n3.
vKeys.push_back(kp);
522 else if(kp.pt.y<n1.
BR.y)
523 n2.
vKeys.push_back(kp);
525 n4.
vKeys.push_back(kp);
528 if(n1.
vKeys.size()==1)
530 if(n2.
vKeys.size()==1)
532 if(n3.
vKeys.size()==1)
534 if(n4.
vKeys.size()==1)
540 const int &maxX,
const int &minY,
const int &maxY,
const int &N,
const int &level)
543 const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));
545 const float hX =
static_cast<float>(maxX-minX)/nIni;
547 list<ExtractorNode> lNodes;
549 vector<ExtractorNode*> vpIniNodes;
550 vpIniNodes.resize(nIni);
552 for(
int i=0; i<nIni; i++)
555 ni.
UL = cv::Point2i(hX*static_cast<float>(i),0);
556 ni.
UR = cv::Point2i(hX*static_cast<float>(i+1),0);
557 ni.
BL = cv::Point2i(ni.
UL.x,maxY-minY);
558 ni.
BR = cv::Point2i(ni.
UR.x,maxY-minY);
559 ni.
vKeys.reserve(vToDistributeKeys.size());
561 lNodes.push_back(ni);
562 vpIniNodes[i] = &lNodes.back();
566 for(
size_t i=0;i<vToDistributeKeys.size();i++)
568 const cv::KeyPoint &kp = vToDistributeKeys[i];
569 vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
572 list<ExtractorNode>::iterator lit = lNodes.begin();
574 while(lit!=lNodes.end())
576 if(lit->vKeys.size()==1)
581 else if(lit->vKeys.empty())
582 lit = lNodes.erase(lit);
587 bool bFinish =
false;
591 vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
592 vSizeAndPointerToNode.reserve(lNodes.size()*4);
598 int prevSize = lNodes.size();
600 lit = lNodes.begin();
604 vSizeAndPointerToNode.clear();
606 while(lit!=lNodes.end())
621 if(n1.
vKeys.size()>0)
623 lNodes.push_front(n1);
624 if(n1.
vKeys.size()>1)
627 vSizeAndPointerToNode.push_back(make_pair(n1.
vKeys.size(),&lNodes.front()));
628 lNodes.front().lit = lNodes.begin();
631 if(n2.
vKeys.size()>0)
633 lNodes.push_front(n2);
634 if(n2.
vKeys.size()>1)
637 vSizeAndPointerToNode.push_back(make_pair(n2.
vKeys.size(),&lNodes.front()));
638 lNodes.front().lit = lNodes.begin();
641 if(n3.
vKeys.size()>0)
643 lNodes.push_front(n3);
644 if(n3.
vKeys.size()>1)
647 vSizeAndPointerToNode.push_back(make_pair(n3.
vKeys.size(),&lNodes.front()));
648 lNodes.front().lit = lNodes.begin();
651 if(n4.
vKeys.size()>0)
653 lNodes.push_front(n4);
654 if(n4.
vKeys.size()>1)
657 vSizeAndPointerToNode.push_back(make_pair(n4.
vKeys.size(),&lNodes.front()));
658 lNodes.front().lit = lNodes.begin();
662 lit=lNodes.erase(lit);
669 if((
int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
673 else if(((
int)lNodes.size()+nToExpand*3)>N)
679 prevSize = lNodes.size();
681 vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
682 vSizeAndPointerToNode.clear();
684 sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
685 for(
int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
688 vPrevSizeAndPointerToNode[j].second->
DivideNode(n1,n2,n3,n4);
691 if(n1.
vKeys.size()>0)
693 lNodes.push_front(n1);
694 if(n1.
vKeys.size()>1)
696 vSizeAndPointerToNode.push_back(make_pair(n1.
vKeys.size(),&lNodes.front()));
697 lNodes.front().lit = lNodes.begin();
700 if(n2.
vKeys.size()>0)
702 lNodes.push_front(n2);
703 if(n2.
vKeys.size()>1)
705 vSizeAndPointerToNode.push_back(make_pair(n2.
vKeys.size(),&lNodes.front()));
706 lNodes.front().lit = lNodes.begin();
709 if(n3.
vKeys.size()>0)
711 lNodes.push_front(n3);
712 if(n3.
vKeys.size()>1)
714 vSizeAndPointerToNode.push_back(make_pair(n3.
vKeys.size(),&lNodes.front()));
715 lNodes.front().lit = lNodes.begin();
718 if(n4.
vKeys.size()>0)
720 lNodes.push_front(n4);
721 if(n4.
vKeys.size()>1)
723 vSizeAndPointerToNode.push_back(make_pair(n4.
vKeys.size(),&lNodes.front()));
724 lNodes.front().lit = lNodes.begin();
728 lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);
730 if((
int)lNodes.size()>=N)
734 if((
int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
742 vector<cv::KeyPoint> vResultKeys;
744 for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
746 vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
747 cv::KeyPoint* pKP = &vNodeKeys[0];
748 float maxResponse = pKP->response;
750 for(
size_t k=1;k<vNodeKeys.size();k++)
752 if(vNodeKeys[k].response>maxResponse)
755 maxResponse = vNodeKeys[k].response;
759 vResultKeys.push_back(*pKP);
771 for (
int level = 0; level <
nlevels; ++level)
773 const int minBorderX = EDGE_THRESHOLD-3;
774 const int minBorderY = minBorderX;
775 const int maxBorderX =
mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
776 const int maxBorderY =
mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
778 vector<cv::KeyPoint> vToDistributeKeys;
781 const float width = (maxBorderX-minBorderX);
782 const float height = (maxBorderY-minBorderY);
784 const int nCols = width/W;
785 const int nRows = height/W;
786 const int wCell = ceil(width/nCols);
787 const int hCell = ceil(height/nRows);
789 for(
int i=0; i<nRows; i++)
791 const float iniY =minBorderY+i*hCell;
792 float maxY = iniY+hCell+6;
794 if(iniY>=maxBorderY-3)
799 for(
int j=0; j<nCols; j++)
801 const float iniX =minBorderX+j*wCell;
802 float maxX = iniX+wCell+6;
803 if(iniX>=maxBorderX-6)
808 vector<cv::KeyPoint> vKeysCell;
809 FAST(
mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
812 if(vKeysCell.empty())
814 FAST(
mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
818 if(!vKeysCell.empty())
820 for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
822 (*vit).pt.x+=j*wCell;
823 (*vit).pt.y+=i*hCell;
824 vToDistributeKeys.push_back(*vit);
831 vector<KeyPoint> & keypoints = allKeypoints[level];
840 const int nkps = keypoints.size();
841 for(
int i=0; i<nkps ; i++)
843 keypoints[i].pt.x+=minBorderX;
844 keypoints[i].pt.y+=minBorderY;
845 keypoints[i].octave=level;
846 keypoints[i].size = scaledPatchSize;
851 for (
int level = 0; level <
nlevels; ++level)
861 for (
int level = 0; level <
nlevels; ++level)
865 const int levelCols = sqrt((
float)nDesiredFeatures/(5*imageRatio));
866 const int levelRows = imageRatio*levelCols;
869 const int minBorderY = minBorderX;
873 const int W = maxBorderX - minBorderX;
874 const int H = maxBorderY - minBorderY;
875 const int cellW = ceil((
float)W/levelCols);
876 const int cellH = ceil((
float)H/levelRows);
878 const int nCells = levelRows*levelCols;
879 const int nfeaturesCell = ceil((
float)nDesiredFeatures/nCells);
881 vector<vector<vector<KeyPoint> > > cellKeyPoints(levelRows, vector<vector<KeyPoint> >(levelCols));
883 vector<vector<int> > nToRetain(levelRows,vector<int>(levelCols,0));
884 vector<vector<int> > nTotal(levelRows,vector<int>(levelCols,0));
885 vector<vector<bool> > bNoMore(levelRows,vector<bool>(levelCols,
false));
886 vector<int> iniXCol(levelCols);
887 vector<int> iniYRow(levelRows);
889 int nToDistribute = 0;
892 float hY = cellH + 6;
894 for(
int i=0; i<levelRows; i++)
896 const float iniY = minBorderY + i*cellH - 3;
901 hY = maxBorderY+3-iniY;
906 float hX = cellW + 6;
908 for(
int j=0; j<levelCols; j++)
914 iniX = minBorderX + j*cellW - 3;
925 hX = maxBorderX+3-iniX;
931 Mat cellImage =
mvImagePyramid[level].rowRange(iniY,iniY+hY).colRange(iniX,iniX+hX);
933 cellKeyPoints[i][j].reserve(nfeaturesCell*5);
935 FAST(cellImage,cellKeyPoints[i][j],
iniThFAST,
true);
937 if(cellKeyPoints[i][j].size()<=3)
939 cellKeyPoints[i][j].clear();
941 FAST(cellImage,cellKeyPoints[i][j],
minThFAST,
true);
945 const int nKeys = cellKeyPoints[i][j].size();
946 nTotal[i][j] = nKeys;
948 if(nKeys>nfeaturesCell)
950 nToRetain[i][j] = nfeaturesCell;
951 bNoMore[i][j] =
false;
955 nToRetain[i][j] = nKeys;
956 nToDistribute += nfeaturesCell-nKeys;
957 bNoMore[i][j] =
true;
967 while(nToDistribute>0 && nNoMore<nCells)
969 int nNewFeaturesCell = nfeaturesCell + ceil((
float)nToDistribute/(nCells-nNoMore));
972 for(
int i=0; i<levelRows; i++)
974 for(
int j=0; j<levelCols; j++)
978 if(nTotal[i][j]>nNewFeaturesCell)
980 nToRetain[i][j] = nNewFeaturesCell;
981 bNoMore[i][j] =
false;
985 nToRetain[i][j] = nTotal[i][j];
986 nToDistribute += nNewFeaturesCell-nTotal[i][j];
987 bNoMore[i][j] =
true;
995 vector<KeyPoint> & keypoints = allKeypoints[level];
996 keypoints.reserve(nDesiredFeatures*2);
1001 for(
int i=0; i<levelRows; i++)
1003 for(
int j=0; j<levelCols; j++)
1005 vector<KeyPoint> &keysCell = cellKeyPoints[i][j];
1006 KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]);
1007 if((
int)keysCell.size()>nToRetain[i][j])
1008 keysCell.resize(nToRetain[i][j]);
1011 for(
size_t k=0, kend=keysCell.size(); k<kend; k++)
1013 keysCell[k].pt.x+=iniXCol[j];
1014 keysCell[k].pt.y+=iniYRow[i];
1015 keysCell[k].octave=level;
1016 keysCell[k].size = scaledPatchSize;
1017 keypoints.push_back(keysCell[k]);
1022 if((
int)keypoints.size()>nDesiredFeatures)
1024 KeyPointsFilter::retainBest(keypoints,nDesiredFeatures);
1025 keypoints.resize(nDesiredFeatures);
1030 for (
int level = 0; level <
nlevels; ++level)
1037 descriptors = Mat::zeros((
int)keypoints.size(), 32, CV_8UC1);
1039 for (
size_t i = 0; i < keypoints.size(); i++)
1044 OutputArray _descriptors)
1049 Mat image = _image.getMat();
1050 assert(image.type() == CV_8UC1 );
1055 vector < vector<KeyPoint> > allKeypoints;
1062 for (
int level = 0; level <
nlevels; ++level)
1063 nkeypoints += (
int)allKeypoints[level].size();
1064 if( nkeypoints == 0 )
1065 _descriptors.release();
1068 _descriptors.create(nkeypoints, 32, CV_8U);
1069 descriptors = _descriptors.getMat();
1073 _keypoints.reserve(nkeypoints);
1076 for (
int level = 0; level <
nlevels; ++level)
1078 vector<KeyPoint>& keypoints = allKeypoints[level];
1079 int nkeypointsLevel = (int)keypoints.size();
1081 if(nkeypointsLevel==0)
1086 GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
1089 Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
1092 offset += nkeypointsLevel;
1098 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
1099 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
1100 keypoint->pt *= scale;
1103 _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
1109 for (
int level = 0; level <
nlevels; ++level)
1112 Size sz(cvRound((
float)image.cols*scale), cvRound((
float)image.rows*scale));
1113 Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
1114 Mat temp(wholeSize, image.type()), masktemp;
1115 mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
1120 resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
1122 copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1123 BORDER_REFLECT_101+BORDER_ISOLATED);
1127 copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1128 BORDER_REFLECT_101);
static void computeOrbDescriptor(const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
const int HALF_PATCH_SIZE
TFSIMD_FORCE_INLINE const tfScalar & x() const
static void computeDescriptors(const Mat &image, vector< KeyPoint > &keypoints, Mat &descriptors, const vector< Point > &pattern)
static int bit_pattern_31_[256 *4]
static void computeOrientation(const Mat &image, vector< KeyPoint > &keypoints, const vector< int > &umax)
static float IC_Angle(const Mat &image, Point2f pt, const vector< int > &u_max)