1 /* Original code has been submitted by Liu Liu. Here is the copyright.
2 ----------------------------------------------------------------------------------
3 * An OpenCV Implementation of SURF
4 * Further Information Refer to "SURF: Speed-Up Robust Feature"
6 * liuliu.1987+opencv@gmail.com
8 * There are still serveral lacks for this experimental implementation:
9 * 1.The interpolation of sub-pixel mentioned in article was not implemented yet;
10 * 2.A comparision with original libSurf.so shows that the hessian detector is not a 100% match to their implementation;
11 * 3.Due to above reasons, I recommanded the original one for study and reuse;
13 * However, the speed of this implementation is something comparable to original one.
15 * Copyright© 2008, Liu Liu All rights reserved.
17 * Redistribution and use in source and binary forms, with or
18 * without modification, are permitted provided that the following
20 * Redistributions of source code must retain the above
21 * copyright notice, this list of conditions and the following
23 * Redistributions in binary form must reproduce the above
24 * copyright notice, this list of conditions and the following
25 * disclaimer in the documentation and/or other materials
26 * provided with the distribution.
27 * The name of Contributor may not be used to endorse or
28 * promote products derived from this software without
29 * specific prior written permission.
31 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
32 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
33 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
34 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
35 * DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY
36 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
37 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
38 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
39 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
40 * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
41 * TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
42 * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
47 The following changes have been made, comparing to the original contribution:
48 1. A lot of small optimizations, less memory allocations, got rid of global buffers
49 2. Reversed order of cvGetQuadrangleSubPix and cvResize calls; probably less accurate, but much faster
50 3. The descriptor computing part (which is most expensive) is threaded using OpenMP
51 (subpixel-accurate keypoint localization and scale estimation are still TBD)
55 KeyPoint position and scale interpolation has been implemented as described in
56 the Brown and Lowe paper cited by the SURF paper.
58 The sampling step along the x and y axes of the image for the determinant of the
59 Hessian is now the same for each layer in an octave. While this increases the
60 computation time, it ensures that a true 3x3x3 neighbourhood exists, with
61 samples calculated at the same position in the layers above and below. This
62 results in improved maxima detection and non-maxima suppression, and I think it
63 is consistent with the description in the SURF paper.
65 The wavelet size sampling interval has also been made consistent. The wavelet
66 size at the first layer of the first octave is now 9 instead of 7. Along with
67 regular position sampling steps, this makes location and scale interpolation
68 easy. I think this is consistent with the SURF paper and original
71 The scaling of the wavelet parameters has been fixed to ensure that the patterns
72 are symmetric around the centre. Previously the truncation caused by integer
73 division in the scaling ratio caused a bias towards the top left of the wavelet,
74 resulting in inconsistent keypoint positions.
76 The matrices for the determinant and trace of the Hessian are now reused in each
79 The extraction of the patch of pixels surrounding a keypoint used to build a
80 descriptor has been simplified.
82 KeyPoint descriptor normalisation has been changed from normalising each 4x4
83 cell (resulting in a descriptor of magnitude 16) to normalising the entire
84 descriptor to magnitude 1.
86 The default number of octaves has been increased from 3 to 4 to match the
87 original SURF binary default. The increase in computation time is minimal since
88 the higher octaves are sampled sparsely.
90 The default number of layers per octave has been reduced from 3 to 2, to prevent
91 redundant calculation of similar sizes in consecutive octaves. This decreases
92 computation time. The number of features extracted may be less, however the
93 additional features were mostly redundant.
95 The radius of the circle of gradient samples used to assign an orientation has
96 been increased from 4 to 6 to match the description in the SURF paper. This is
97 now defined by ORI_RADIUS, and could be made into a parameter.
99 The size of the sliding window used in orientation assignment has been reduced
100 from 120 to 60 degrees to match the description in the SURF paper. This is now
101 defined by ORI_WIN, and could be made into a parameter.
103 Other options like HAAR_SIZE0, HAAR_SIZE_INC, SAMPLE_STEP0, ORI_SEARCH_INC,
104 ORI_SIGMA and DESC_SIGMA have been separated from the code and documented.
105 These could also be made into parameters.
107 Modifications by Ian Mahon
110 #include "precomp.hpp"
112 CvSURFParams cvSURFParams(double threshold, int extended)
115 params.hessianThreshold = threshold;
116 params.extended = extended;
119 params.nOctaveLayers = 2;
127 CvSurfHF(): p0(0),p1(0),p2(0),p3(0),w(0) {}
131 icvCalcHaarPattern( const int* origin, const CvSurfHF* f, int n )
134 for( int k = 0; k < n; k++ )
135 d += (origin[f[k].p0] + origin[f[k].p3] - origin[f[k].p1] - origin[f[k].p2])*f[k].w;
140 icvResizeHaarPattern( const int src[][5], CvSurfHF* dst, int n, int oldSize, int newSize, int widthStep )
142 float ratio = (float)newSize/oldSize;
143 for( int k = 0; k < n; k++ )
145 int dx1 = cvRound( ratio*src[k][0] );
146 int dy1 = cvRound( ratio*src[k][1] );
147 int dx2 = cvRound( ratio*src[k][2] );
148 int dy2 = cvRound( ratio*src[k][3] );
149 dst[k].p0 = dy1*widthStep + dx1;
150 dst[k].p1 = dy2*widthStep + dx1;
151 dst[k].p2 = dy1*widthStep + dx2;
152 dst[k].p3 = dy2*widthStep + dx2;
153 dst[k].w = src[k][4]/((float)(dx2-dx1)*(dy2-dy1));
158 * Calculate the determinant and trace of the Hessian for a layer of the
159 * scale-space pyramid
162 icvCalcLayerDetAndTrace( const CvMat* sum, int size, int sampleStep, CvMat *det, CvMat *trace )
164 const int NX=3, NY=3, NXY=4;
165 const int dx_s[NX][5] = { {0, 2, 3, 7, 1}, {3, 2, 6, 7, -2}, {6, 2, 9, 7, 1} };
166 const int dy_s[NY][5] = { {2, 0, 7, 3, 1}, {2, 3, 7, 6, -2}, {2, 6, 7, 9, 1} };
167 const int dxy_s[NXY][5] = { {1, 1, 4, 4, 1}, {5, 1, 8, 4, -1}, {1, 5, 4, 8, -1}, {5, 5, 8, 8, 1} };
169 CvSurfHF Dx[NX], Dy[NY], Dxy[NXY];
170 double dx = 0, dy = 0, dxy = 0;
171 int i, j, samples_i, samples_j, margin;
173 float *det_ptr, *trace_ptr;
175 if( size>sum->rows-1 || size>sum->cols-1 )
178 icvResizeHaarPattern( dx_s , Dx , NX , 9, size, sum->cols );
179 icvResizeHaarPattern( dy_s , Dy , NY , 9, size, sum->cols );
180 icvResizeHaarPattern( dxy_s, Dxy, NXY, 9, size, sum->cols );
182 /* The integral image 'sum' is one pixel bigger than the source image */
183 samples_i = 1+(sum->rows-1-size)/sampleStep;
184 samples_j = 1+(sum->cols-1-size)/sampleStep;
186 /* Ignore pixels where some of the kernel is outside the image */
187 margin = (size/2)/sampleStep;
189 for( i = 0; i < samples_i; i++ )
191 sum_ptr = sum->data.i + (i*sampleStep)*sum->cols;
192 det_ptr = det->data.fl + (i+margin)*det->cols + margin;
193 trace_ptr = trace->data.fl + (i+margin)*trace->cols + margin;
194 for( j=0; j<samples_j; j++ )
196 dx = icvCalcHaarPattern( sum_ptr, Dx , 3 );
197 dy = icvCalcHaarPattern( sum_ptr, Dy , 3 );
198 dxy = icvCalcHaarPattern( sum_ptr, Dxy, 4 );
199 sum_ptr += sampleStep;
200 *det_ptr++ = (float)(dx*dy - 0.81*dxy*dxy);
201 *trace_ptr++ = (float)(dx + dy);
208 * Maxima location interpolation as described in "Invariant Features from
209 * Interest Point Groups" by Matthew Brown and David Lowe. This is performed by
210 * fitting a 3D quadratic to a set of neighbouring samples.
212 * The gradient vector and Hessian matrix at the initial keypoint location are
213 * approximated using central differences. The linear system Ax = b is then
214 * solved, where A is the Hessian, b is the negative gradient, and x is the
215 * offset of the interpolated maxima coordinates from the initial estimate.
216 * This is equivalent to an iteration of Netwon's optimisation algorithm.
218 * N9 contains the samples in the 3x3x3 neighbourhood of the maxima
219 * dx is the sampling step in x
220 * dy is the sampling step in y
221 * ds is the sampling step in size
222 * point contains the keypoint coordinates and scale to be modified
224 * Return value is 1 if interpolation was successful, 0 on failure.
227 icvInterpolateKeypoint( float N9[3][9], int dx, int dy, int ds, CvSURFPoint *point )
230 float A[9], x[3], b[3];
231 CvMat matA = cvMat(3, 3, CV_32F, A);
232 CvMat _x = cvMat(3, 1, CV_32F, x);
233 CvMat _b = cvMat(3, 1, CV_32F, b);
235 b[0] = -(N9[1][5]-N9[1][3])/2; /* Negative 1st deriv with respect to x */
236 b[1] = -(N9[1][7]-N9[1][1])/2; /* Negative 1st deriv with respect to y */
237 b[2] = -(N9[2][4]-N9[0][4])/2; /* Negative 1st deriv with respect to s */
239 A[0] = N9[1][3]-2*N9[1][4]+N9[1][5]; /* 2nd deriv x, x */
240 A[1] = (N9[1][8]-N9[1][6]-N9[1][2]+N9[1][0])/4; /* 2nd deriv x, y */
241 A[2] = (N9[2][5]-N9[2][3]-N9[0][5]+N9[0][3])/4; /* 2nd deriv x, s */
242 A[3] = A[1]; /* 2nd deriv y, x */
243 A[4] = N9[1][1]-2*N9[1][4]+N9[1][7]; /* 2nd deriv y, y */
244 A[5] = (N9[2][7]-N9[2][1]-N9[0][7]+N9[0][1])/4; /* 2nd deriv y, s */
245 A[6] = A[2]; /* 2nd deriv s, x */
246 A[7] = A[5]; /* 2nd deriv s, y */
247 A[8] = N9[0][4]-2*N9[1][4]+N9[2][4]; /* 2nd deriv s, s */
249 solve_ok = cvSolve( &matA, &_b, &_x );
252 if (x[0] > 1 || x[0] <-1 || x[1] > 1 || x[1] <-1 || x[2] > 1 || x[2] <-1 )
256 point->pt.x += x[0]*dx;
257 point->pt.y += x[1]*dy;
258 point->size = cvRound( point->size + x[2]*ds );
265 * Find the maxima in the determinant of the Hessian in a layer of the
266 * scale-space pyramid
269 icvFindMaximaInLayer( const CvMat *sum, const CvMat* mask_sum, const CvSURFParams* params,
270 CvMat **dets, CvMat **traces, const int *sizes,
271 int layer, int sampleStep, CvSeq* points )
275 const int dm[NM][5] = { {0, 0, 9, 9, 1} };
278 int i, j, size, margin, layer_rows, layer_cols;
279 float *det_ptr, *trace_ptr;
283 /* The integral image 'sum' is one pixel bigger than the source image */
284 layer_rows = (sum->rows-1)/sampleStep;
285 layer_cols = (sum->cols-1)/sampleStep;
287 /* Ignore pixels without a 3x3x3 neighbourhood in the layer above */
288 margin = (sizes[layer+1]/2)/sampleStep+1;
291 icvResizeHaarPattern( dm, &Dm, NM, 9, size, mask_sum->cols );
293 for( i = margin; i < layer_rows-margin; i++ )
295 det_ptr = dets[layer]->data.fl + i*dets[layer]->cols;
296 trace_ptr = traces[layer]->data.fl + i*traces[layer]->cols;
297 for( j = margin; j < layer_cols-margin; j++ )
299 float val0 = det_ptr[j];
300 if( val0 > params->hessianThreshold )
302 /* Coordinates for the start of the wavelet in the sum image. There
303 is some integer division involved, so don't try to simplify this
304 (cancel out sampleStep) without checking the result is the same */
305 int sum_i = sampleStep*(i-(size/2)/sampleStep);
306 int sum_j = sampleStep*(j-(size/2)/sampleStep);
308 /* The 3x3x3 neighbouring samples around the maxima.
309 The maxima is included at N9[1][4] */
310 int c = dets[layer]->cols;
311 const float *det1 = dets[layer-1]->data.fl + i*c + j;
312 const float *det2 = dets[layer]->data.fl + i*c + j;
313 const float *det3 = dets[layer+1]->data.fl + i*c + j;
314 float N9[3][9] = { { det1[-c-1], det1[-c], det1[-c+1],
315 det1[-1] , det1[0] , det1[1],
316 det1[c-1] , det1[c] , det1[c+1] },
317 { det2[-c-1], det2[-c], det2[-c+1],
318 det2[-1] , det2[0] , det2[1],
319 det2[c-1] , det2[c] , det2[c+1] },
320 { det3[-c-1], det3[-c], det3[-c+1],
321 det3[-1] , det3[0] , det3[1],
322 det3[c-1] , det3[c] , det3[c+1] } };
324 /* Check the mask - why not just check the mask at the center of the wavelet? */
327 const int* mask_ptr = mask_sum->data.i + mask_sum->cols*sum_i + sum_j;
328 float mval = icvCalcHaarPattern( mask_ptr, &Dm, 1 );
333 /* Non-maxima suppression. val0 is at N9[1][4]*/
334 if( val0 > N9[0][0] && val0 > N9[0][1] && val0 > N9[0][2] &&
335 val0 > N9[0][3] && val0 > N9[0][4] && val0 > N9[0][5] &&
336 val0 > N9[0][6] && val0 > N9[0][7] && val0 > N9[0][8] &&
337 val0 > N9[1][0] && val0 > N9[1][1] && val0 > N9[1][2] &&
338 val0 > N9[1][3] && val0 > N9[1][5] &&
339 val0 > N9[1][6] && val0 > N9[1][7] && val0 > N9[1][8] &&
340 val0 > N9[2][0] && val0 > N9[2][1] && val0 > N9[2][2] &&
341 val0 > N9[2][3] && val0 > N9[2][4] && val0 > N9[2][5] &&
342 val0 > N9[2][6] && val0 > N9[2][7] && val0 > N9[2][8] )
344 /* Calculate the wavelet center coordinates for the maxima */
345 double center_i = sum_i + (double)(size-1)/2;
346 double center_j = sum_j + (double)(size-1)/2;
348 CvSURFPoint point = cvSURFPoint( cvPoint2D32f(center_j,center_i),
349 CV_SIGN(trace_ptr[j]), sizes[layer], 0, val0 );
351 /* Interpolate maxima location within the 3x3x3 neighbourhood */
352 int ds = size-sizes[layer-1];
353 int interp_ok = icvInterpolateKeypoint( N9, sampleStep, sampleStep, ds, &point );
355 /* Sometimes the interpolation step gives a negative size etc. */
358 /*printf( "KeyPoint %f %f %d\n", point.pt.x, point.pt.y, point.size );*/
361 tbb::mutex::scoped_lock lock(m);
363 cvSeqPush( points, &point );
374 /* Multi-threaded construction of the scale-space pyramid */
375 struct SURFBuildInvoker
377 SURFBuildInvoker( const CvMat *_sum, const int *_sizes, const int *_sampleSteps,
378 CvMat** _dets, CvMat** _traces )
382 sampleSteps = _sampleSteps;
387 void operator()(const BlockedRange& range) const
389 for( int i=range.begin(); i<range.end(); i++ )
390 icvCalcLayerDetAndTrace( sum, sizes[i], sampleSteps[i], dets[i], traces[i] );
395 const int *sampleSteps;
400 /* Multi-threaded search of the scale-space pyramid for keypoints */
401 struct SURFFindInvoker
403 SURFFindInvoker( const CvMat *_sum, const CvMat *_mask_sum, const CvSURFParams* _params,
404 CvMat** _dets, CvMat** _traces, const int *_sizes,
405 const int *_sampleSteps, const int *_middleIndices, CvSeq* _points )
409 mask_sum = _mask_sum;
414 sampleSteps = _sampleSteps;
415 middleIndices = _middleIndices;
419 void operator()(const BlockedRange& range) const
421 for( int i=range.begin(); i<range.end(); i++ )
423 int layer = middleIndices[i];
424 icvFindMaximaInLayer( sum, mask_sum, params, dets, traces, sizes, layer,
425 sampleSteps[layer], points );
430 const CvMat *mask_sum;
431 const CvSURFParams* params;
435 const int *sampleSteps;
436 const int *middleIndices;
444 /* Wavelet size at first layer of first octave. */
445 const int HAAR_SIZE0 = 9;
447 /* Wavelet size increment between layers. This should be an even number,
448 such that the wavelet sizes in an octave are either all even or all odd.
449 This ensures that when looking for the neighbours of a sample, the layers
450 above and below are aligned correctly. */
451 const int HAAR_SIZE_INC = 6;
454 static CvSeq* icvFastHessianDetector( const CvMat* sum, const CvMat* mask_sum,
455 CvMemStorage* storage, const CvSURFParams* params )
457 CvSeq* points = cvCreateSeq( 0, sizeof(CvSeq), sizeof(CvSURFPoint), storage );
459 /* Sampling step along image x and y axes at first octave. This is doubled
460 for each additional octave. WARNING: Increasing this improves speed,
461 however keypoint extraction becomes unreliable. */
462 const int SAMPLE_STEP0 = 1;
464 int nTotalLayers = (params->nOctaveLayers+2)*params->nOctaves;
465 int nMiddleLayers = params->nOctaveLayers*params->nOctaves;
467 cv::AutoBuffer<CvMat*> dets(nTotalLayers);
468 cv::AutoBuffer<CvMat*> traces(nTotalLayers);
469 cv::AutoBuffer<int> sizes(nTotalLayers);
470 cv::AutoBuffer<int> sampleSteps(nTotalLayers);
471 cv::AutoBuffer<int> middleIndices(nMiddleLayers);
472 int octave, layer, step, index, middleIndex;
474 /* Allocate space and calculate properties of each layer */
478 for( octave=0; octave<params->nOctaves; octave++ )
480 for( layer=0; layer<params->nOctaveLayers+2; layer++ )
482 /* The integral image sum is one pixel bigger than the source image*/
483 dets[index] = cvCreateMat( (sum->rows-1)/step, (sum->cols-1)/step, CV_32FC1 );
484 traces[index] = cvCreateMat( (sum->rows-1)/step, (sum->cols-1)/step, CV_32FC1 );
485 sizes[index] = (HAAR_SIZE0+HAAR_SIZE_INC*layer)<<octave;
486 sampleSteps[index] = step;
488 if( layer!=0 && layer!=params->nOctaveLayers+1 )
489 middleIndices[middleIndex++] = index;
496 /* Calculate hessian determinant and trace samples in each layer*/
497 cv::parallel_for( cv::BlockedRange(0, nTotalLayers),
498 cv::SURFBuildInvoker(sum,sizes,sampleSteps,dets,traces) );
500 /* Find maxima in the determinant of the hessian */
501 cv::parallel_for( cv::BlockedRange(0, nMiddleLayers),
502 cv::SURFFindInvoker(sum,mask_sum,params,dets,traces,sizes,
503 sampleSteps,middleIndices,points) );
505 cv::SURFBuildInvoker(sum,sizes,sampleSteps,dets,traces)
506 (cv::BlockedRange(0, nTotalLayers));
508 cv::SURFFindInvoker(sum,mask_sum,params,dets,traces,sizes, sampleSteps,middleIndices,points)
509 ( cv::BlockedRange(0, nMiddleLayers) );
513 for( layer = 0; layer < nTotalLayers; layer++ )
515 cvReleaseMat( &dets[layer] );
516 cvReleaseMat( &traces[layer] );
526 /* Methods to free data allocated in SURFInvoker constructor */
527 template<> inline void Ptr<float>::delete_obj() { cvFree(&obj); }
528 template<> inline void Ptr<CvPoint>::delete_obj() { cvFree(&obj); }
532 enum { ORI_RADIUS = 6, ORI_WIN = 60, PATCH_SZ = 20 };
534 static const int ORI_SEARCH_INC;
535 static const float ORI_SIGMA;
536 static const float DESC_SIGMA;
538 SURFInvoker( const CvSURFParams* _params,
539 CvSeq* _keypoints, CvSeq* _descriptors,
540 const CvMat* _img, const CvMat* _sum )
543 keypoints = _keypoints;
544 descriptors = _descriptors;
548 /* Simple bound for number of grid points in circle of radius ORI_RADIUS */
549 const int nOriSampleBound = (2*ORI_RADIUS+1)*(2*ORI_RADIUS+1);
551 /* Allocate arrays */
552 apt = (CvPoint*)cvAlloc(nOriSampleBound*sizeof(CvPoint));
553 aptw = (float*)cvAlloc(nOriSampleBound*sizeof(float));
554 DW = (float*)cvAlloc(PATCH_SZ*PATCH_SZ*sizeof(float));
556 /* Coordinates and weights of samples used to calculate orientation */
557 cv::Mat G_ori = cv::getGaussianKernel( 2*ORI_RADIUS+1, ORI_SIGMA, CV_32F );
559 for( int i = -ORI_RADIUS; i <= ORI_RADIUS; i++ )
561 for( int j = -ORI_RADIUS; j <= ORI_RADIUS; j++ )
563 if( i*i + j*j <= ORI_RADIUS*ORI_RADIUS )
565 apt[nOriSamples] = cvPoint(i,j);
566 aptw[nOriSamples++] = G_ori.at<float>(i+ORI_RADIUS,0) * G_ori.at<float>(j+ORI_RADIUS,0);
570 CV_Assert( nOriSamples <= nOriSampleBound );
572 /* Gaussian used to weight descriptor samples */
573 cv::Mat G_desc = cv::getGaussianKernel( PATCH_SZ, DESC_SIGMA, CV_32F );
574 for( int i = 0; i < PATCH_SZ; i++ )
576 for( int j = 0; j < PATCH_SZ; j++ )
577 DW[i*PATCH_SZ+j] = G_desc.at<float>(i,0) * G_desc.at<float>(j,0);
581 void operator()(const BlockedRange& range) const
583 /* X and Y gradient wavelet data */
584 const int NX=2, NY=2;
585 const int dx_s[NX][5] = {{0, 0, 2, 4, -1}, {2, 0, 4, 4, 1}};
586 const int dy_s[NY][5] = {{0, 0, 4, 2, 1}, {0, 2, 4, 4, -1}};
588 const int descriptor_size = params->extended ? 128 : 64;
589 /* Optimisation is better using nOriSampleBound than nOriSamples for
590 array lengths. Maybe because it is a constant known at compile time */
591 const int nOriSampleBound =(2*ORI_RADIUS+1)*(2*ORI_RADIUS+1);
593 float X[nOriSampleBound], Y[nOriSampleBound], angle[nOriSampleBound];
594 uchar PATCH[PATCH_SZ+1][PATCH_SZ+1];
595 float DX[PATCH_SZ][PATCH_SZ], DY[PATCH_SZ][PATCH_SZ];
596 CvMat matX = cvMat(1, nOriSampleBound, CV_32F, X);
597 CvMat matY = cvMat(1, nOriSampleBound, CV_32F, Y);
598 CvMat _angle = cvMat(1, nOriSampleBound, CV_32F, angle);
599 CvMat _patch = cvMat(PATCH_SZ+1, PATCH_SZ+1, CV_8U, PATCH);
601 int k, k1 = range.begin(), k2 = range.end();
603 for( k = k1; k < k2; k++ )
605 maxSize = std::max(maxSize, ((CvSURFPoint*)cvGetSeqElem( keypoints, k ))->size);
607 maxSize = cvCeil((PATCH_SZ+1)*maxSize*1.2f/9.0f);
608 Ptr<CvMat> winbuf = cvCreateMat( 1, maxSize > 0 ? maxSize*maxSize : 1, CV_8U );
609 for( k = k1; k < k2; k++ )
611 const int* sum_ptr = sum->data.i;
612 int sum_cols = sum->cols;
613 int i, j, kk, x, y, nangle;
615 CvSurfHF dx_t[NX], dy_t[NY];
616 CvSURFPoint* kp = (CvSURFPoint*)cvGetSeqElem( keypoints, k );
618 CvPoint2D32f center = kp->pt;
619 /* The sampling intervals and wavelet sized for selecting an orientation
620 and building the keypoint descriptor are defined relative to 's' */
621 float s = (float)size*1.2f/9.0f;
622 /* To find the dominant orientation, the gradients in x and y are
623 sampled in a circle of radius 6s using wavelets of size 4s.
624 We ensure the gradient wavelet size is even to ensure the
625 wavelet pattern is balanced and symmetric around its center */
626 int grad_wav_size = 2*cvRound( 2*s );
627 if ( sum->rows < grad_wav_size || sum->cols < grad_wav_size )
629 /* when grad_wav_size is too big,
630 * the sampling of gradient will be meaningless
631 * mark keypoint for deletion. */
636 float descriptor_dir = 90.f;
637 if (params->upright == 0)
639 icvResizeHaarPattern( dx_s, dx_t, NX, 4, grad_wav_size, sum->cols );
640 icvResizeHaarPattern( dy_s, dy_t, NY, 4, grad_wav_size, sum->cols );
641 for( kk = 0, nangle = 0; kk < nOriSamples; kk++ )
645 x = cvRound( center.x + apt[kk].x*s - (float)(grad_wav_size-1)/2 );
646 y = cvRound( center.y + apt[kk].y*s - (float)(grad_wav_size-1)/2 );
647 if( (unsigned)y >= (unsigned)(sum->rows - grad_wav_size) ||
648 (unsigned)x >= (unsigned)(sum->cols - grad_wav_size) )
650 ptr = sum_ptr + x + y*sum_cols;
651 vx = icvCalcHaarPattern( ptr, dx_t, 2 );
652 vy = icvCalcHaarPattern( ptr, dy_t, 2 );
653 X[nangle] = vx*aptw[kk]; Y[nangle] = vy*aptw[kk];
658 /* No gradient could be sampled because the keypoint is too
659 * near too one or more of the sides of the image. As we
660 * therefore cannot find a dominant direction, we skip this
661 * keypoint and mark it for later deletion from the sequence. */
665 matX.cols = matY.cols = _angle.cols = nangle;
666 cvCartToPolar( &matX, &matY, 0, &_angle, 1 );
668 float bestx = 0, besty = 0, descriptor_mod = 0;
669 for( i = 0; i < 360; i += ORI_SEARCH_INC )
671 float sumx = 0, sumy = 0, temp_mod;
672 for( j = 0; j < nangle; j++ )
674 int d = std::abs(cvRound(angle[j]) - i);
675 if( d < ORI_WIN/2 || d > 360-ORI_WIN/2 )
681 temp_mod = sumx*sumx + sumy*sumy;
682 if( temp_mod > descriptor_mod )
684 descriptor_mod = temp_mod;
689 descriptor_dir = cvFastArctan( besty, bestx );
691 kp->dir = descriptor_dir;
695 /* Extract a window of pixels around the keypoint of size 20s */
696 int win_size = (int)((PATCH_SZ+1)*s);
697 CV_Assert( winbuf->cols >= win_size*win_size );
698 CvMat win = cvMat(win_size, win_size, CV_8U, winbuf->data.ptr);
700 if (params->upright == 0)
702 descriptor_dir *= (float)(CV_PI/180);
703 float sin_dir = sin(descriptor_dir);
704 float cos_dir = cos(descriptor_dir);
706 /* Subpixel interpolation version (slower). Subpixel not required since
707 the pixels will all get averaged when we scale down to 20 pixels */
709 float w[] = { cos_dir, sin_dir, center.x,
710 -sin_dir, cos_dir , center.y };
711 CvMat W = cvMat(2, 3, CV_32F, w);
712 cvGetQuadrangleSubPix( img, &win, &W );
715 /* Nearest neighbour version (faster) */
716 float win_offset = -(float)(win_size-1)/2;
717 float start_x = center.x + win_offset*cos_dir + win_offset*sin_dir;
718 float start_y = center.y - win_offset*sin_dir + win_offset*cos_dir;
719 uchar* WIN = win.data.ptr;
720 for( i = 0; i < win_size; i++, start_x += sin_dir, start_y += cos_dir )
722 float pixel_x = start_x;
723 float pixel_y = start_y;
724 for( j = 0; j < win_size; j++, pixel_x += cos_dir, pixel_y -= sin_dir )
726 int x = std::min(std::max(cvRound(pixel_x), 0), img->cols-1);
727 int y = std::min(std::max(cvRound(pixel_y), 0), img->rows-1);
728 WIN[i*win_size + j] = img->data.ptr[y*img->step + x];
734 /* extract rect - slightly optimized version of the code above
735 TODO: find faster code, as this is simply an extract rect operation,
736 e.g. by using cvGetSubRect, problem is the border processing */
737 // descriptor_dir == 90 grad
741 float win_offset = -(float)(win_size-1)/2;
742 int start_x = cvRound(center.x + win_offset);
743 int start_y = cvRound(center.y - win_offset);
744 uchar* WIN = win.data.ptr;
745 for( i = 0; i < win_size; i++, start_x++ )
747 int pixel_x = start_x;
748 int pixel_y = start_y;
749 for( j=0; j<win_size; j++, pixel_y-- )
751 x = MAX( pixel_x, 0 );
752 y = MAX( pixel_y, 0 );
753 x = MIN( x, img->cols-1 );
754 y = MIN( y, img->rows-1 );
755 WIN[i*win_size + j] = img->data.ptr[y*img->step+x];
759 /* Scale the window to size PATCH_SZ so each pixel's size is s. This
760 makes calculating the gradients with wavelets of size 2s easy */
761 cvResize( &win, &_patch, CV_INTER_AREA );
763 /* Calculate gradients in x and y with wavelets of size 2s */
764 for( i = 0; i < PATCH_SZ; i++ )
765 for( j = 0; j < PATCH_SZ; j++ )
767 float dw = DW[i*PATCH_SZ + j];
768 float vx = (PATCH[i][j+1] - PATCH[i][j] + PATCH[i+1][j+1] - PATCH[i+1][j])*dw;
769 float vy = (PATCH[i+1][j] - PATCH[i][j] + PATCH[i+1][j+1] - PATCH[i][j+1])*dw;
774 /* Construct the descriptor */
775 vec = (float*)cvGetSeqElem( descriptors, k );
776 for( kk = 0; kk < (int)(descriptors->elem_size/sizeof(vec[0])); kk++ )
778 double square_mag = 0;
779 if( params->extended )
781 /* 128-bin descriptor */
782 for( i = 0; i < 4; i++ )
783 for( j = 0; j < 4; j++ )
785 for( y = i*5; y < i*5+5; y++ )
787 for( x = j*5; x < j*5+5; x++ )
789 float tx = DX[y][x], ty = DY[y][x];
793 vec[1] += (float)fabs(tx);
796 vec[3] += (float)fabs(tx);
801 vec[5] += (float)fabs(ty);
804 vec[7] += (float)fabs(ty);
808 for( kk = 0; kk < 8; kk++ )
809 square_mag += vec[kk]*vec[kk];
815 /* 64-bin descriptor */
816 for( i = 0; i < 4; i++ )
817 for( j = 0; j < 4; j++ )
819 for( y = i*5; y < i*5+5; y++ )
821 for( x = j*5; x < j*5+5; x++ )
823 float tx = DX[y][x], ty = DY[y][x];
824 vec[0] += tx; vec[1] += ty;
825 vec[2] += (float)fabs(tx); vec[3] += (float)fabs(ty);
828 for( kk = 0; kk < 4; kk++ )
829 square_mag += vec[kk]*vec[kk];
834 /* unit vector is essential for contrast invariance */
835 vec = (float*)cvGetSeqElem( descriptors, k );
836 double scale = 1./(sqrt(square_mag) + DBL_EPSILON);
837 for( kk = 0; kk < descriptor_size; kk++ )
838 vec[kk] = (float)(vec[kk]*scale);
843 const CvSURFParams* params;
849 /* Pre-calculated values */
851 cv::Ptr<CvPoint> apt;
856 const int SURFInvoker::ORI_SEARCH_INC = 5;
857 const float SURFInvoker::ORI_SIGMA = 2.5f;
858 const float SURFInvoker::DESC_SIGMA = 3.3f;
863 cvExtractSURF( const CvArr* _img, const CvArr* _mask,
864 CvSeq** _keypoints, CvSeq** _descriptors,
865 CvMemStorage* storage, CvSURFParams params,
866 int useProvidedKeyPts)
868 CvMat *sum = 0, *mask1 = 0, *mask_sum = 0;
870 if( _keypoints && !useProvidedKeyPts ) // If useProvidedKeyPts!=0 we'll use current contents of "*_keypoints"
875 CvSeq *keypoints, *descriptors = 0;
876 CvMat imghdr, *img = cvGetMat(_img, &imghdr);
877 CvMat maskhdr, *mask = _mask ? cvGetMat(_mask, &maskhdr) : 0;
879 int descriptor_size = params.extended ? 128 : 64;
880 const int descriptor_data_type = CV_32F;
884 CV_Assert(CV_MAT_TYPE(img->type) == CV_8UC1);
885 CV_Assert(mask == 0 || (CV_ARE_SIZES_EQ(img,mask) && CV_MAT_TYPE(mask->type) == CV_8UC1));
886 CV_Assert(storage != 0);
887 CV_Assert(params.hessianThreshold >= 0);
888 CV_Assert(params.nOctaves > 0);
889 CV_Assert(params.nOctaveLayers > 0);
891 sum = cvCreateMat( img->rows+1, img->cols+1, CV_32SC1 );
892 cvIntegral( img, sum );
894 // Compute keypoints only if we are not asked for evaluating the descriptors are some given locations:
895 if (!useProvidedKeyPts)
899 mask1 = cvCreateMat( img->height, img->width, CV_8UC1 );
900 mask_sum = cvCreateMat( img->height+1, img->width+1, CV_32SC1 );
901 cvMinS( mask, 1, mask1 );
902 cvIntegral( mask1, mask_sum );
904 keypoints = icvFastHessianDetector( sum, mask_sum, storage, ¶ms );
908 CV_Assert(useProvidedKeyPts && (_keypoints != 0) && (*_keypoints != 0));
909 keypoints = *_keypoints;
912 N = keypoints->total;
915 descriptors = cvCreateSeq( 0, sizeof(CvSeq),
916 descriptor_size*CV_ELEM_SIZE(descriptor_data_type), storage );
917 cvSeqPushMulti( descriptors, 0, N );
924 cv::parallel_for(cv::BlockedRange(0, N),
925 cv::SURFInvoker(¶ms, keypoints, descriptors, img, sum) );
927 cv::SURFInvoker invoker(¶ms, keypoints, descriptors, img, sum);
928 invoker(cv::BlockedRange(0, N));
933 /* remove keypoints that were marked for deletion */
934 for ( i = 0; i < N; i++ )
936 CvSURFPoint* kp = (CvSURFPoint*)cvGetSeqElem( keypoints, i );
937 if ( kp->size == -1 )
939 cvSeqRemove( keypoints, i );
941 cvSeqRemove( descriptors, i );
947 if( _keypoints && !useProvidedKeyPts )
948 *_keypoints = keypoints;
950 *_descriptors = descriptors;
952 cvReleaseMat( &sum );
953 if (mask1) cvReleaseMat( &mask1 );
954 if (mask_sum) cvReleaseMat( &mask_sum );
963 hessianThreshold = 100;
970 SURF::SURF(double _threshold, int _nOctaves, int _nOctaveLayers, bool _extended, bool _upright)
972 hessianThreshold = _threshold;
973 extended = _extended;
975 nOctaves = _nOctaves;
976 nOctaveLayers = _nOctaveLayers;
979 int SURF::descriptorSize() const { return extended ? 128 : 64; }
982 static int getPointOctave(const CvSURFPoint& kpt, const CvSURFParams& params)
984 int octave = 0, layer = 0, best_octave = 0;
985 float min_diff = FLT_MAX;
986 for( octave = 1; octave < params.nOctaves; octave++ )
987 for( layer = 0; layer < params.nOctaveLayers; layer++ )
989 float diff = std::abs(kpt.size - (float)((HAAR_SIZE0 + HAAR_SIZE_INC*layer) << octave));
990 if( min_diff > diff )
993 best_octave = octave;
1002 void SURF::operator()(const Mat& img, const Mat& mask,
1003 vector<KeyPoint>& keypoints) const
1005 CvMat _img = img, _mask, *pmask = 0;
1007 pmask = &(_mask = mask);
1008 MemStorage storage(cvCreateMemStorage(0));
1009 Seq<CvSURFPoint> kp;
1010 cvExtractSURF(&_img, pmask, &kp.seq, 0, storage, *(const CvSURFParams*)this, 0);
1011 Seq<CvSURFPoint>::iterator it = kp.begin();
1012 size_t i, n = kp.size();
1013 keypoints.resize(n);
1014 for( i = 0; i < n; i++, ++it )
1016 const CvSURFPoint& kpt = *it;
1017 keypoints[i] = KeyPoint(kpt.pt, (float)kpt.size, kpt.dir,
1018 kpt.hessian, getPointOctave(kpt, *this));
1022 void SURF::operator()(const Mat& img, const Mat& mask,
1023 vector<KeyPoint>& keypoints,
1024 vector<float>& descriptors,
1025 bool useProvidedKeypoints) const
1027 CvMat _img = img, _mask, *pmask = 0;
1029 pmask = &(_mask = mask);
1030 MemStorage storage(cvCreateMemStorage(0));
1031 Seq<CvSURFPoint> kp;
1034 if( useProvidedKeypoints )
1036 kp = cvCreateSeq( 0, sizeof(CvSeq), sizeof(CvSURFPoint), storage);
1037 n = keypoints.size();
1038 for( i = 0; i < n; i++ )
1040 const KeyPoint& kpt = keypoints[i];
1041 kp.push_back(cvSURFPoint(kpt.pt, 1, cvRound(kpt.size), kpt.angle, kpt.response));
1045 cvExtractSURF(&_img, pmask, &kp.seq, &d, storage,
1046 *(const CvSURFParams*)this, useProvidedKeypoints);
1048 // input keypoints can be filtered in cvExtractSURF()
1049 if( !useProvidedKeypoints || (useProvidedKeypoints && keypoints.size() != kp.size()) )
1051 Seq<CvSURFPoint>::iterator it = kp.begin();
1052 size_t i, n = kp.size();
1053 keypoints.resize(n);
1054 for( i = 0; i < n; i++, ++it )
1056 const CvSURFPoint& kpt = *it;
1057 keypoints[i] = KeyPoint(kpt.pt, (float)kpt.size, kpt.dir,
1058 kpt.hessian, getPointOctave(kpt, *this),
1062 descriptors.resize(d ? d->total*d->elem_size/sizeof(float) : 0);
1063 if(descriptors.size() != 0)
1064 cvCvtSeqToArray(d, &descriptors[0]);