00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include "opencv2/features2d/features2d.hpp"
00038 #include "opencv2/imgproc/imgproc.hpp"
00039 #include "opencv2/imgproc/imgproc_c.h"
00040 #include "opencv2/core/internal.hpp"
00041 #include "aorb.h"
00042 #include <iterator>
00043
00045
00046 namespace cv
00047 {
00048
00049 const float HARRIS_K = 0.04f;
00050 const int DESCRIPTOR_SIZE = 32;
00051
00056 static void
00057 HarrisResponses(const Mat& img, vector<KeyPoint>& pts, int blockSize, float harris_k)
00058 {
00059 CV_Assert( img.type() == CV_8UC1 && blockSize*blockSize <= 2048 );
00060
00061 size_t ptidx, ptsize = pts.size();
00062
00063 const uchar* ptr00 = img.ptr<uchar>();
00064 int step = (int)(img.step/img.elemSize1());
00065 int r = blockSize/2;
00066
00067 float scale = (1 << 2) * blockSize * 255.0f;
00068 scale = 1.0f / scale;
00069 float scale_sq_sq = scale * scale * scale * scale;
00070
00071 AutoBuffer<int> ofsbuf(blockSize*blockSize);
00072 int* ofs = ofsbuf;
00073 for( int i = 0; i < blockSize; i++ )
00074 for( int j = 0; j < blockSize; j++ )
00075 ofs[i*blockSize + j] = (int)(i*step + j);
00076
00077 for( ptidx = 0; ptidx < ptsize; ptidx++ )
00078 {
00079 int x0 = cvRound(pts[ptidx].pt.x - r);
00080 int y0 = cvRound(pts[ptidx].pt.y - r);
00081
00082 const uchar* ptr0 = ptr00 + y0*step + x0;
00083 int a = 0, b = 0, c = 0;
00084
00085 for( int k = 0; k < blockSize*blockSize; k++ )
00086 {
00087 const uchar* ptr = ptr0 + ofs[k];
00088 int Ix = (ptr[1] - ptr[-1])*2 + (ptr[-step+1] - ptr[-step-1]) + (ptr[step+1] - ptr[step-1]);
00089 int Iy = (ptr[step] - ptr[-step])*2 + (ptr[step-1] - ptr[-step-1]) + (ptr[step+1] - ptr[-step+1]);
00090 a += Ix*Ix;
00091 b += Iy*Iy;
00092 c += Ix*Iy;
00093 }
00094 pts[ptidx].response = ((float)a * b - (float)c * c -
00095 harris_k * ((float)a + b) * ((float)a + b))*scale_sq_sq;
00096 }
00097 }
00098
00100
00101 static float IC_Angle(const Mat& image, const int half_k, Point2f pt,
00102 const vector<int> & u_max)
00103 {
00104 int m_01 = 0, m_10 = 0;
00105
00106 const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));
00107
00108
00109 for (int u = -half_k; u <= half_k; ++u)
00110 m_10 += u * center[u];
00111
00112
00113 int step = (int)image.step1();
00114 for (int v = 1; v <= half_k; ++v)
00115 {
00116
00117 int v_sum = 0;
00118 int d = u_max[v];
00119 for (int u = -d; u <= d; ++u)
00120 {
00121 int val_plus = center[u + v*step], val_minus = center[u - v*step];
00122 v_sum += (val_plus - val_minus);
00123 m_10 += u * (val_plus + val_minus);
00124 }
00125 m_01 += v * v_sum;
00126 }
00127
00128 return fastAtan2((float)m_01, (float)m_10);
00129 }
00130
00132
00133 static void computeOrbDescriptor(const KeyPoint& kpt,
00134 const Mat& img, const Point* pattern,
00135 uchar* desc, int dsize, int WTA_K)
00136 {
00137 float angle = kpt.angle;
00138
00139 angle *= (float)(CV_PI/180.f);
00140 float a = (float)cos(angle), b = (float)sin(angle);
00141
00142 const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
00143 int step = (int)img.step;
00144
00145 #if 1
00146 #define GET_VALUE(idx) \
00147 center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
00148 cvRound(pattern[idx].x*a - pattern[idx].y*b)]
00149 #else
00150 float x, y;
00151 int ix, iy;
00152 #define GET_VALUE(idx) \
00153 (x = pattern[idx].x*a - pattern[idx].y*b, \
00154 y = pattern[idx].x*b + pattern[idx].y*a, \
00155 ix = cvFloor(x), iy = cvFloor(y), \
00156 x -= ix, y -= iy, \
00157 cvRound(center[iy*step + ix]*(1-x)*(1-y) + center[(iy+1)*step + ix]*(1-x)*y + \
00158 center[iy*step + ix+1]*x*(1-y) + center[(iy+1)*step + ix+1]*x*y))
00159 #endif
00160
00161 if( WTA_K == 2 )
00162 {
00163 for (int i = 0; i < dsize; ++i, pattern += 16)
00164 {
00165 int t0, t1, val;
00166 t0 = GET_VALUE(0); t1 = GET_VALUE(1);
00167 val = t0 < t1;
00168 t0 = GET_VALUE(2); t1 = GET_VALUE(3);
00169 val |= (t0 < t1) << 1;
00170 t0 = GET_VALUE(4); t1 = GET_VALUE(5);
00171 val |= (t0 < t1) << 2;
00172 t0 = GET_VALUE(6); t1 = GET_VALUE(7);
00173 val |= (t0 < t1) << 3;
00174 t0 = GET_VALUE(8); t1 = GET_VALUE(9);
00175 val |= (t0 < t1) << 4;
00176 t0 = GET_VALUE(10); t1 = GET_VALUE(11);
00177 val |= (t0 < t1) << 5;
00178 t0 = GET_VALUE(12); t1 = GET_VALUE(13);
00179 val |= (t0 < t1) << 6;
00180 t0 = GET_VALUE(14); t1 = GET_VALUE(15);
00181 val |= (t0 < t1) << 7;
00182
00183 desc[i] = (uchar)val;
00184 }
00185 }
00186 else if( WTA_K == 3 )
00187 {
00188 for (int i = 0; i < dsize; ++i, pattern += 12)
00189 {
00190 int t0, t1, t2, val;
00191 t0 = GET_VALUE(0); t1 = GET_VALUE(1); t2 = GET_VALUE(2);
00192 val = t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0);
00193
00194 t0 = GET_VALUE(3); t1 = GET_VALUE(4); t2 = GET_VALUE(5);
00195 val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 2;
00196
00197 t0 = GET_VALUE(6); t1 = GET_VALUE(7); t2 = GET_VALUE(8);
00198 val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 4;
00199
00200 t0 = GET_VALUE(9); t1 = GET_VALUE(10); t2 = GET_VALUE(11);
00201 val |= (t2 > t1 ? (t2 > t0 ? 2 : 0) : (t1 > t0)) << 6;
00202
00203 desc[i] = (uchar)val;
00204 }
00205 }
00206 else if( WTA_K == 4 )
00207 {
00208 for (int i = 0; i < dsize; ++i, pattern += 16)
00209 {
00210 int t0, t1, t2, t3, u, v, k, val;
00211 t0 = GET_VALUE(0); t1 = GET_VALUE(1);
00212 t2 = GET_VALUE(2); t3 = GET_VALUE(3);
00213 u = 0, v = 2;
00214 if( t1 > t0 ) t0 = t1, u = 1;
00215 if( t3 > t2 ) t2 = t3, v = 3;
00216 k = t0 > t2 ? u : v;
00217 val = k;
00218
00219 t0 = GET_VALUE(4); t1 = GET_VALUE(5);
00220 t2 = GET_VALUE(6); t3 = GET_VALUE(7);
00221 u = 0, v = 2;
00222 if( t1 > t0 ) t0 = t1, u = 1;
00223 if( t3 > t2 ) t2 = t3, v = 3;
00224 k = t0 > t2 ? u : v;
00225 val |= k << 2;
00226
00227 t0 = GET_VALUE(8); t1 = GET_VALUE(9);
00228 t2 = GET_VALUE(10); t3 = GET_VALUE(11);
00229 u = 0, v = 2;
00230 if( t1 > t0 ) t0 = t1, u = 1;
00231 if( t3 > t2 ) t2 = t3, v = 3;
00232 k = t0 > t2 ? u : v;
00233 val |= k << 4;
00234
00235 t0 = GET_VALUE(12); t1 = GET_VALUE(13);
00236 t2 = GET_VALUE(14); t3 = GET_VALUE(15);
00237 u = 0, v = 2;
00238 if( t1 > t0 ) t0 = t1, u = 1;
00239 if( t3 > t2 ) t2 = t3, v = 3;
00240 k = t0 > t2 ? u : v;
00241 val |= k << 6;
00242
00243 desc[i] = (uchar)val;
00244 }
00245 }
00246 else
00247 CV_Error( CV_StsBadSize, "Wrong WTA_K. It can be only 2, 3 or 4." );
00248
00249 #undef GET_VALUE
00250 }
00251
00252
00253 static void initializeOrbPattern( const Point* pattern0, vector<Point>& pattern, int ntuples, int tupleSize, int poolSize )
00254 {
00255 RNG rng(0x12345678);
00256 int i, k, k1;
00257 pattern.resize(ntuples*tupleSize);
00258
00259 for( i = 0; i < ntuples; i++ )
00260 {
00261 for( k = 0; k < tupleSize; k++ )
00262 {
00263 for(;;)
00264 {
00265 int idx = rng.uniform(0, poolSize);
00266 Point pt = pattern0[idx];
00267 for( k1 = 0; k1 < k; k1++ )
00268 if( pattern[tupleSize*i + k1] == pt )
00269 break;
00270 if( k1 == k )
00271 {
00272 pattern[tupleSize*i + k] = pt;
00273 break;
00274 }
00275 }
00276 }
00277 }
00278 }
00279
00280 static int bit_pattern_31_[256*4] =
00281 {
00282 8,-3, 9,5,
00283 4,2, 7,-12,
00284 -11,9, -8,2,
00285 7,-12, 12,-13,
00286 2,-13, 2,12,
00287 1,-7, 1,6,
00288 -2,-10, -2,-4,
00289 -13,-13, -11,-8,
00290 -13,-3, -12,-9,
00291 10,4, 11,9,
00292 -13,-8, -8,-9,
00293 -11,7, -9,12,
00294 7,7, 12,6,
00295 -4,-5, -3,0,
00296 -13,2, -12,-3,
00297 -9,0, -7,5,
00298 12,-6, 12,-1,
00299 -3,6, -2,12,
00300 -6,-13, -4,-8,
00301 11,-13, 12,-8,
00302 4,7, 5,1,
00303 5,-3, 10,-3,
00304 3,-7, 6,12,
00305 -8,-7, -6,-2,
00306 -2,11, -1,-10,
00307 -13,12, -8,10,
00308 -7,3, -5,-3,
00309 -4,2, -3,7,
00310 -10,-12, -6,11,
00311 5,-12, 6,-7,
00312 5,-6, 7,-1,
00313 1,0, 4,-5,
00314 9,11, 11,-13,
00315 4,7, 4,12,
00316 2,-1, 4,4,
00317 -4,-12, -2,7,
00318 -8,-5, -7,-10,
00319 4,11, 9,12,
00320 0,-8, 1,-13,
00321 -13,-2, -8,2,
00322 -3,-2, -2,3,
00323 -6,9, -4,-9,
00324 8,12, 10,7,
00325 0,9, 1,3,
00326 7,-5, 11,-10,
00327 -13,-6, -11,0,
00328 10,7, 12,1,
00329 -6,-3, -6,12,
00330 10,-9, 12,-4,
00331 -13,8, -8,-12,
00332 -13,0, -8,-4,
00333 3,3, 7,8,
00334 5,7, 10,-7,
00335 -1,7, 1,-12,
00336 3,-10, 5,6,
00337 2,-4, 3,-10,
00338 -13,0, -13,5,
00339 -13,-7, -12,12,
00340 -13,3, -11,8,
00341 -7,12, -4,7,
00342 6,-10, 12,8,
00343 -9,-1, -7,-6,
00344 -2,-5, 0,12,
00345 -12,5, -7,5,
00346 3,-10, 8,-13,
00347 -7,-7, -4,5,
00348 -3,-2, -1,-7,
00349 2,9, 5,-11,
00350 -11,-13, -5,-13,
00351 -1,6, 0,-1,
00352 5,-3, 5,2,
00353 -4,-13, -4,12,
00354 -9,-6, -9,6,
00355 -12,-10, -8,-4,
00356 10,2, 12,-3,
00357 7,12, 12,12,
00358 -7,-13, -6,5,
00359 -4,9, -3,4,
00360 7,-1, 12,2,
00361 -7,6, -5,1,
00362 -13,11, -12,5,
00363 -3,7, -2,-6,
00364 7,-8, 12,-7,
00365 -13,-7, -11,-12,
00366 1,-3, 12,12,
00367 2,-6, 3,0,
00368 -4,3, -2,-13,
00369 -1,-13, 1,9,
00370 7,1, 8,-6,
00371 1,-1, 3,12,
00372 9,1, 12,6,
00373 -1,-9, -1,3,
00374 -13,-13, -10,5,
00375 7,7, 10,12,
00376 12,-5, 12,9,
00377 6,3, 7,11,
00378 5,-13, 6,10,
00379 2,-12, 2,3,
00380 3,8, 4,-6,
00381 2,6, 12,-13,
00382 9,-12, 10,3,
00383 -8,4, -7,9,
00384 -11,12, -4,-6,
00385 1,12, 2,-8,
00386 6,-9, 7,-4,
00387 2,3, 3,-2,
00388 6,3, 11,0,
00389 3,-3, 8,-8,
00390 7,8, 9,3,
00391 -11,-5, -6,-4,
00392 -10,11, -5,10,
00393 -5,-8, -3,12,
00394 -10,5, -9,0,
00395 8,-1, 12,-6,
00396 4,-6, 6,-11,
00397 -10,12, -8,7,
00398 4,-2, 6,7,
00399 -2,0, -2,12,
00400 -5,-8, -5,2,
00401 7,-6, 10,12,
00402 -9,-13, -8,-8,
00403 -5,-13, -5,-2,
00404 8,-8, 9,-13,
00405 -9,-11, -9,0,
00406 1,-8, 1,-2,
00407 7,-4, 9,1,
00408 -2,1, -1,-4,
00409 11,-6, 12,-11,
00410 -12,-9, -6,4,
00411 3,7, 7,12,
00412 5,5, 10,8,
00413 0,-4, 2,8,
00414 -9,12, -5,-13,
00415 0,7, 2,12,
00416 -1,2, 1,7,
00417 5,11, 7,-9,
00418 3,5, 6,-8,
00419 -13,-4, -8,9,
00420 -5,9, -3,-3,
00421 -4,-7, -3,-12,
00422 6,5, 8,0,
00423 -7,6, -6,12,
00424 -13,6, -5,-2,
00425 1,-10, 3,10,
00426 4,1, 8,-4,
00427 -2,-2, 2,-13,
00428 2,-12, 12,12,
00429 -2,-13, 0,-6,
00430 4,1, 9,3,
00431 -6,-10, -3,-5,
00432 -3,-13, -1,1,
00433 7,5, 12,-11,
00434 4,-2, 5,-7,
00435 -13,9, -9,-5,
00436 7,1, 8,6,
00437 7,-8, 7,6,
00438 -7,-4, -7,1,
00439 -8,11, -7,-8,
00440 -13,6, -12,-8,
00441 2,4, 3,9,
00442 10,-5, 12,3,
00443 -6,-5, -6,7,
00444 8,-3, 9,-8,
00445 2,-12, 2,8,
00446 -11,-2, -10,3,
00447 -12,-13, -7,-9,
00448 -11,0, -10,-5,
00449 5,-3, 11,8,
00450 -2,-13, -1,12,
00451 -1,-8, 0,9,
00452 -13,-11, -12,-5,
00453 -10,-2, -10,11,
00454 -3,9, -2,-13,
00455 2,-3, 3,2,
00456 -9,-13, -4,0,
00457 -4,6, -3,-10,
00458 -4,12, -2,-7,
00459 -6,-11, -4,9,
00460 6,-3, 6,11,
00461 -13,11, -5,5,
00462 11,11, 12,6,
00463 7,-5, 12,-2,
00464 -1,12, 0,7,
00465 -4,-8, -3,-2,
00466 -7,1, -6,7,
00467 -13,-12, -8,-13,
00468 -7,-2, -6,-8,
00469 -8,5, -6,-9,
00470 -5,-1, -4,5,
00471 -13,7, -8,10,
00472 1,5, 5,-13,
00473 1,0, 10,-13,
00474 9,12, 10,-1,
00475 5,-8, 10,-9,
00476 -1,11, 1,-13,
00477 -9,-3, -6,2,
00478 -1,-10, 1,12,
00479 -13,1, -8,-10,
00480 8,-11, 10,-6,
00481 2,-13, 3,-6,
00482 7,-13, 12,-9,
00483 -10,-10, -5,-7,
00484 -10,-8, -8,-13,
00485 4,-6, 8,5,
00486 3,12, 8,-13,
00487 -4,2, -3,-3,
00488 5,-13, 10,-12,
00489 4,-13, 5,-1,
00490 -9,9, -4,3,
00491 0,3, 3,-9,
00492 -12,1, -6,1,
00493 3,2, 4,-8,
00494 -10,-10, -10,9,
00495 8,-13, 12,12,
00496 -8,-12, -6,-5,
00497 2,2, 3,7,
00498 10,6, 11,-8,
00499 6,8, 8,-12,
00500 -7,10, -6,5,
00501 -3,-9, -3,9,
00502 -1,-13, -1,5,
00503 -3,-7, -3,4,
00504 -8,-2, -8,3,
00505 4,2, 12,12,
00506 2,-5, 3,11,
00507 6,-9, 11,-13,
00508 3,-1, 7,12,
00509 11,-1, 12,4,
00510 -3,0, -3,6,
00511 4,-11, 4,12,
00512 2,-4, 2,1,
00513 -10,-6, -8,1,
00514 -13,7, -11,1,
00515 -13,12, -11,-13,
00516 6,0, 11,-13,
00517 0,-1, 1,4,
00518 -13,3, -9,-2,
00519 -9,8, -6,-3,
00520 -13,-6, -8,-2,
00521 5,-9, 8,10,
00522 2,7, 3,-9,
00523 -1,-6, -1,-1,
00524 9,5, 11,-2,
00525 11,-3, 12,-8,
00526 3,0, 3,5,
00527 -1,4, 0,10,
00528 3,-6, 4,5,
00529 -13,0, -10,5,
00530 5,8, 12,11,
00531 8,9, 9,-6,
00532 7,-4, 8,-12,
00533 -10,4, -10,9,
00534 7,3, 12,4,
00535 9,-7, 10,-2,
00536 7,0, 12,-2,
00537 -1,-6, 0,-11
00538 };
00539
00540
00541 static void makeRandomPattern(int patchSize, Point* pattern, int npoints)
00542 {
00543 RNG rng(0x34985739);
00544
00545 for( int i = 0; i < npoints; i++ )
00546 {
00547 pattern[i].x = rng.uniform(-patchSize/2, patchSize/2+1);
00548 pattern[i].y = rng.uniform(-patchSize/2, patchSize/2+1);
00549 }
00550 }
00551
00552
00553 static inline float getScale(int level, int firstLevel, double scaleFactor)
00554 {
00555 return (float)std::pow(scaleFactor, (double)(level - firstLevel));
00556 }
00557
00561 AORB::AORB(int _nfeatures, float _scaleFactor, int _nlevels, int _edgeThreshold,
00562 int _firstLevel, int WTA_K, int _scoreType, int _patchSize, int _fastThreshold) :
00563 nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
00564 edgeThreshold(_edgeThreshold), firstLevel(_firstLevel), WTA_K(WTA_K),
00565 scoreType(_scoreType), patchSize(_patchSize), fastThreshold(_fastThreshold)
00566 {}
00567
00568
00569 int AORB::descriptorSize() const
00570 {
00571 return kBytes;
00572 }
00573
00574 int AORB::descriptorType() const
00575 {
00576 return CV_8U;
00577 }
00578
00584 void AORB::operator()(InputArray image, InputArray mask, vector<KeyPoint>& keypoints) const
00585 {
00586 (*this)(image, mask, keypoints, noArray(), false);
00587 }
00588
00589
00596 static void computeOrientation(const Mat& image, vector<KeyPoint>& keypoints,
00597 int halfPatchSize, const vector<int>& umax)
00598 {
00599
00600 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00601 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00602 {
00603 keypoint->angle = IC_Angle(image, halfPatchSize, keypoint->pt, umax);
00604 }
00605 }
00606
00607
00613 static void computeKeyPoints(const vector<Mat>& imagePyramid,
00614 const vector<Mat>& maskPyramid,
00615 vector<vector<KeyPoint> >& allKeypoints,
00616 int nfeatures, int firstLevel, double scaleFactor,
00617 int edgeThreshold, int patchSize, int scoreType, int fastThreshold )
00618 {
00619 int nlevels = (int)imagePyramid.size();
00620 vector<int> nfeaturesPerLevel(nlevels);
00621
00622
00623 float factor = (float)(1.0 / scaleFactor);
00624 float ndesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
00625
00626 int sumFeatures = 0;
00627 for( int level = 0; level < nlevels-1; level++ )
00628 {
00629 nfeaturesPerLevel[level] = cvRound(ndesiredFeaturesPerScale);
00630 sumFeatures += nfeaturesPerLevel[level];
00631 ndesiredFeaturesPerScale *= factor;
00632 }
00633 nfeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
00634
00635
00636
00637
00638
00639 int halfPatchSize = patchSize / 2;
00640 vector<int> umax(halfPatchSize + 1);
00641
00642 int v, v0, vmax = cvFloor(halfPatchSize * sqrt(2.f) / 2 + 1);
00643 int vmin = cvCeil(halfPatchSize * sqrt(2.f) / 2);
00644 for (v = 0; v <= vmax; ++v)
00645 umax[v] = cvRound(sqrt((double)halfPatchSize * halfPatchSize - v * v));
00646
00647
00648 for (v = halfPatchSize, v0 = 0; v >= vmin; --v)
00649 {
00650 while (umax[v0] == umax[v0 + 1])
00651 ++v0;
00652 umax[v] = v0;
00653 ++v0;
00654 }
00655
00656 allKeypoints.resize(nlevels);
00657
00658 for (int level = 0; level < nlevels; ++level)
00659 {
00660 int nfeatures = nfeaturesPerLevel[level];
00661 allKeypoints[level].reserve(nfeatures*2);
00662
00663 vector<KeyPoint> & keypoints = allKeypoints[level];
00664
00665
00666 FastFeatureDetector fd(fastThreshold, true);
00667 fd.detect(imagePyramid[level], keypoints, maskPyramid[level]);
00668
00669
00670 KeyPointsFilter::runByImageBorder(keypoints, imagePyramid[level].size(), edgeThreshold);
00671
00672 if( scoreType == AORB::HARRIS_SCORE )
00673 {
00674
00675 KeyPointsFilter::retainBest(keypoints, 2 * nfeatures);
00676
00677
00678 HarrisResponses(imagePyramid[level], keypoints, 7, HARRIS_K);
00679 }
00680
00681
00682 KeyPointsFilter::retainBest(keypoints, nfeatures);
00683
00684 float sf = getScale(level, firstLevel, scaleFactor);
00685
00686
00687 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00688 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00689 {
00690 keypoint->octave = level;
00691 keypoint->size = patchSize*sf;
00692 }
00693
00694 computeOrientation(imagePyramid[level], keypoints, halfPatchSize, umax);
00695 }
00696 }
00697
00698
00706 static void computeDescriptors(const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors,
00707 const vector<Point>& pattern, int dsize, int WTA_K)
00708 {
00709
00710 CV_Assert(image.type() == CV_8UC1);
00711
00712 descriptors = Mat::zeros((int)keypoints.size(), dsize, CV_8UC1);
00713
00714 for (size_t i = 0; i < keypoints.size(); i++)
00715 computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i), dsize, WTA_K);
00716 }
00717
00718
00727 void AORB::operator()( InputArray _image, InputArray _mask, vector<KeyPoint>& _keypoints,
00728 OutputArray _descriptors, bool useProvidedKeypoints) const
00729 {
00730 bool do_keypoints = !useProvidedKeypoints;
00731 bool do_descriptors = _descriptors.needed();
00732
00733 if( (!do_keypoints && !do_descriptors) || _image.empty() )
00734 return;
00735
00736
00737 const int HARRIS_BLOCK_SIZE = 9;
00738 int halfPatchSize = patchSize / 2;
00739 int border = std::max(edgeThreshold, std::max(halfPatchSize, HARRIS_BLOCK_SIZE/2))+1;
00740
00741 Mat image = _image.getMat(), mask = _mask.getMat();
00742 if( image.type() != CV_8UC1 )
00743 cvtColor(_image, image, CV_BGR2GRAY);
00744
00745 int nlevels = this->nlevels;
00746
00747 if( !do_keypoints )
00748 {
00749
00750
00751
00752
00753
00754
00755
00756
00757
00758 nlevels = 0;
00759 for( size_t i = 0; i < _keypoints.size(); i++ )
00760 nlevels = std::max(nlevels, std::max(_keypoints[i].octave, 0));
00761 nlevels++;
00762 }
00763
00764
00765 vector<Mat> imagePyramid(nlevels), maskPyramid(nlevels);
00766 for (int level = 0; level < nlevels; ++level)
00767 {
00768 float scale = 1/getScale(level, firstLevel, scaleFactor);
00769 Size sz(cvRound(image.cols*scale), cvRound(image.rows*scale));
00770 Size wholeSize(sz.width + border*2, sz.height + border*2);
00771 Mat temp(wholeSize, image.type()), masktemp;
00772 imagePyramid[level] = temp(Rect(border, border, sz.width, sz.height));
00773
00774 if( !mask.empty() )
00775 {
00776 masktemp = Mat(wholeSize, mask.type());
00777 maskPyramid[level] = masktemp(Rect(border, border, sz.width, sz.height));
00778 }
00779
00780
00781 if( level != firstLevel )
00782 {
00783 if( level < firstLevel )
00784 {
00785 resize(image, imagePyramid[level], sz, scale, scale, INTER_LINEAR);
00786 if (!mask.empty())
00787 resize(mask, maskPyramid[level], sz, scale, scale, INTER_LINEAR);
00788 copyMakeBorder(imagePyramid[level], temp, border, border, border, border,
00789 BORDER_REFLECT_101+BORDER_ISOLATED);
00790 }
00791 else
00792 {
00793 resize(imagePyramid[level-1], imagePyramid[level], sz,
00794 1./scaleFactor, 1./scaleFactor, INTER_LINEAR);
00795 if (!mask.empty())
00796 resize(maskPyramid[level-1], maskPyramid[level], sz,
00797 1./scaleFactor, 1./scaleFactor, INTER_LINEAR);
00798 copyMakeBorder(imagePyramid[level], temp, border, border, border, border,
00799 BORDER_REFLECT_101+BORDER_ISOLATED);
00800 }
00801 }
00802 else
00803 {
00804 copyMakeBorder(image, temp, border, border, border, border,
00805 BORDER_REFLECT_101);
00806 image.copyTo(imagePyramid[level]);
00807 if( !mask.empty() )
00808 mask.copyTo(maskPyramid[level]);
00809 }
00810
00811 if( !mask.empty() )
00812 copyMakeBorder(maskPyramid[level], masktemp, border, border, border, border,
00813 BORDER_CONSTANT+BORDER_ISOLATED);
00814 }
00815
00816
00817 vector < vector<KeyPoint> > allKeypoints;
00818 if( do_keypoints )
00819 {
00820
00821 computeKeyPoints(imagePyramid, maskPyramid, allKeypoints,
00822 nfeatures, firstLevel, scaleFactor,
00823 edgeThreshold, patchSize, scoreType, fastThreshold);
00824
00825
00826
00827
00828
00829
00830
00831
00832
00833
00834
00835
00836
00837
00838
00839
00840 }
00841 else
00842 {
00843
00844 KeyPointsFilter::runByImageBorder(_keypoints, image.size(), edgeThreshold);
00845
00846
00847 allKeypoints.resize(nlevels);
00848 for (vector<KeyPoint>::iterator keypoint = _keypoints.begin(),
00849 keypointEnd = _keypoints.end(); keypoint != keypointEnd; ++keypoint)
00850 allKeypoints[keypoint->octave].push_back(*keypoint);
00851
00852
00853 for (int level = 0; level < nlevels; ++level)
00854 {
00855 if (level == firstLevel)
00856 continue;
00857
00858 vector<KeyPoint> & keypoints = allKeypoints[level];
00859 float scale = 1/getScale(level, firstLevel, scaleFactor);
00860 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00861 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00862 keypoint->pt *= scale;
00863 }
00864 }
00865
00866 Mat descriptors;
00867 vector<Point> pattern;
00868
00869 if( do_descriptors )
00870 {
00871 int nkeypoints = 0;
00872 for (int level = 0; level < nlevels; ++level)
00873 nkeypoints += (int)allKeypoints[level].size();
00874 if( nkeypoints == 0 )
00875 _descriptors.release();
00876 else
00877 {
00878 _descriptors.create(nkeypoints, descriptorSize(), CV_8U);
00879 descriptors = _descriptors.getMat();
00880 }
00881
00882 const int npoints = 512;
00883 Point patternbuf[npoints];
00884 const Point* pattern0 = (const Point*)bit_pattern_31_;
00885
00886 if( patchSize != 31 )
00887 {
00888 pattern0 = patternbuf;
00889 makeRandomPattern(patchSize, patternbuf, npoints);
00890 }
00891
00892 CV_Assert( WTA_K == 2 || WTA_K == 3 || WTA_K == 4 );
00893
00894 if( WTA_K == 2 )
00895 std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
00896 else
00897 {
00898 int ntuples = descriptorSize()*4;
00899 initializeOrbPattern(pattern0, pattern, ntuples, WTA_K, npoints);
00900 }
00901 }
00902
00903 _keypoints.clear();
00904 int offset = 0;
00905 for (int level = 0; level < nlevels; ++level)
00906 {
00907
00908 vector<KeyPoint>& keypoints = allKeypoints[level];
00909 int nkeypoints = (int)keypoints.size();
00910
00911
00912 if (do_descriptors)
00913 {
00914 Mat desc;
00915 if (!descriptors.empty())
00916 {
00917 desc = descriptors.rowRange(offset, offset + nkeypoints);
00918 }
00919
00920 offset += nkeypoints;
00921
00922 Mat& workingMat = imagePyramid[level];
00923
00924 GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
00925 computeDescriptors(workingMat, keypoints, desc, pattern, descriptorSize(), WTA_K);
00926 }
00927
00928
00929 if (level != firstLevel)
00930 {
00931 float scale = getScale(level, firstLevel, scaleFactor);
00932 for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
00933 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
00934 keypoint->pt *= scale;
00935 }
00936
00937 _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
00938 }
00939 }
00940
00941 void AORB::detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask) const
00942 {
00943 (*this)(image, mask, keypoints, noArray(), false);
00944 }
00945
00946 void AORB::computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors) const
00947 {
00948 (*this)(image, Mat(), keypoints, descriptors, true);
00949 }
00950
00951 static Algorithm* createAORB() { return new AORB; }
00952 static AlgorithmInfo& aorb_info()
00953 {
00954 static AlgorithmInfo aorb_info_var("Feature2D.AORB", createAORB);
00955 return aorb_info_var;
00956 }
00957
00958 static AlgorithmInfo& aorb_info_auto = aorb_info();
00959
00960 AlgorithmInfo* AORB::info() const
00961 {
00962 static volatile bool initialized = false;
00963 if( !initialized )
00964 {
00965 AORB obj;
00966 aorb_info().addParam(obj, "nFeatures", obj.nfeatures);
00967 aorb_info().addParam(obj, "scaleFactor", obj.scaleFactor);
00968 aorb_info().addParam(obj, "nLevels", obj.nlevels);
00969 aorb_info().addParam(obj, "firstLevel", obj.firstLevel);
00970 aorb_info().addParam(obj, "edgeThreshold", obj.edgeThreshold);
00971 aorb_info().addParam(obj, "patchSize", obj.patchSize);
00972 aorb_info().addParam(obj, "WTA_K", obj.WTA_K);
00973 aorb_info().addParam(obj, "scoreType", obj.scoreType);
00974 aorb_info().addParam(obj, "fastThreshold", obj.fastThreshold);
00975
00976 initialized = true;
00977 }
00978 return &aorb_info();
00979 }
00980
00981 }
00982