1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009
5  * Engin Tola
6  * web : http://www.engintola.com
7  * email : engin.tola+libdaisy@gmail.com
8  *
9  *  Redistribution and use in source and binary forms, with or without
10  *  modification, are permitted provided that the following conditions
11  *  are met:
12  *
13  *   * Redistributions of source code must retain the above copyright
14  *     notice, this list of conditions and the following disclaimer.
15  *   * Redistributions in binary form must reproduce the above
16  *     copyright notice, this list of conditions and the following
17  *     disclaimer in the documentation and/or other materials provided
18  *     with the distribution.
19  *   * Neither the name of the Willow Garage nor the names of its
20  *     contributors may be used to endorse or promote products derived
21  *     from this software without specific prior written permission.
22  *
23  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  *  POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /*
38  "DAISY: An Efficient Dense Descriptor Applied to Wide Baseline Stereo"
39  by Engin Tola, Vincent Lepetit and Pascal Fua. IEEE Transactions on
40  Pattern Analysis and achine Intelligence, 31 Mar. 2009.
41  IEEE computer Society Digital Library. IEEE Computer Society,
42  http:doi.ieeecomputersociety.org/10.1109/TPAMI.2009.77
43 
44  "A fast local descriptor for dense matching" by Engin Tola, Vincent
45  Lepetit, and Pascal Fua. Intl. Conf. on Computer Vision and Pattern
46  Recognition, Alaska, USA, June 2008
47 
48  OpenCV port by: Cristian Balint <cristian dot balint at gmail dot com>
49  */
50 
51 #include "precomp.hpp"
52 
53 #include <fstream>
54 #include <stdlib.h>
55 
56 namespace cv
57 {
58 namespace xfeatures2d
59 {
60 
61 // constants
62 const double g_sigma_0 = 1;
63 const double g_sigma_1 = sqrt(2.0);
64 const double g_sigma_step = std::pow(2,1.0/2);
65 const int g_scale_st = int( (log(g_sigma_1/g_sigma_0)) / log(g_sigma_step) );
66 static int g_scale_en = 1;
67 
68 const double g_sigma_init = 1.6;
69 const static int g_grid_orientation_resolution = 360;
70 
71 static const int MAX_CUBE_NO = 64;
72 static const int MAX_NORMALIZATION_ITER = 5;
73 
74 int g_selected_cubes[MAX_CUBE_NO]; // m_rad_q_no < MAX_CUBE_NO
75 
compute(InputArrayOfArrays images,std::vector<std::vector<KeyPoint>> & keypoints,OutputArrayOfArrays descriptors)76 void DAISY::compute( InputArrayOfArrays images,
77                      std::vector<std::vector<KeyPoint> >& keypoints,
78                      OutputArrayOfArrays descriptors )
79 {
80     DescriptorExtractor::compute(images, keypoints, descriptors);
81 }
82 
83 /*
84  !DAISY implementation
85  */
86 class DAISY_Impl CV_FINAL : public DAISY
87 {
88 
89 public:
90     /** Constructor
91      * @param radius radius of the descriptor at the initial scale
92      * @param q_radius amount of radial range divisions
93      * @param q_theta amount of angular range divisions
94      * @param q_hist amount of gradient orientations range divisions
95      * @param norm normalization type
96      * @param H optional 3x3 homography matrix used to warp the grid of daisy but sampling keypoints remains unwarped on image
97      * @param interpolation switch to disable interpolation at minor costs of quality (default is true)
98      * @param use_orientation sample patterns using keypoints orientation, disabled by default.
99      */
100     explicit DAISY_Impl(float radius=15, int q_radius=3, int q_theta=8, int q_hist=8,
101                         DAISY::NormalizationType norm = DAISY::NRM_NONE, InputArray H = noArray(),
102                         bool interpolation = true, bool use_orientation = false);
103 
104     virtual ~DAISY_Impl() CV_OVERRIDE;
105 
106     /** returns the descriptor length in bytes */
descriptorSize() const107     virtual int descriptorSize() const CV_OVERRIDE {
108         // +1 is for center pixel
109         return ( (m_rad_q_no * m_th_q_no + 1) * m_hist_th_q_no );
110     };
111 
112     /** returns the descriptor type */
descriptorType() const113     virtual int descriptorType() const CV_OVERRIDE { return CV_32F; }
114 
115     /** returns the default norm type */
defaultNorm() const116     virtual int defaultNorm() const CV_OVERRIDE { return NORM_L2; }
117 
118     /**
119      * @param image image to extract descriptors
120      * @param keypoints of interest within image
121      * @param descriptors resulted descriptors array
122      */
123     virtual void compute( InputArray image, std::vector<KeyPoint>& keypoints, OutputArray descriptors ) CV_OVERRIDE;
124 
125     /** @overload
126      * @param image image to extract descriptors
127      * @param roi region of interest within image
128      * @param descriptors resulted descriptors array
129      */
130     virtual void compute( InputArray image, Rect roi, OutputArray descriptors ) CV_OVERRIDE;
131 
132     /** @overload
133      * @param image image to extract descriptors
134      * @param descriptors resulted descriptors array
135      */
136     virtual void compute( InputArray image, OutputArray descriptors ) CV_OVERRIDE;
137 
138     /**
139      * @param y position y on image
140      * @param x position x on image
141      * @param orientation orientation on image (0->360)
142      * @param descriptor supplied array for descriptor storage
143      */
144     virtual void GetDescriptor( double y, double x, int orientation, float* descriptor ) const CV_OVERRIDE;
145 
146     /**
147      * @param y position y on image
148      * @param x position x on image
149      * @param orientation orientation on image (0->360)
150      * @param descriptor supplied array for descriptor storage
151      * @param H homography matrix for warped grid
152      */
153     virtual bool GetDescriptor( double y, double x, int orientation, float* descriptor, double* H ) const CV_OVERRIDE;
154 
155     /**
156      * @param y position y on image
157      * @param x position x on image
158      * @param orientation orientation on image (0->360)
159      * @param descriptor supplied array for descriptor storage
160      */
161     virtual void GetUnnormalizedDescriptor( double y, double x, int orientation, float* descriptor ) const CV_OVERRIDE;
162 
163     /**
164      * @param y position y on image
165      * @param x position x on image
166      * @param orientation orientation on image (0->360)
167      * @param descriptor supplied array for descriptor storage
168      * @param H homography matrix for warped grid
169      */
170     virtual bool GetUnnormalizedDescriptor( double y, double x, int orientation, float* descriptor, double* H ) const CV_OVERRIDE;
171 
172 protected:
173 
174     /*
175      * DAISY parameters
176      */
177 
178     // maximum radius of the descriptor region.
179     float m_rad;
180 
181     // the number of quantizations of the radius.
182     int m_rad_q_no;
183 
184     // the number of quantizations of the angle.
185     int m_th_q_no;
186 
187     // the number of quantizations of the gradient orientations.
188     int m_hist_th_q_no;
189 
190     // holds the type of the normalization to apply; equals to NRM_PARTIAL by
191     // default. change the value using set_normalization() function.
192     DAISY::NormalizationType m_nrm_type;
193 
194     // the size of the descriptor vector
195     int m_descriptor_size;
196 
197     // the number of grid locations
198     int m_grid_point_number;
199 
200     // number of bins in the histograms while computing orientation
201     int m_orientation_resolution;
202 
203 
204     /*
205      * DAISY switches
206      */
207 
208     // if set to true, descriptors are scale invariant
209     bool m_scale_invariant;
210 
211     // if set to true, descriptors are rotation invariant
212     bool m_rotation_invariant;
213 
214     // if enabled, descriptors are computed with casting non-integer locations
215     // to integer positions otherwise we use interpolation.
216     bool m_enable_interpolation;
217 
218     // switch to enable sample by keypoints orientation
219     bool m_use_orientation;
220 
221     /*
222      * DAISY arrays
223      */
224 
225     // holds optional H matrix
226     Mat m_h_matrix;
227 
228     // internal float image.
229     Mat m_image;
230 
231     // image roi
232     Rect m_roi;
233 
234     // stores the layered gradients in successively smoothed form :
235     // layer[n] = m_gradient_layers * gaussian( sigma_n );
236     // n>= 1; layer[0] is the layered_gradient
237     std::vector<Mat> m_smoothed_gradient_layers;
238 
239     // hold the scales of the pixels
240     Mat m_scale_map;
241 
242     // holds the orientaitons of the pixels
243     Mat m_orientation_map;
244 
245     // Holds the oriented coordinates (y,x) of the grid points of the region.
246     Mat m_oriented_grid_points;
247 
248     // holds the gaussian sigmas for radius quantizations for an incremental
249     // application
250     Mat m_cube_sigmas;
251 
252     // Holds the coordinates (y,x) of the grid points of the region.
253     Mat m_grid_points;
254 
255     // holds the amount of shift that's required for histogram computation
256     double m_orientation_shift_table[360];
257 
258 
259 private:
260 
261     /*
262      * DAISY functions
263      */
264 
265     // initializes the class: computes gradient and structure-points
266     inline void initialize();
267 
268     // initializes for get_descriptor(double, double, int) mode: pre-computes
269     // convolutions of gradient layers in m_smoothed_gradient_layers
270     inline void initialize_single_descriptor_mode();
271 
272     // set & precompute parameters
273     inline void set_parameters();
274 
275     // image set image as working
276     inline void set_image( InputArray image );
277 
278     // releases all the used memory; call this if you want to process
279     // multiple images within a loop.
280     inline void reset();
281 
282     // releases unused memory after descriptor computation is completed.
283     inline void release_auxiliary();
284 
285     // computes the descriptors for every pixel in the image.
286     inline void compute_descriptors( Mat* m_dense_descriptors );
287 
288     // computes scales for every pixel and scales the structure grid so that the
289     // resulting descriptors are scale invariant.  you must set
290     // m_scale_invariant flag to 1 for the program to call this function
291     inline void compute_scales();
292 
293     // compute the smoothed gradient layers.
294     inline void compute_smoothed_gradient_layers();
295 
296     // computes pixel orientations and rotates the structure grid so that
297     // resulting descriptors are rotation invariant. If the scales is also
298     // detected, then orientations are computed at the computed scales. you must
299     // set m_rotation_invariant flag to 1 for the program to call this function
300     inline void compute_orientations();
301 
302     // computes the histogram at yx; the size of histogram is m_hist_th_q_no
303     inline void compute_histogram( float* hcube, int y, int x, float* histogram );
304 
305     // reorganizes the cube data so that histograms are sequential in memory.
306     inline void compute_histograms();
307 
308     // computes the sigma's of layers from descriptor parameters if the user did
309     // not sets it. these define the size of the petals of the descriptor.
310     inline void compute_cube_sigmas();
311 
312     // Computes the locations of the unscaled unrotated points where the
313     // histograms are going to be computed according to the given parameters.
314     inline void compute_grid_points();
315 
316     // Computes the locations of the unscaled rotated points where the
317     // histograms are going to be computed according to the given parameters.
318     inline void compute_oriented_grid_points();
319 
320     // applies one of the normalizations (partial,full,sift) to the desciptors.
321     inline void normalize_descriptors( Mat* m_dense_descriptors );
322 
323     inline void update_selected_cubes();
324 
325 }; // END DAISY_Impl CLASS
326 
327 
328 // -------------------------------------------------
329 /* DAISY computation routines */
330 
reset()331 inline void DAISY_Impl::reset()
332 {
333     m_image.release();
334 
335     m_scale_map.release();
336     m_orientation_map.release();
337 
338     for (size_t i=0; i<m_smoothed_gradient_layers.size(); i++)
339       m_smoothed_gradient_layers[i].release();
340     m_smoothed_gradient_layers.clear();
341 }
342 
release_auxiliary()343 inline void DAISY_Impl::release_auxiliary()
344 {
345     reset();
346 
347     m_cube_sigmas.release();
348     m_grid_points.release();
349     m_oriented_grid_points.release();
350 }
351 
filter_size(double sigma,double factor)352 static int filter_size( double sigma, double factor )
353 {
354     int fsz = (int)( factor * sigma );
355     // kernel size must be odd
356     if( fsz%2 == 0 ) fsz++;
357     // kernel size cannot be smaller than 3
358     if( fsz < 3 ) fsz = 3;
359 
360     return fsz;
361 }
362 
363 // transform a point via the homography
pt_H(double * H,double x,double y,double & u,double & v)364 static void pt_H( double* H, double x, double y, double &u, double &v )
365 {
366     double kxp = H[0]*x + H[1]*y + H[2];
367     double kyp = H[3]*x + H[4]*y + H[5];
368     double kp  = H[6]*x + H[7]*y + H[8];
369     u = kxp / kp; v = kyp / kp;
370 }
371 
372 
interpolate_peak(float left,float center,float right)373 static float interpolate_peak( float left, float center, float right )
374 {
375     if( center < 0.0 )
376     {
377       left = -left;
378       center = -center;
379       right = -right;
380     }
381     CV_Assert(center >= left  &&  center >= right);
382 
383     float den = (float) (left - 2.0 * center + right);
384 
385     if( den == 0 ) return 0;
386     else           return (float) (0.5*(left -right)/den);
387 }
388 
smooth_histogram(Mat * hist,int hsz)389 static void smooth_histogram( Mat* hist, int hsz )
390 {
391     int i;
392     float prev, temp;
393 
394     prev = hist->at<float>(hsz - 1);
395     for (i = 0; i < hsz; i++)
396     {
397       temp = hist->at<float>(i);
398       hist->at<float>(i) = (prev + hist->at<float>(i) + hist->at<float>( (i + 1 == hsz) ? 0 : i + 1) ) / 3.0f;
399       prev = temp;
400     }
401 }
402 
403 struct LayeredGradientInvoker : ParallelLoopBody
404 {
LayeredGradientInvokercv::xfeatures2d::LayeredGradientInvoker405     LayeredGradientInvoker( Mat* _layers, Mat& _dy, Mat& _dx )
406     {
407       dy = _dy;
408       dx = _dx;
409       layers = _layers;
410       layer_no = layers->size[0];
411     }
412 
operator ()cv::xfeatures2d::LayeredGradientInvoker413     void operator ()(const cv::Range& range) const CV_OVERRIDE
414     {
415       for (int l = range.start; l < range.end; ++l)
416       {
417         double angle = l * 2 * (float)CV_PI / layer_no;
418         Mat layer( dx.rows, dx.cols, CV_32F, layers->ptr<float>(l,0,0) );
419         addWeighted( dx, cos( angle ), dy, sin( angle ), 0.0f, layer, CV_32F );
420         max( layer, 0.0f, layer );
421       }
422     }
423 
424     Mat dy, dx;
425     Mat *layers;
426     int layer_no;
427 };
428 
layered_gradient(Mat & data,Mat * layers)429 static void layered_gradient( Mat& data, Mat* layers )
430 {
431     Mat cvO, dx, dy;
432     int layer_no = layers->size[0];
433 
434     GaussianBlur( data, cvO, Size(5, 5), 0.5f, 0.5f, BORDER_REPLICATE );
435     Sobel( cvO, dx, CV_32F, 1, 0, 1, 0.5f, 0.0f, BORDER_REPLICATE );
436     Sobel( cvO, dy, CV_32F, 0, 1, 1, 0.5f, 0.0f, BORDER_REPLICATE );
437 
438     parallel_for_( Range(0, layer_no), LayeredGradientInvoker( layers, dy, dx ) );
439 }
440 
441 struct SmoothLayersInvoker : ParallelLoopBody
442 {
SmoothLayersInvokercv::xfeatures2d::SmoothLayersInvoker443     SmoothLayersInvoker( Mat* _layers, const float _sigma )
444     {
445       layers = _layers;
446       sigma = _sigma;
447 
448       h = layers->size[1];
449       w = layers->size[2];
450       ks = filter_size( sigma, 5.0f );
451     }
452 
operator ()cv::xfeatures2d::SmoothLayersInvoker453     void operator ()(const cv::Range& range) const CV_OVERRIDE
454     {
455       for (int l = range.start; l < range.end; ++l)
456       {
457         Mat layer( h, w, CV_32FC1, layers->ptr<float>(l,0,0) );
458         GaussianBlur( layer, layer, Size(ks, ks), sigma, sigma, BORDER_REPLICATE );
459       }
460     }
461 
462     float sigma;
463     int ks, h, w;
464     Mat *layers;
465 };
466 
smooth_layers(Mat * layers,float sigma)467 static void smooth_layers( Mat* layers, float sigma )
468 {
469     int layer_no = layers->size[0];
470     parallel_for_( Range(0, layer_no), SmoothLayersInvoker( layers, sigma ) );
471 }
472 
quantize_radius(float rad,const int _rad_q_no,const Mat & _cube_sigmas)473 static int quantize_radius( float rad, const int _rad_q_no, const Mat& _cube_sigmas )
474 {
475     if( rad <= _cube_sigmas.at<double>(0) )
476         return 0;
477     if( rad >= _cube_sigmas.at<double>(_rad_q_no-1) )
478         return _rad_q_no-1;
479 
480     int idx_min[2];
481     minMaxIdx( abs( _cube_sigmas - rad ), NULL, NULL, idx_min );
482 
483     return idx_min[1];
484 }
485 
normalize_partial(float * desc,const int _grid_point_number,const int _hist_th_q_no)486 static void normalize_partial( float* desc, const int _grid_point_number, const int _hist_th_q_no )
487 {
488     for( int h=0; h<_grid_point_number; h++ )
489     {
490       // l2 norm
491       double sum = 0.0f;
492       for( int i=0; i<_hist_th_q_no; i++ )
493       {
494           sum += desc[h*_hist_th_q_no + i]
495                * desc[h*_hist_th_q_no + i];
496       }
497 
498       float norm = (float)sqrt( sum );
499 
500       if( norm != 0.0 )
501       // divide with norm
502       for( int i=0; i<_hist_th_q_no; i++ )
503       {
504           desc[h*_hist_th_q_no + i] /= norm;
505       }
506     }
507 }
508 
normalize_sift_way(float * desc,const int _descriptor_size)509 static void normalize_sift_way( float* desc, const int _descriptor_size )
510 {
511     int h;
512     int iter = 0;
513     bool changed = true;
514     while( changed && iter < MAX_NORMALIZATION_ITER )
515     {
516       iter++;
517       changed = false;
518 
519       double sum = 0.0f;
520       for( int i=0; i<_descriptor_size; i++ )
521       {
522           sum += desc[i] * desc[i];
523       }
524 
525       float norm = (float)sqrt( sum );
526 
527       if( norm > 1e-5 )
528       // divide with norm
529       for( int i=0; i<_descriptor_size; i++ )
530       {
531           desc[i] /= norm;
532       }
533 
534       for( h=0; h<_descriptor_size; h++ )
535       {  // sift magical number
536          if( desc[ h ] > 0.154f )
537          {
538             desc[ h ] = 0.154f;
539             changed = true;
540          }
541       }
542     }
543 }
544 
normalize_full(float * desc,const int _descriptor_size)545 static void normalize_full( float* desc, const int _descriptor_size )
546 {
547     // l2 norm
548     double sum = 0.0f;
549     for( int i=0; i<_descriptor_size; i++ )
550     {
551         sum += desc[i] * desc[i];
552     }
553 
554     float norm = (float)sqrt( sum );
555 
556     if( norm != 0.0 )
557     // divide with norm
558     for( int i=0; i<_descriptor_size; i++ )
559     {
560         desc[i] /= norm;
561     }
562 }
563 
normalize_descriptor(float * desc,const DAISY::NormalizationType nrm_type,const int _grid_point_number,const int _hist_th_q_no,const int _descriptor_size)564 static void normalize_descriptor( float* desc, const DAISY::NormalizationType nrm_type, const int _grid_point_number,
565                                   const int _hist_th_q_no, const int _descriptor_size  )
566 {
567     if( nrm_type == DAISY::NRM_NONE ) return;
568     else if( nrm_type == DAISY::NRM_PARTIAL ) normalize_partial(desc,_grid_point_number,_hist_th_q_no);
569     else if( nrm_type == DAISY::NRM_FULL    ) normalize_full(desc,_descriptor_size);
570     else if( nrm_type == DAISY::NRM_SIFT    ) normalize_sift_way(desc,_descriptor_size);
571     else
572         CV_Error( Error::StsInternal, "No such normalization" );
573 }
574 
ni_get_histogram(float * histogram,const int y,const int x,const int shift,const Mat * hcube)575 static void ni_get_histogram( float* histogram, const int y, const int x, const int shift, const Mat* hcube )
576 {
577 
578     if ( ! Point( x, y ).inside(
579            Rect( 0, 0, hcube->size[1]-1, hcube->size[0]-1 ) )
580        ) return;
581 
582     int _hist_th_q_no = hcube->size[2];
583     const float* hptr = hcube->ptr<float>(y,x,0);
584     for( int h=0; h<_hist_th_q_no; h++ )
585     {
586       int hi = h+shift;
587       if( hi >= _hist_th_q_no ) hi -= _hist_th_q_no;
588       histogram[h] = hptr[hi];
589     }
590 }
591 
bi_get_histogram(float * histogram,const double y,const double x,const int shift,const Mat * hcube)592 static void bi_get_histogram( float* histogram, const double y, const double x, const int shift, const Mat* hcube )
593 {
594     int mnx = int( x );
595     int mny = int( y );
596     int _hist_th_q_no = hcube->size[2];
597     if( mnx >= hcube->size[1]-2  || mny >= hcube->size[0]-2 )
598     {
599       memset(histogram, 0, sizeof(float)*_hist_th_q_no);
600       return;
601     }
602 
603     // A C --> pixel positions
604     // B D
605     const float* A = hcube->ptr<float>( mny   ,  mnx   , 0);
606     const float* B = hcube->ptr<float>((mny+1),  mnx   , 0);
607     const float* C = hcube->ptr<float>( mny   , (mnx+1), 0);
608     const float* D = hcube->ptr<float>((mny+1), (mnx+1), 0);
609 
610     double alpha = mnx+1-x;
611     double beta  = mny+1-y;
612 
613     float w0 = (float) ( alpha * beta );
614     float w1 = (float) ( beta - w0    );         // (1-alpha)*beta;
615     float w2 = (float) ( alpha - w0   );         // (1-beta)*alpha;
616     float w3 = (float) ( 1 + w0 - alpha - beta); // (1-beta)*(1-alpha);
617 
618     int h;
619 
620     for( h=0; h<_hist_th_q_no; h++ ) {
621       if( h+shift < _hist_th_q_no ) histogram[h] = w0 * A[h+shift];
622       else                          histogram[h] = w0 * A[h+shift-_hist_th_q_no];
623     }
624     for( h=0; h<_hist_th_q_no; h++ ) {
625       if( h+shift < _hist_th_q_no ) histogram[h] += w1 * C[h+shift];
626       else                          histogram[h] += w1 * C[h+shift-_hist_th_q_no];
627     }
628     for( h=0; h<_hist_th_q_no; h++ ) {
629       if( h+shift < _hist_th_q_no ) histogram[h] += w2 * B[h+shift];
630       else                          histogram[h] += w2 * B[h+shift-_hist_th_q_no];
631     }
632     for( h=0; h<_hist_th_q_no; h++ ) {
633       if( h+shift < _hist_th_q_no ) histogram[h] += w3 * D[h+shift];
634       else                          histogram[h] += w3 * D[h+shift-_hist_th_q_no];
635     }
636 }
637 
ti_get_histogram(float * histogram,const double y,const double x,const double shift,const Mat * hcube)638 static void ti_get_histogram( float* histogram, const double y, const double x, const double shift, const Mat* hcube )
639 {
640     int ishift = int( shift );
641     double layer_alpha  = shift - ishift;
642 
643     float thist[MAX_CUBE_NO];
644     bi_get_histogram( thist, y, x, ishift, hcube );
645 
646     int _hist_th_q_no = hcube->size[2];
647     for( int h=0; h<_hist_th_q_no-1; h++ )
648       histogram[h] = (float) ((1-layer_alpha)*thist[h]+layer_alpha*thist[h+1]);
649     histogram[_hist_th_q_no-1] = (float) ((1-layer_alpha)*thist[_hist_th_q_no-1]+layer_alpha*thist[0]);
650 }
651 
i_get_histogram(float * histogram,const double y,const double x,const double shift,const Mat * hcube)652 static void i_get_histogram( float* histogram, const double y, const double x, const double shift, const Mat* hcube )
653 {
654     int ishift = (int)shift;
655     double fshift = shift-ishift;
656     if     ( fshift < 0.01 ) bi_get_histogram( histogram, y, x, ishift  , hcube );
657     else if( fshift > 0.99 ) bi_get_histogram( histogram, y, x, ishift+1, hcube );
658     else                     ti_get_histogram( histogram, y, x,  shift  , hcube );
659 }
660 
ni_get_descriptor(const double y,const double x,const int orientation,float * descriptor,const std::vector<Mat> * layers,const Mat * _oriented_grid_points,const double * _orientation_shift_table,const int _th_q_no)661 static void ni_get_descriptor( const double y, const double x, const int orientation, float* descriptor, const std::vector<Mat>* layers,
662                                const Mat* _oriented_grid_points, const double* _orientation_shift_table, const int _th_q_no )
663 {
664     CV_Assert( y >= 0 && y < layers->at(0).size[0] );
665     CV_Assert( x >= 0 && x < layers->at(0).size[1] );
666     CV_Assert( orientation >= 0 && orientation < 360 );
667     CV_Assert( !layers->empty() );
668     CV_Assert( !_oriented_grid_points->empty() );
669     CV_Assert( descriptor != NULL );
670 
671     int _rad_q_no = (int) layers->size();
672     int _hist_th_q_no = layers->at(0).size[2];
673     double shift = _orientation_shift_table[orientation];
674     int ishift = (int)shift;
675     if( shift - ishift > 0.5  ) ishift++;
676 
677     int iy = (int)y; if( y - iy > 0.5 ) iy++;
678     int ix = (int)x; if( x - ix > 0.5 ) ix++;
679 
680     // center
681     ni_get_histogram( descriptor, iy, ix, ishift, &layers->at(g_selected_cubes[0]) );
682 
683     double yy, xx;
684     float* histogram=0;
685     // petals of the flower
686     int r, rdt, region;
687     Mat grid = _oriented_grid_points->row( orientation );
688     for( r=0; r<_rad_q_no; r++ )
689     {
690       rdt = r*_th_q_no+1;
691       for( region=rdt; region<rdt+_th_q_no; region++ )
692       {
693          yy = y + grid.at<double>(2*region  );
694          xx = x + grid.at<double>(2*region+1);
695          iy = (int)yy; if( yy - iy > 0.5 ) iy++;
696          ix = (int)xx; if( xx - ix > 0.5 ) ix++;
697 
698          if ( ! Point2f( (float)xx, (float)yy ).inside(
699                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
700             ) continue;
701 
702          histogram = descriptor + region*_hist_th_q_no;
703          ni_get_histogram( histogram, iy, ix, ishift, &layers->at(g_selected_cubes[r]) );
704       }
705     }
706 }
707 
i_get_descriptor(const double y,const double x,const int orientation,float * descriptor,const std::vector<Mat> * layers,const Mat * _oriented_grid_points,const double * _orientation_shift_table,const int _th_q_no)708 static void i_get_descriptor( const double y, const double x, const int orientation, float* descriptor, const std::vector<Mat>* layers,
709                               const Mat* _oriented_grid_points, const double *_orientation_shift_table, const int _th_q_no )
710 {
711     CV_Assert( y >= 0 && y < layers->at(0).size[0] );
712     CV_Assert( x >= 0 && x < layers->at(0).size[1] );
713     CV_Assert( orientation >= 0 && orientation < 360 );
714     CV_Assert( !layers->empty() );
715     CV_Assert( !_oriented_grid_points->empty() );
716     CV_Assert( descriptor != NULL );
717 
718     int _rad_q_no = (int) layers->size();
719     int _hist_th_q_no = layers->at(0).size[2];
720     double shift = _orientation_shift_table[orientation];
721 
722     i_get_histogram( descriptor, y, x, shift, &layers->at(g_selected_cubes[0]) );
723 
724     int r, rdt, region;
725     double yy, xx;
726     float* histogram = 0;
727 
728     Mat grid = _oriented_grid_points->row( orientation );
729 
730     // petals of the flower
731     for( r=0; r<_rad_q_no; r++ )
732     {
733       rdt  = r*_th_q_no+1;
734       for( region=rdt; region<rdt+_th_q_no; region++ )
735       {
736          yy = y + grid.at<double>(2*region    );
737          xx = x + grid.at<double>(2*region + 1);
738 
739          if ( ! Point2f( (float)xx, (float)yy ).inside(
740                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
741             ) continue;
742 
743          histogram = descriptor + region*_hist_th_q_no;
744          i_get_histogram( histogram, yy, xx, shift, &layers->at(r) );
745       }
746     }
747 }
748 
ni_get_descriptor_h(const double y,const double x,const int orientation,double * H,float * descriptor,const std::vector<Mat> * layers,const Mat & _cube_sigmas,const Mat * _grid_points,const double * _orientation_shift_table,const int _th_q_no)749 static bool ni_get_descriptor_h( const double y, const double x, const int orientation, double* H, float* descriptor, const std::vector<Mat>* layers,
750                                  const Mat& _cube_sigmas, const Mat* _grid_points, const double* _orientation_shift_table, const int _th_q_no )
751 {
752     CV_Assert( orientation >= 0 && orientation < 360 );
753     CV_Assert( !layers->empty() );
754     CV_Assert( descriptor != NULL );
755 
756     int hradius[MAX_CUBE_NO];
757 
758     double hy, hx, ry, rx;
759 
760     pt_H(H, x, y, hx, hy );
761 
762     if ( ! Point2f( (float)hx, (float)hy ).inside(
763                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
764        ) return false;
765 
766     int _rad_q_no = (int) layers->size();
767     int _hist_th_q_no = layers->at(0).size[2];
768     double shift = _orientation_shift_table[orientation];
769     int  ishift = (int)shift; if( shift - ishift > 0.5  ) ishift++;
770 
771     pt_H(H, x+_cube_sigmas.at<double>(g_selected_cubes[0]), y, rx, ry);
772     double d0 = rx - hx; double d1 = ry - hy;
773     double radius = sqrt( d0*d0 + d1*d1 );
774     hradius[0] = quantize_radius( (float) radius, _rad_q_no, _cube_sigmas );
775 
776     int ihx = (int)hx; if( hx - ihx > 0.5 ) ihx++;
777     int ihy = (int)hy; if( hy - ihy > 0.5 ) ihy++;
778 
779     int r, rdt, th, region;
780     double gy, gx;
781     float* histogram=0;
782     ni_get_histogram( descriptor, ihy, ihx, ishift, &layers->at(hradius[0]) );
783     for( r=0; r<_rad_q_no; r++)
784     {
785       rdt = r*_th_q_no + 1;
786       for( th=0; th<_th_q_no; th++ )
787       {
788          region = rdt + th;
789 
790          gy = y + _grid_points->at<double>(region,0);
791          gx = x + _grid_points->at<double>(region,1);
792 
793          pt_H(H, gx, gy, hx, hy);
794          if( th == 0 )
795          {
796             pt_H(H, gx+_cube_sigmas.at<double>(g_selected_cubes[r]), gy, rx, ry);
797             d0 = rx - hx; d1 = ry - hy;
798             radius = sqrt( d0*d0 + d1*d1 );
799             hradius[r] = quantize_radius( (float) radius, _rad_q_no, _cube_sigmas );
800          }
801 
802          ihx = (int)hx; if( hx - ihx > 0.5 ) ihx++;
803          ihy = (int)hy; if( hy - ihy > 0.5 ) ihy++;
804 
805          if ( ! Point( ihx, ihy ).inside(
806                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
807             ) continue;
808 
809          histogram = descriptor + region*_hist_th_q_no;
810          ni_get_histogram( histogram, ihy, ihx, ishift, &layers->at(hradius[r]) );
811       }
812     }
813     return true;
814 }
815 
i_get_descriptor_h(const double y,const double x,const int orientation,double * H,float * descriptor,const std::vector<Mat> * layers,const Mat _cube_sigmas,const Mat * _grid_points,const double * _orientation_shift_table,const int _th_q_no)816 static bool i_get_descriptor_h( const double y, const double x, const int orientation, double* H, float* descriptor, const std::vector<Mat>* layers,
817                                 const Mat _cube_sigmas, const Mat* _grid_points, const double* _orientation_shift_table, const int _th_q_no )
818 {
819     CV_Assert( orientation >= 0 && orientation < 360 );
820     CV_Assert( !layers->empty() );
821     CV_Assert( descriptor != NULL );
822 
823     int hradius[MAX_CUBE_NO];
824 
825     double hy, hx, ry, rx;
826     pt_H( H, x, y, hx, hy );
827 
828     if ( ! Point2f( (float)hx, (float)hy ).inside(
829                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
830        ) return false;
831 
832     int _rad_q_no = (int) layers->size();
833     int _hist_th_q_no = layers->at(0).size[0];
834     pt_H( H, x+_cube_sigmas.at<double>(g_selected_cubes[0]), y, rx, ry);
835     double d0 = rx - hx; double d1 = ry - hy;
836     double radius = sqrt( d0*d0 + d1*d1 );
837     hradius[0] = quantize_radius( (float) radius, _rad_q_no, _cube_sigmas );
838 
839     double shift = _orientation_shift_table[orientation];
840     i_get_histogram( descriptor, hy, hx, shift, &layers->at(hradius[0]) );
841 
842     double gy, gx;
843     int r, rdt, th, region;
844     float* histogram=0;
845     for( r=0; r<_rad_q_no; r++)
846     {
847       rdt = r*_th_q_no + 1;
848       for( th=0; th<_th_q_no; th++ )
849       {
850          region = rdt + th;
851 
852          gy = y + _grid_points->at<double>(region,0);
853          gx = x + _grid_points->at<double>(region,1);
854 
855          pt_H(H, gx, gy, hx, hy);
856          if( th == 0 )
857          {
858             pt_H(H, gx+_cube_sigmas.at<double>(g_selected_cubes[r]), gy, rx, ry);
859             d0 = rx - hx; d1 = ry - hy;
860             radius = sqrt( d0*d0 + d1*d1 );
861             hradius[r] = quantize_radius( (float) radius, _rad_q_no, _cube_sigmas );
862          }
863 
864          if ( ! Point2f( (float)hx, (float)hy ).inside(
865                 Rect( 0, 0, layers->at(0).size[1]-1, layers->at(0).size[0]-1 ) )
866             ) continue;
867 
868          histogram = descriptor + region*_hist_th_q_no;
869          i_get_histogram( histogram, hy, hx, shift, &layers->at(hradius[r]) );
870       }
871     }
872     return true;
873 }
874 
get_unnormalized_descriptor(const double y,const double x,const int orientation,float * descriptor,const std::vector<Mat> * m_smoothed_gradient_layers,const Mat * m_oriented_grid_points,const double * m_orientation_shift_table,const int m_th_q_no,const bool m_enable_interpolation)875 static void get_unnormalized_descriptor( const double y, const double x, const int orientation, float* descriptor,
876             const std::vector<Mat>* m_smoothed_gradient_layers, const Mat* m_oriented_grid_points,
877             const double* m_orientation_shift_table, const int m_th_q_no, const bool m_enable_interpolation )
878 {
879     if( m_enable_interpolation )
880       i_get_descriptor( y, x, orientation, descriptor, m_smoothed_gradient_layers,
881                         m_oriented_grid_points, m_orientation_shift_table, m_th_q_no );
882     else
883      ni_get_descriptor( y, x, orientation, descriptor, m_smoothed_gradient_layers,
884                         m_oriented_grid_points, m_orientation_shift_table, m_th_q_no);
885 }
886 
get_descriptor(const double y,const double x,const int orientation,float * descriptor,const std::vector<Mat> * m_smoothed_gradient_layers,const Mat * m_oriented_grid_points,const double * m_orientation_shift_table,const int m_th_q_no,const int m_hist_th_q_no,const int m_grid_point_number,const int m_descriptor_size,const bool m_enable_interpolation,const DAISY::NormalizationType m_nrm_type)887 static void get_descriptor( const double y, const double x, const int orientation, float* descriptor,
888             const std::vector<Mat>* m_smoothed_gradient_layers, const Mat* m_oriented_grid_points,
889             const double* m_orientation_shift_table, const int m_th_q_no, const int m_hist_th_q_no,
890             const int m_grid_point_number, const int m_descriptor_size, const bool m_enable_interpolation,
891             const DAISY::NormalizationType m_nrm_type)
892 {
893     get_unnormalized_descriptor( y, x, orientation, descriptor, m_smoothed_gradient_layers,
894                                  m_oriented_grid_points, m_orientation_shift_table, m_th_q_no, m_enable_interpolation );
895     normalize_descriptor( descriptor, m_nrm_type, m_grid_point_number, m_hist_th_q_no, m_descriptor_size );
896 }
897 
get_unnormalized_descriptor_h(const double y,const double x,const int orientation,float * descriptor,double * H,const std::vector<Mat> * m_smoothed_gradient_layers,const Mat & m_cube_sigmas,const Mat * m_grid_points,const double * m_orientation_shift_table,const int m_th_q_no,const bool m_enable_interpolation)898 static bool get_unnormalized_descriptor_h( const double y, const double x, const int orientation, float* descriptor, double* H,
899             const std::vector<Mat>* m_smoothed_gradient_layers, const Mat& m_cube_sigmas,
900             const Mat* m_grid_points, const double* m_orientation_shift_table, const int m_th_q_no, const bool m_enable_interpolation )
901 
902 {
903     if( m_enable_interpolation )
904       return  i_get_descriptor_h( y, x, orientation, H, descriptor, m_smoothed_gradient_layers, m_cube_sigmas,
905                                   m_grid_points, m_orientation_shift_table, m_th_q_no );
906     else
907       return ni_get_descriptor_h( y, x, orientation, H, descriptor, m_smoothed_gradient_layers, m_cube_sigmas,
908                                   m_grid_points, m_orientation_shift_table, m_th_q_no );
909 }
910 
get_descriptor_h(const double y,const double x,const int orientation,float * descriptor,double * H,const std::vector<Mat> * m_smoothed_gradient_layers,const Mat & m_cube_sigmas,const Mat * m_grid_points,const double * m_orientation_shift_table,const int m_th_q_no,const int m_hist_th_q_no,const int m_grid_point_number,const int m_descriptor_size,const bool m_enable_interpolation,const DAISY::NormalizationType m_nrm_type)911 static bool get_descriptor_h( const double y, const double x, const int orientation, float* descriptor, double* H,
912             const std::vector<Mat>* m_smoothed_gradient_layers, const Mat& m_cube_sigmas,
913             const Mat* m_grid_points, const double* m_orientation_shift_table, const int m_th_q_no,
914             const int m_hist_th_q_no, const int m_grid_point_number, const int m_descriptor_size,
915             const bool m_enable_interpolation, const DAISY::NormalizationType m_nrm_type)
916 
917 {
918     bool rval =
919       get_unnormalized_descriptor_h( y, x, orientation, descriptor, H, m_smoothed_gradient_layers, m_cube_sigmas,
920                                    m_grid_points, m_orientation_shift_table, m_th_q_no, m_enable_interpolation );
921 
922     if( rval )
923       normalize_descriptor( descriptor, m_nrm_type, m_grid_point_number, m_hist_th_q_no, m_descriptor_size );
924 
925     return rval;
926 }
927 
GetDescriptor(double y,double x,int orientation,float * descriptor) const928 void DAISY_Impl::GetDescriptor( double y, double x, int orientation, float* descriptor ) const
929 {
930     get_descriptor( y, x, orientation, descriptor, &m_smoothed_gradient_layers,
931                     &m_oriented_grid_points, m_orientation_shift_table, m_th_q_no,
932                     m_hist_th_q_no, m_grid_point_number, m_descriptor_size, m_enable_interpolation,
933                     m_nrm_type );
934 }
935 
GetDescriptor(double y,double x,int orientation,float * descriptor,double * H) const936 bool DAISY_Impl::GetDescriptor( double y, double x, int orientation, float* descriptor, double* H ) const
937 {
938   return
939   get_descriptor_h( y, x, orientation, descriptor, H, &m_smoothed_gradient_layers,
940                     m_cube_sigmas, &m_grid_points, m_orientation_shift_table, m_th_q_no,
941                     m_hist_th_q_no, m_grid_point_number, m_descriptor_size, m_enable_interpolation,
942                     m_nrm_type );
943 }
944 
GetUnnormalizedDescriptor(double y,double x,int orientation,float * descriptor) const945 void DAISY_Impl::GetUnnormalizedDescriptor( double y, double x, int orientation, float* descriptor ) const
946 {
947     get_unnormalized_descriptor( y, x, orientation, descriptor, &m_smoothed_gradient_layers,
948                                  &m_oriented_grid_points, m_orientation_shift_table, m_th_q_no,
949                                  m_enable_interpolation );
950 }
951 
GetUnnormalizedDescriptor(double y,double x,int orientation,float * descriptor,double * H) const952 bool DAISY_Impl::GetUnnormalizedDescriptor( double y, double x, int orientation, float* descriptor, double* H ) const
953 {
954   return
955   get_unnormalized_descriptor_h( y, x, orientation, descriptor, H, &m_smoothed_gradient_layers,
956                                  m_cube_sigmas, &m_grid_points, m_orientation_shift_table, m_th_q_no,
957                                  m_enable_interpolation );
958 }
959 
compute_grid_points()960 inline void DAISY_Impl::compute_grid_points()
961 {
962     double r_step = m_rad / (double)m_rad_q_no;
963     double t_step = 2*CV_PI / m_th_q_no;
964 
965     m_grid_points.release();
966     m_grid_points = Mat( m_grid_point_number, 2, CV_64F );
967 
968     for( int y=0; y<m_grid_point_number; y++ )
969     {
970       m_grid_points.at<double>(y,0) = 0;
971       m_grid_points.at<double>(y,1) = 0;
972     }
973 
974     for( int r=0; r<m_rad_q_no; r++ )
975     {
976       int region = r*m_th_q_no+1;
977       for( int t=0; t<m_th_q_no; t++ )
978       {
979          m_grid_points.at<double>(region+t,0) = (r+1)*r_step * sin( t*t_step );
980          m_grid_points.at<double>(region+t,1) = (r+1)*r_step * cos( t*t_step );
981       }
982     }
983 
984     compute_oriented_grid_points();
985 }
986 
987 struct ComputeDescriptorsInvoker : ParallelLoopBody
988 {
ComputeDescriptorsInvokercv::xfeatures2d::ComputeDescriptorsInvoker989     ComputeDescriptorsInvoker( Mat* _descriptors, Mat* _image, Rect* _roi,
990                                std::vector<Mat>* _layers, Mat* _orientation_map,
991                                Mat* _oriented_grid_points, double* _orientation_shift_table,
992                                int _th_q_no, bool _enable_interpolation )
993     {
994       x_off = _roi->x;
995       x_end = _roi->x + _roi->width;
996       image = _image;
997       layers = _layers;
998       th_q_no = _th_q_no;
999       descriptors = _descriptors;
1000       orientation_map = _orientation_map;
1001       enable_interpolation = _enable_interpolation;
1002       oriented_grid_points = _oriented_grid_points;
1003       orientation_shift_table = _orientation_shift_table;
1004     }
1005 
operator ()cv::xfeatures2d::ComputeDescriptorsInvoker1006     void operator ()(const cv::Range& range) const CV_OVERRIDE
1007     {
1008       int index, orientation;
1009       for (int y = range.start; y < range.end; ++y)
1010       {
1011         for( int x = x_off; x < x_end; x++ )
1012         {
1013           index = y*image->cols + x;
1014           orientation = 0;
1015           if( !orientation_map->empty() )
1016               orientation = (int) orientation_map->at<ushort>( y, x );
1017           if( !( orientation >= 0 && orientation < g_grid_orientation_resolution ) )
1018               orientation = 0;
1019           get_unnormalized_descriptor( y, x, orientation, descriptors->ptr<float>( index ),
1020                                        layers, oriented_grid_points, orientation_shift_table,
1021                                        th_q_no, enable_interpolation );
1022         }
1023       }
1024     }
1025 
1026     int th_q_no;
1027     int x_off, x_end;
1028     std::vector<Mat>* layers;
1029     Mat *descriptors;
1030     Mat *orientation_map;
1031     bool enable_interpolation;
1032     double* orientation_shift_table;
1033     Mat *image, *oriented_grid_points;
1034 };
1035 
1036 // Computes the descriptor by sampling convoluted orientation maps.
compute_descriptors(Mat * m_dense_descriptors)1037 inline void DAISY_Impl::compute_descriptors( Mat* m_dense_descriptors )
1038 {
1039     int y_off = m_roi.y;
1040     int y_end = m_roi.y + m_roi.height;
1041 
1042     if( m_scale_invariant    ) compute_scales();
1043     if( m_rotation_invariant ) compute_orientations();
1044 
1045     m_dense_descriptors->setTo( Scalar(0) );
1046 
1047     parallel_for_( Range(y_off, y_end),
1048         ComputeDescriptorsInvoker( m_dense_descriptors, &m_image, &m_roi, &m_smoothed_gradient_layers,
1049                                    &m_orientation_map, &m_oriented_grid_points, m_orientation_shift_table,
1050                                    m_th_q_no, m_enable_interpolation )
1051     );
1052 
1053 }
1054 
1055 struct NormalizeDescriptorsInvoker : ParallelLoopBody
1056 {
NormalizeDescriptorsInvokercv::xfeatures2d::NormalizeDescriptorsInvoker1057     NormalizeDescriptorsInvoker( Mat* _descriptors, DAISY::NormalizationType _nrm_type, int _grid_point_number,
1058                                  int _hist_th_q_no, int _descriptor_size )
1059     {
1060       descriptors = _descriptors;
1061       nrm_type = _nrm_type;
1062       grid_point_number = _grid_point_number;
1063       hist_th_q_no = _hist_th_q_no;
1064       descriptor_size = _descriptor_size;
1065     }
1066 
operator ()cv::xfeatures2d::NormalizeDescriptorsInvoker1067     void operator ()(const cv::Range& range) const CV_OVERRIDE
1068     {
1069       for (int d = range.start; d < range.end; ++d)
1070       {
1071         normalize_descriptor( descriptors->ptr<float>(d), nrm_type,
1072                               grid_point_number, hist_th_q_no, descriptor_size );
1073       }
1074     }
1075 
1076     Mat *descriptors;
1077     DAISY::NormalizationType nrm_type;
1078     int grid_point_number;
1079     int hist_th_q_no;
1080     int descriptor_size;
1081 };
1082 
normalize_descriptors(Mat * m_dense_descriptors)1083 inline void DAISY_Impl::normalize_descriptors( Mat* m_dense_descriptors )
1084 {
1085     CV_Assert( !m_dense_descriptors->empty() );
1086     int number_of_descriptors =  m_roi.width * m_roi.height;
1087 
1088     parallel_for_( Range(0, number_of_descriptors),
1089         NormalizeDescriptorsInvoker( m_dense_descriptors, m_nrm_type, m_grid_point_number, m_hist_th_q_no, m_descriptor_size )
1090     );
1091 }
1092 
initialize()1093 inline void DAISY_Impl::initialize()
1094 {
1095     // no image ?
1096     CV_Assert(m_image.rows != 0);
1097     CV_Assert(m_image.cols != 0);
1098 
1099     // (m_rad_q_no + 1) cubes
1100     // 3 dims tensor (idhist, img_y, img_x);
1101     m_smoothed_gradient_layers.resize( m_rad_q_no + 1 );
1102 
1103     int dims[3] = { m_hist_th_q_no, m_image.rows, m_image.cols };
1104     for ( int c=0; c<=m_rad_q_no; c++)
1105       m_smoothed_gradient_layers[c] = Mat( 3, dims, CV_32F );
1106 
1107     layered_gradient( m_image, &m_smoothed_gradient_layers[0] );
1108 
1109     // assuming a 0.5 image smoothness, we pull this to 1.6 as in sift
1110     smooth_layers( &m_smoothed_gradient_layers[0], (float)sqrt(g_sigma_init*g_sigma_init-0.25f) );
1111 
1112 }
1113 
compute_cube_sigmas()1114 inline void DAISY_Impl::compute_cube_sigmas()
1115 {
1116     if( m_cube_sigmas.empty() )
1117     {
1118 
1119       m_cube_sigmas = Mat(1, m_rad_q_no, CV_64F);
1120 
1121       double r_step = (double)m_rad / m_rad_q_no / 2;
1122       for( int r=0; r<m_rad_q_no; r++ )
1123       {
1124         m_cube_sigmas.at<double>(r) = (r+1) * r_step;
1125       }
1126     }
1127     update_selected_cubes();
1128 }
1129 
update_selected_cubes()1130 inline void DAISY_Impl::update_selected_cubes()
1131 {
1132     double scale = m_rad/m_rad_q_no/2.0;
1133     for( int r=0; r<m_rad_q_no; r++ )
1134     {
1135       double seed_sigma = ((double)r+1) * scale;
1136       g_selected_cubes[r] = quantize_radius( (float)seed_sigma, m_rad_q_no, m_cube_sigmas );
1137     }
1138 }
1139 
1140 struct ComputeHistogramsInvoker : ParallelLoopBody
1141 {
ComputeHistogramsInvokercv::xfeatures2d::ComputeHistogramsInvoker1142     ComputeHistogramsInvoker( std::vector<Mat>* _layers, int _r )
1143     {
1144       r = _r;
1145       layers = _layers;
1146       _hist_th_q_no = layers->at(r).size[2];
1147     }
1148 
operator ()cv::xfeatures2d::ComputeHistogramsInvoker1149     void operator ()(const cv::Range& range) const CV_OVERRIDE
1150     {
1151       for (int y = range.start; y < range.end; ++y)
1152       {
1153         for( int x = 0; x < layers->at(r).size[1]; x++ )
1154         {
1155           float* hist = layers->at(r).ptr<float>(y,x,0);
1156           for( int h = 0; h < _hist_th_q_no; h++ )
1157           {
1158             hist[h] = layers->at(r+1).at<float>(h,y,x);
1159           }
1160         }
1161       }
1162     }
1163 
1164     int r, _hist_th_q_no;
1165     std::vector<Mat> *layers;
1166 };
1167 
compute_histograms()1168 inline void DAISY_Impl::compute_histograms()
1169 {
1170     for( int r=0; r<m_rad_q_no; r++ )
1171     {
1172       // remap cubes from Mat(h,y,x) -> Mat(y,x,h)
1173       // final sampling is speeded up by aligned h dim
1174       int m_h = m_smoothed_gradient_layers.at(r).size[0];
1175       int m_y = m_smoothed_gradient_layers.at(r).size[1];
1176       int m_x = m_smoothed_gradient_layers.at(r).size[2];
1177 
1178       // empty targeted cube
1179       m_smoothed_gradient_layers.at(r).release();
1180 
1181       // recreate cube space
1182       int dims[3] = { m_y, m_x, m_h };
1183       m_smoothed_gradient_layers.at(r) = Mat( 3, dims, CV_32F );
1184 
1185       // copy backward all cubes and realign structure
1186       parallel_for_( Range(0, m_image.rows), ComputeHistogramsInvoker( &m_smoothed_gradient_layers, r ) );
1187     }
1188     // trim unused region from collection of cubes
1189     m_smoothed_gradient_layers[m_rad_q_no].release();
1190     m_smoothed_gradient_layers.pop_back();
1191 }
1192 
compute_smoothed_gradient_layers()1193 inline void DAISY_Impl::compute_smoothed_gradient_layers()
1194 {
1195     double sigma;
1196     for( int r=0; r<m_rad_q_no; r++ )
1197     {
1198       // incremental smoothing
1199       if( r == 0 )
1200         sigma = m_cube_sigmas.at<double>(0);
1201       else
1202         sigma = sqrt( m_cube_sigmas.at<double>(r  ) * m_cube_sigmas.at<double>(r  )
1203                     - m_cube_sigmas.at<double>(r-1) * m_cube_sigmas.at<double>(r-1) );
1204 
1205       int ks = filter_size( sigma, 5.0f );
1206 
1207       for( int th=0; th<m_hist_th_q_no; th++ )
1208       {
1209         Mat cvI( m_image.rows, m_image.cols, CV_32F, m_smoothed_gradient_layers[r  ].ptr<float>(th,0,0) );
1210         Mat cvO( m_image.rows, m_image.cols, CV_32F, m_smoothed_gradient_layers[r+1].ptr<float>(th,0,0) );
1211         GaussianBlur( cvI, cvO, Size(ks, ks), sigma, sigma, BORDER_REPLICATE );
1212       }
1213     }
1214     compute_histograms();
1215 }
1216 
compute_oriented_grid_points()1217 inline void DAISY_Impl::compute_oriented_grid_points()
1218 {
1219     m_oriented_grid_points =
1220         Mat( g_grid_orientation_resolution, m_grid_point_number*2, CV_64F );
1221 
1222     for( int i=0; i<g_grid_orientation_resolution; i++ )
1223     {
1224       double angle = -i*2.0*CV_PI/g_grid_orientation_resolution;
1225 
1226       double kos = cos( angle );
1227       double zin = sin( angle );
1228 
1229       Mat point_list = m_oriented_grid_points.row( i );
1230 
1231       for( int k=0; k<m_grid_point_number; k++ )
1232       {
1233          double y = m_grid_points.at<double>(k,0);
1234          double x = m_grid_points.at<double>(k,1);
1235 
1236          point_list.at<double>(2*k+1) =  x*kos + y*zin; // x
1237          point_list.at<double>(2*k  ) = -x*zin + y*kos; // y
1238       }
1239     }
1240 }
1241 
1242 struct MaxDoGInvoker : ParallelLoopBody
1243 {
MaxDoGInvokercv::xfeatures2d::MaxDoGInvoker1244     MaxDoGInvoker( Mat* _next_sim, Mat* _sim, Mat* _max_dog, Mat* _scale_map, int _i, int _r )
1245     {
1246       i = _i;
1247       r = _r;
1248       sim = _sim;
1249       max_dog = _max_dog;
1250       next_sim = _next_sim;
1251       scale_map = _scale_map;
1252     }
1253 
operator ()cv::xfeatures2d::MaxDoGInvoker1254     void operator ()(const cv::Range& range) const CV_OVERRIDE
1255     {
1256       for (int c = range.start; c < range.end; ++c)
1257       {
1258         float dog = (float) fabs( next_sim->at<float>(r,c) - sim->at<float>(r,c) );
1259         if( dog > max_dog->at<float>(r,c) )
1260         {
1261           max_dog->at<float>(r,c) = dog;
1262           scale_map->at<float>(r,c) = (float) i;
1263         }
1264       }
1265     }
1266     int i, r;
1267     Mat* max_dog;
1268     Mat* scale_map;
1269     Mat *sim, *next_sim;
1270 };
1271 
1272 struct RoundingInvoker : ParallelLoopBody
1273 {
RoundingInvokercv::xfeatures2d::RoundingInvoker1274     RoundingInvoker( Mat* _scale_map, int _r )
1275     {
1276       r = _r;
1277       scale_map = _scale_map;
1278     }
1279 
operator ()cv::xfeatures2d::RoundingInvoker1280     void operator ()(const cv::Range& range) const CV_OVERRIDE
1281     {
1282       for (int c = range.start; c < range.end; ++c)
1283       {
1284         scale_map->at<float>(r,c) = (float) cvRound( scale_map->at<float>(r,c) );
1285       }
1286     }
1287     int r;
1288     Mat* scale_map;
1289 };
1290 
compute_scales()1291 inline void DAISY_Impl::compute_scales()
1292 {
1293     //###############################################################################
1294     //# scale detection is work-in-progress! do not use it if you're not Engin Tola #
1295     //###############################################################################
1296 
1297     Mat sim, next_sim;
1298     float sigma = (float) ( pow( g_sigma_step, g_scale_st)*g_sigma_0 );
1299 
1300     int ks = filter_size( sigma, 3.0f );
1301     GaussianBlur( m_image, sim, Size(ks, ks), sigma, sigma, BORDER_REPLICATE );
1302 
1303     Mat max_dog( m_image.rows, m_image.cols, CV_32F, Scalar(0) );
1304     m_scale_map = Mat( m_image.rows, m_image.cols, CV_32F, Scalar(0) );
1305 
1306 
1307     float sigma_prev;
1308     float sigma_new;
1309     float sigma_inc;
1310 
1311     sigma_prev = (float) g_sigma_0;
1312     for( int i=0; i<g_scale_en; i++ )
1313     {
1314       sigma_new  = (float) ( pow( g_sigma_step, g_scale_st + i  ) * g_sigma_0 );
1315       sigma_inc  = sqrt( sigma_new*sigma_new - sigma_prev*sigma_prev );
1316       sigma_prev = sigma_new;
1317 
1318       ks = filter_size( sigma_inc, 3.0f );
1319 
1320       GaussianBlur( sim, next_sim, Size(ks, ks), sigma_inc, sigma_inc, BORDER_REPLICATE );
1321 
1322       for( int r=0; r<m_image.rows; r++ )
1323       {
1324         parallel_for_( Range(0, m_image.cols), MaxDoGInvoker( &next_sim, &sim, &max_dog, &m_scale_map, i, r ) );
1325       }
1326       sim.release();
1327       sim = next_sim;
1328     }
1329 
1330     ks = filter_size( 10.0f, 3.0f );
1331     GaussianBlur( m_scale_map, m_scale_map, Size(ks, ks), 10.0f, 10.0f, BORDER_REPLICATE );
1332 
1333     for( int r=0; r<m_image.rows; r++ )
1334     {
1335       parallel_for_( Range(0, m_image.cols), RoundingInvoker( &m_scale_map, r ) );
1336     }
1337 }
1338 
1339 
compute_orientations()1340 inline void DAISY_Impl::compute_orientations()
1341 {
1342     //#####################################################################################
1343     //# orientation detection is work-in-progress! do not use it if you're not Engin Tola #
1344     //#####################################################################################
1345 
1346     CV_Assert( !m_image.empty() );
1347 
1348     int dims[4] = { 1, m_orientation_resolution, m_image.rows, m_image.cols };
1349     Mat rotation_layers(4, dims, CV_32F);
1350     layered_gradient( m_image, &rotation_layers );
1351 
1352     m_orientation_map = Mat(m_image.rows, m_image.cols, CV_16U, Scalar(0));
1353 
1354     int ori, max_ind;
1355     float max_val;
1356 
1357     int next, prev;
1358     float peak, angle;
1359 
1360     int x, y, kk;
1361 
1362     Mat hist;
1363 
1364     float sigma_inc;
1365     float sigma_prev = 0.0f;
1366     float sigma_new;
1367 
1368     for( int scale=0; scale<g_scale_en; scale++ )
1369     {
1370 
1371       sigma_new  = (float)( pow( g_sigma_step, scale  ) * m_rad / 3.0f );
1372       sigma_inc  = sqrt( sigma_new*sigma_new - sigma_prev*sigma_prev );
1373       sigma_prev = sigma_new;
1374 
1375       smooth_layers( &rotation_layers, sigma_inc );
1376 
1377       for( y=0; y<m_image.rows; y ++ )
1378       {
1379          hist = Mat(1, m_orientation_resolution, CV_32F);
1380 
1381          for( x=0; x<m_image.cols; x++ )
1382          {
1383             if( m_scale_invariant && m_scale_map.at<float>(y,x) != scale ) continue;
1384 
1385             for (ori = 0; ori < m_orientation_resolution; ori++)
1386             {
1387               hist.at<float>(ori) = rotation_layers.at<float>(ori, y, x);
1388             }
1389             for( kk=0; kk<6; kk++ )
1390                smooth_histogram( &hist, m_orientation_resolution );
1391 
1392             max_val = -1;
1393             max_ind =  0;
1394             for( ori=0; ori<m_orientation_resolution; ori++ )
1395             {
1396                if( hist.at<float>(ori) > max_val )
1397                {
1398                   max_val = hist.at<float>(ori);
1399                   max_ind = ori;
1400                }
1401             }
1402 
1403             prev = max_ind-1;
1404             if( prev < 0 )
1405                prev += m_orientation_resolution;
1406 
1407             next = max_ind+1;
1408             if( next >= m_orientation_resolution )
1409                next -= m_orientation_resolution;
1410 
1411             peak = interpolate_peak(hist.at<float>(prev), hist.at<float>(max_ind), hist.at<float>(next));
1412             angle = (float)( ((float)max_ind + peak)*360.0/m_orientation_resolution );
1413 
1414             int iangle = int(angle);
1415 
1416             if( iangle <    0 ) iangle += 360;
1417             if( iangle >= 360 ) iangle -= 360;
1418 
1419             if( !(iangle >= 0.0 && iangle < 360.0) )
1420             {
1421                angle = 0;
1422             }
1423             m_orientation_map.at<float>(y,x) = (float)iangle;
1424          }
1425          hist.release();
1426       }
1427     }
1428     compute_oriented_grid_points();
1429 }
1430 
1431 
initialize_single_descriptor_mode()1432 inline void DAISY_Impl::initialize_single_descriptor_mode( )
1433 {
1434     initialize();
1435     compute_smoothed_gradient_layers();
1436 }
1437 
set_parameters()1438 inline void DAISY_Impl::set_parameters( )
1439 {
1440     m_grid_point_number = m_rad_q_no * m_th_q_no + 1; // +1 is for center pixel
1441     m_descriptor_size = m_grid_point_number * m_hist_th_q_no;
1442 
1443     for( int i=0; i<360; i++ )
1444     {
1445       m_orientation_shift_table[i] = i/360.0 * m_hist_th_q_no;
1446     }
1447 
1448     compute_cube_sigmas();
1449     compute_grid_points();
1450 }
1451 
1452 // set/convert image array for daisy internal routines
1453 // daisy internals use CV_32F image with norm to 1.0f
set_image(InputArray _image)1454 inline void DAISY_Impl::set_image( InputArray _image )
1455 {
1456     // release previous image
1457     // and previous workspace
1458     reset();
1459     // fetch new image
1460     Mat image = _image.getMat();
1461     // image cannot be empty
1462     CV_Assert( ! image.empty() );
1463     // clone image for conversion
1464     if ( image.depth() != CV_32F ) {
1465 
1466       m_image = image.clone();
1467       // convert to gray inplace
1468       if( m_image.channels() > 1 )
1469           cvtColor( m_image, m_image, COLOR_BGR2GRAY );
1470       // convert and normalize
1471       m_image.convertTo( m_image, CV_32F );
1472       m_image /= 255.0f;
1473     } else
1474       // use original user supplied CV_32F image
1475       // should be a normalized one (cannot check)
1476       m_image = image;
1477 }
1478 
1479 
1480 // -------------------------------------------------
1481 /* DAISY interface implementation */
1482 
1483 // keypoint scope
compute(InputArray _image,std::vector<KeyPoint> & keypoints,OutputArray _descriptors)1484 void DAISY_Impl::compute( InputArray _image, std::vector<KeyPoint>& keypoints, OutputArray _descriptors )
1485 {
1486     // do nothing if no image
1487     if( _image.getMat().empty() )
1488       return;
1489 
1490     set_image( _image );
1491 
1492     // whole image
1493     m_roi = Rect( 0, 0, m_image.cols, m_image.rows );
1494 
1495     // get homography
1496     Mat H = m_h_matrix;
1497 
1498     // convert to double if case
1499     if ( H.depth() != CV_64F )
1500         H.convertTo( H, CV_64F );
1501 
1502     set_parameters();
1503 
1504     initialize_single_descriptor_mode();
1505 
1506     // allocate array
1507     _descriptors.create( (int) keypoints.size(), m_descriptor_size, CV_32F );
1508 
1509     // prepare descriptors
1510     Mat descriptors = _descriptors.getMat();
1511     descriptors.setTo( Scalar(0) );
1512 
1513     // iterate over keypoints
1514     // and fill computed descriptors
1515     if ( H.empty() )
1516       for (int k = 0; k < (int) keypoints.size(); k++)
1517       {
1518           get_descriptor( keypoints[k].pt.y, keypoints[k].pt.x,
1519                           m_use_orientation ? (int) keypoints[k].angle : 0,
1520                           &descriptors.at<float>( k, 0 ), &m_smoothed_gradient_layers,
1521                           &m_oriented_grid_points, m_orientation_shift_table, m_th_q_no,
1522                           m_hist_th_q_no, m_grid_point_number, m_descriptor_size, m_enable_interpolation,
1523                           m_nrm_type );
1524       }
1525     else
1526       for (int k = 0; k < (int) keypoints.size(); k++)
1527       {
1528         get_descriptor_h( keypoints[k].pt.y, keypoints[k].pt.x,
1529                           m_use_orientation ? (int) keypoints[k].angle : 0,
1530                           &descriptors.at<float>( k, 0 ), &H.at<double>( 0 ), &m_smoothed_gradient_layers,
1531                           m_cube_sigmas, &m_grid_points, m_orientation_shift_table, m_th_q_no,
1532                           m_hist_th_q_no, m_grid_point_number, m_descriptor_size, m_enable_interpolation,
1533                           m_nrm_type );
1534       }
1535 
1536 }
1537 
1538 // full scope with roi
compute(InputArray _image,Rect roi,OutputArray _descriptors)1539 void DAISY_Impl::compute( InputArray _image, Rect roi, OutputArray _descriptors )
1540 {
1541     // do nothing if no image
1542     if( _image.getMat().empty() )
1543       return;
1544 
1545     CV_Assert( m_h_matrix.empty() );
1546     CV_Assert( ! m_use_orientation );
1547 
1548     set_image( _image );
1549 
1550     m_roi = roi;
1551 
1552     set_parameters();
1553     initialize_single_descriptor_mode();
1554 
1555     _descriptors.create( m_roi.width*m_roi.height, m_descriptor_size, CV_32F );
1556 
1557     Mat descriptors = _descriptors.getMat();
1558 
1559     // compute full desc
1560     compute_descriptors( &descriptors );
1561     normalize_descriptors( &descriptors );
1562 }
1563 
1564 // full scope
compute(InputArray _image,OutputArray _descriptors)1565 void DAISY_Impl::compute( InputArray _image, OutputArray _descriptors )
1566 {
1567     // do nothing if no image
1568     if( _image.getMat().empty() )
1569       return;
1570 
1571     CV_Assert( m_h_matrix.empty() );
1572     CV_Assert( ! m_use_orientation );
1573 
1574     set_image( _image );
1575 
1576     // whole image
1577     m_roi = Rect( 0, 0, m_image.cols, m_image.rows );
1578 
1579     set_parameters();
1580     initialize_single_descriptor_mode();
1581 
1582     _descriptors.create( m_roi.width*m_roi.height, m_descriptor_size, CV_32F );
1583 
1584     Mat descriptors = _descriptors.getMat();
1585 
1586     // compute full desc
1587     compute_descriptors( &descriptors );
1588     normalize_descriptors( &descriptors );
1589 }
1590 
1591 // constructor
DAISY_Impl(float _radius,int _q_radius,int _q_theta,int _q_hist,DAISY::NormalizationType _norm,InputArray _H,bool _interpolation,bool _use_orientation)1592 DAISY_Impl::DAISY_Impl( float _radius, int _q_radius, int _q_theta, int _q_hist,
1593              DAISY::NormalizationType _norm, InputArray _H, bool _interpolation, bool _use_orientation )
1594            : m_rad(_radius), m_rad_q_no(_q_radius), m_th_q_no(_q_theta), m_hist_th_q_no(_q_hist),
1595              m_nrm_type(_norm), m_enable_interpolation(_interpolation), m_use_orientation(_use_orientation)
1596 {
1597 
1598     m_descriptor_size = 0;
1599     m_grid_point_number = 0;
1600 
1601     m_scale_invariant = false;
1602     m_rotation_invariant = false;
1603     m_orientation_resolution = 36;
1604 
1605     m_h_matrix = _H.getMat();
1606 }
1607 
1608 // destructor
~DAISY_Impl()1609 DAISY_Impl::~DAISY_Impl()
1610 {
1611     release_auxiliary();
1612 }
1613 
create(float radius,int q_radius,int q_theta,int q_hist,DAISY::NormalizationType norm,InputArray H,bool interpolation,bool use_orientation)1614 Ptr<DAISY> DAISY::create( float radius, int q_radius, int q_theta, int q_hist,
1615              DAISY::NormalizationType norm, InputArray H, bool interpolation, bool use_orientation)
1616 {
1617     return makePtr<DAISY_Impl>(radius, q_radius, q_theta, q_hist, norm, H, interpolation, use_orientation);
1618 }
1619 
1620 
1621 } // END NAMESPACE XFEATURES2D
1622 } // END NAMESPACE CV
1623