SIFTFeatureCalculator.cpp
Go to the documentation of this file.
1 // ****************************************************************************
2 // This file is part of the Integrating Vision Toolkit (IVT).
3 //
4 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
5 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
6 //
7 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
8 // All rights reserved.
9 //
10 // Redistribution and use in source and binary forms, with or without
11 // modification, are permitted provided that the following conditions are met:
12 //
13 // 1. Redistributions of source code must retain the above copyright
14 // notice, this list of conditions and the following disclaimer.
15 //
16 // 2. Redistributions in binary form must reproduce the above copyright
17 // notice, this list of conditions and the following disclaimer in the
18 // documentation and/or other materials provided with the distribution.
19 //
20 // 3. Neither the name of the KIT nor the names of its contributors may be
21 // used to endorse or promote products derived from this software
22 // without specific prior written permission.
23 //
24 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
25 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
26 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
28 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
29 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
31 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
32 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
33 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
34 // ****************************************************************************
35 // ****************************************************************************
36 // Filename: SIFTFeatureCalculator.cpp
37 // Author: Pedram Azad, Lars Paetzold
38 // Date: 24.09.2008
39 // ****************************************************************************
40 
41 #include <new> // for explicitly using correct new/delete operators on VC DSPs
42 
43 #include "SIFTFeatureCalculator.h"
44 
45 #include "Image/ImageProcessor.h"
46 #include "Image/ByteImage.h"
47 #include "Math/FloatMatrix.h"
48 #include "Math/Constants.h"
50 #include "SIFTFeatureEntry.h"
51 
52 #include <math.h>
53 
54 
55 
56 // ****************************************************************************
57 // Defines
58 // ****************************************************************************
59 
60 #define S 3 // number of scales per octave
61 #define SIGMA0 1.0f // initial sigma of each octave
62 #define PRESIGMA 0.5f // sigma of the input image
63 #define PRESCALE 1.0f // input will be prescaled, 2.0f doubles size, 0.5f half size
64 #define EDGE_THRESHOLD 10.0f
65 
66 
67 // ****************************************************************************
68 // Static variables
69 // ****************************************************************************
70 
72 float CSIFTFeatureCalculator::k_ = powf(2.0f, 1.0f / S);
73 float CSIFTFeatureCalculator::diffk_ = sqrtf(k_ * k_ - 1);
75 float CSIFTFeatureCalculator::diffsigma0_ = SIGMA0 * SIGMA0 - prescaledsigma_ * prescaledsigma_;
76 
85 
86 
87 
88 // ****************************************************************************
89 // Constructor / Destructor
90 // ****************************************************************************
91 
92 CSIFTFeatureCalculator::CSIFTFeatureCalculator(float fThreshold, int nOctaves)
93 {
94  m_fThreshold = fThreshold;
95  m_nOctaves = nOctaves;
96 
97  m_pResultList = 0;
98  m_bManageMemory = true;
99 
101 }
102 
104 {
105 }
106 
107 
108 // ****************************************************************************
109 // Methods
110 // ****************************************************************************
111 
113 {
114  if (!m_bInitialized)
115  {
116  int i, j, k, offset;
117 
118  for (j = 0, offset = 0; j < 16; j++)
119  {
120  for (i = 0; i < 16; i++, offset++)
121  {
122  // sigma = 8 according to paper (half of the window width, which is 16)
123  // 2 * sigma * sigma = 128
124  const int x = i / 4;
125  const int y = j / 4;
126 
127  SIFTPointers[offset] = 8 * (4 * y + x);
128  SIFTWeights[offset] = expf( -((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / 128.0f);
129  }
130  }
131 
132  // sigmas, diffsigmas and kernel sizes
133  SIFTSigmas[0] = SIGMA0;
134  // calculate Gaussians
135  for (i = 1; i < S + 3; i++)
136  {
137  const float diffsigma = diffk_ * SIFTSigmas[i - 1];
138  const int nKernelRadius = int(ceil(3 * diffsigma));
139  const int nKernelSize = nKernelRadius * 2 + 1;
140 
141  SIFTSigmas[i] = SIFTSigmas[i - 1] * k_;
142  SIFTDiffSigmas[i] = diffsigma;
143  SIFTKernelRadius[i] = nKernelRadius;
144  }
145 
146  // orientation weights
147  float sigma = 1.5f * SIGMA0;
148  for (k = 0, offset = 0; k <= MAX_SCALES; k++)
149  {
150  for (j = 0; j < 16; j++)
151  for (i = 0; i < 16; i++)
152  SIFTOrientationWeights[offset++] = expf(-((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / (2.0f * sigma * sigma));
153 
154  sigma *= k_;
155  }
156 
157  // descriptor weights
158  sigma = 8.0f;
159  for (j = 0, offset = 0; j < 16; j++)
160  for (i = 0; i < 16; i++)
161  SIFTDescriptorWeights[offset++] = expf(-((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / (2.0f * sigma * sigma));
162 
163  m_bInitialized = true;
164  }
165 }
166 
167 int CSIFTFeatureCalculator::CalculateFeatures(const CByteImage *pImage, CDynamicArray *pResultList, bool bManageMemory)
168 {
169  if (pImage->type != CByteImage::eGrayScale)
170  {
171  printf("error: input image is not a grayscale image\n");
172  return -1;
173  }
174 
175  m_pResultList = pResultList;
176  m_bManageMemory = bManageMemory;
177 
178  if (PRESCALE == 1.0f)
179  {
180  CFloatMatrix matrix(pImage->width, pImage->height);
181 
182  ImageProcessor::GaussianSmooth(pImage, &matrix, diffsigma0_ * diffsigma0_, 2 * int(ceil(3 * diffsigma0_)) + 1);
183 
184  FindScaleSpaceExtrema(&matrix, PRESCALE, m_nOctaves);
185  }
186  else
187  {
188  const int newWidth = int(pImage->width * PRESCALE);
189  const int newHeight = int(pImage->height * PRESCALE);
190 
191  CFloatMatrix matrix(newWidth, newHeight);
192  CByteImage image(newWidth, newHeight, CByteImage::eGrayScale);
193 
194  ImageProcessor::Resize(pImage, &image);
195  ImageProcessor::GaussianSmooth(&image, &matrix, diffsigma0_ * diffsigma0_, 2 * int(ceil(3 * diffsigma0_)) + 1);
196 
197  FindScaleSpaceExtrema(&matrix, PRESCALE, m_nOctaves);
198  }
199 
200  return pResultList->GetSize();
201 }
202 
203 
204 void CSIFTFeatureCalculator::DetermineDominatingOrientations(const CFloatMatrix *pAngleMatrix, const CFloatMatrix *pMagnitudeMatrix, CDynamicArrayTemplate<float> &orientations, bool bPerform80PercentCheck)
205 {
206  const int nWindowSize = pAngleMatrix->columns;
207  const int nPixels = nWindowSize * nWindowSize;
208  int i;
209 
210  float histogram_space[36 + 2];
211  float *histogram = histogram_space + 1;
212 
213  for (i = 0; i < 37; i++)
214  histogram[i] = 0.0f;
215 
216  const float *angles = pAngleMatrix->data;
217  const float *magnitudes = pMagnitudeMatrix->data;
218  const float factor = 18 / FLOAT_PI;
219 
220  for (i = 0; i < nPixels; i++)
221  {
222  const int d = (int) (factor * angles[i] + 18);
223  histogram[d] += magnitudes[i];
224  }
225 
226  // add hits in bin 36 to bin 0
227  histogram[0] += histogram[36];
228 
229  // find highest peak
230  float max = 0.0f;
231  int best_i = -1;
232  for (i = 0; i < 36; i++)
233  if (histogram[i] > max)
234  {
235  max = histogram[i];
236  best_i = i;
237  }
238 
239  // optimization trick
240  histogram[-1] = histogram[35];
241  histogram[36] = histogram[0];
242 
243  if (bPerform80PercentCheck)
244  {
245  // prepare 80% check
246  max *= 0.8f;
247 
248  // store peaks
249  for (i = 0; i < 36; i++)
250  {
251  if (histogram[i] >= max && histogram[i] > histogram[i + 1] && histogram[i] > histogram[i - 1])
252  {
253  // parabola fitting
254  float angle = 10.0f * (i + 0.5f * (histogram[i + 1] - histogram[i - 1]) / (2.0f * histogram[i] - histogram[i + 1] - histogram[i - 1])) + 5.0f;
255 
256  if (angle < 0.0f)
257  angle += 360.0f;
258 
259  orientations.AddElement(angle);
260  }
261  }
262  }
263  else
264  {
265  if (best_i != -1 && histogram[best_i] > histogram[best_i + 1] && histogram[best_i] > histogram[best_i - 1])
266  {
267  // parabola fitting
268  float angle = 10.0f * (best_i + 0.5f * (histogram[best_i + 1] - histogram[best_i - 1]) / (2.0f * histogram[best_i] - histogram[best_i + 1] - histogram[best_i - 1])) + 5.0f;
269 
270  if (angle < 0.0f)
271  angle += 360.0f;
272 
273  orientations.AddElement(angle);
274  }
275  }
276 }
277 
278 
279 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CFloatMatrix *pImage, CDynamicArray *pResultList, float xp, float yp, float scale, float sigma, const float *pOrientationWeights, bool bManageMemory, bool bPerform80PercentCheck)
280 {
281  const int width = pImage->columns;
282  const int height = pImage->rows;
283  const float *input = pImage->data;
284 
285  // determine upper left corner of window and check boundaries
286  int x0 = int(xp + 0.5f) - 9;
287  int y0 = int(yp + 0.5f) - 9;
288 
289  if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
290  return;
291 
292  // calculate gradients, angles and magnitude
293  CFloatMatrix angleMatrix(16, 16);
294  CFloatMatrix magnitudeMatrix(16, 16);
295  float *angles = angleMatrix.data;
296  float *magnitudes = magnitudeMatrix.data;
297  const int diff = width - 16;
298 
299  for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
300  {
301  for (int x = 0; x < 16; x++, input_offset++, offset++)
302  {
303  const float gx = input[input_offset + 1] - input[input_offset - 1];
304  const float gy = input[input_offset + width] - input[input_offset - width];
305 
306  angles[offset] = atan2f(gy, gx);
307  magnitudes[offset] = sqrtf(gx * gx + gy * gy) * pOrientationWeights[offset];
308  }
309  }
310 
311  // find dominating orientations
312  CDynamicArrayTemplate<float> orientations(20);
313  DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
314 
315  // apply descriptor weights (undo orientation weights)
316  for (int i = 0; i < 256; i++)
317  magnitudes[i] = magnitudes[i] / pOrientationWeights[i] * SIFTDescriptorWeights[i];
318 
319  // create SIFT descriptor for each dominating orientation
320  const int nSize = orientations.GetSize();
321  for (int k = 0; k < nSize; k++)
322  {
323  int i;
324 
325  CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], sigma / scale);
326  float *feature_vector = pEntry->m_pFeature;
327 
328  for (i = 0; i < 128; i++)
329  feature_vector[i] = 0.0f;
330 
331  // create descriptor
332  const float angle = -pEntry->angle * FLOAT_DEG2RAD;
333  const float cosphi = cosf(angle);
334  const float sinphi = sinf(angle);
335 
336  for (int y = 0, offset = 0; y < 16; y++)
337  {
338  for (int x = 0; x < 16; x++, offset++)
339  {
340  const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
341  const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
342 
343  if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
344  {
345  const int offset_ = y_ * 16 + x_;
346 
347  float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
348  phi += angle / FLOAT_PI; // [-2, 2)
349  if (phi < 0.0f) phi += 2.0f; // [0, 2)
350  int d = int(4.0f * phi);
351  if (d > 7) d = 7;
352 
353  feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
354  }
355  }
356  }
357 
358  // normalize and cut off entries > 0.2
359  bool bChanged = false;
360  float sum1 = 0.0f, sum2 = 0.0f;
361 
362  for (i = 0; i < 128; i++)
363  sum1 += feature_vector[i] * feature_vector[i];
364 
365  sum1 = sqrtf(sum1);
366 
367  for (i = 0; i < 128; i++)
368  {
369  feature_vector[i] /= sum1;
370 
371  if (feature_vector[i] > 0.2f)
372  {
373  feature_vector[i] = 0.2f;
374  bChanged = true;
375  }
376 
377  sum2 += feature_vector[i] * feature_vector[i];
378  }
379 
380  if (bChanged)
381  {
382  sum2 = sqrtf(sum2);
383 
384  for (int i = 0; i < 128; i++)
385  feature_vector[i] /= sum2;
386  }
387 
388  pResultList->AddElement(pEntry, false, bManageMemory);
389  }
390 }
391 
392 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CByteImage *pImage, CDynamicArray *pResultList, float xp, float yp, float scale, bool bManageMemory, bool bPerform80PercentCheck)
393 {
394  const int width = pImage->width;
395  const int height = pImage->height;
396  const unsigned char *input = pImage->pixels;
397 
398  // determine upper left corner of window and check boundaries
399  int x0 = int(xp + 0.5f) - 18 / 2;
400  int y0 = int(yp + 0.5f) - 18 / 2;
401 
402  if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
403  return;
404 
405  // calculate gradients, angles and magnitude
406  CFloatMatrix angleMatrix(16, 16);
407  CFloatMatrix magnitudeMatrix(16, 16);
408  float *angles = angleMatrix.data;
409  float *magnitudes = magnitudeMatrix.data;
410  const int diff = width - 16;
411 
412  for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
413  {
414  for (int x = 0; x < 16; x++, input_offset++, offset++)
415  {
416  const int gx = input[input_offset + 1] - input[input_offset - 1];
417  const int gy = input[input_offset + width] - input[input_offset - width];
418 
419  angles[offset] = atan2f((float) gy, (float) gx);
420  magnitudes[offset] = sqrtf(float(gx * gx + gy * gy)); // weighting with Gaussian is ommited in this version
421  }
422  }
423 
424  // find dominating orientations
425  CDynamicArrayTemplate<float> orientations(20);
426  DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
427 
428  // create SIFT descriptor for each dominating orientation
429  const int nSize = orientations.GetSize();
430  for (int k = 0; k < nSize; k++)
431  {
432  int i;
433 
434  CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], scale);
435  float *feature_vector = pEntry->m_pFeature;
436 
437  for (i = 0; i < 128; i++)
438  feature_vector[i] = 0.0f;
439 
440  // create descriptor
441  const float angle = -pEntry->angle * FLOAT_DEG2RAD;
442  const float cosphi = cosf(angle);
443  const float sinphi = sinf(angle);
444 
445  for (int y = 0, offset = 0; y < 16; y++)
446  {
447  for (int x = 0; x < 16; x++, offset++)
448  {
449  const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
450  const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
451 
452  if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
453  {
454  const int offset_ = y_ * 16 + x_;
455 
456  float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
457  phi += angle / FLOAT_PI; // [-2, 2)
458  if (phi < 0.0f) phi += 2.0f; // [0, 2)
459  int d = int(4.0f * phi);
460  if (d > 7) d = 7;
461 
462  feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
463  }
464  }
465  }
466 
467  // normalize and cut off entries > 0.2f
468  bool bChanged = false;
469  float sum1 = 0.0f, sum2 = 0.0f;
470 
471  for (i = 0; i < 128; i++)
472  sum1 += feature_vector[i] * feature_vector[i];
473 
474  sum1 = 1.0f / sqrtf(sum1);
475 
476  for (i = 0; i < 128; i++)
477  {
478  feature_vector[i] *= sum1;
479 
480  if (feature_vector[i] > 0.2f)
481  {
482  feature_vector[i] = 0.2f;
483  bChanged = true;
484  }
485 
486  sum2 += feature_vector[i] * feature_vector[i];
487  }
488 
489  if (bChanged)
490  {
491  sum2 = 1.0f / sqrtf(sum2);
492 
493  for (int i = 0; i < 128; i++)
494  feature_vector[i] *= sum2;
495  }
496 
497  pResultList->AddElement(pEntry, false, bManageMemory);
498  }
499 }
500 
501 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CByteImage *pImage, CDynamicArrayTemplatePointer<CFeatureEntry> &resultList, float xp, float yp, float scale, bool bPerform80PercentCheck)
502 {
503  const int width = pImage->width;
504  const int height = pImage->height;
505  const unsigned char *input = pImage->pixels;
506 
507  // determine upper left corner of window and check boundaries
508  int x0 = int(xp + 0.5f) - 18 / 2;
509  int y0 = int(yp + 0.5f) - 18 / 2;
510 
511  if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
512  return;
513 
514  // calculate gradients, angles and magnitude
515  CFloatMatrix angleMatrix(16, 16);
516  CFloatMatrix magnitudeMatrix(16, 16);
517  float *angles = angleMatrix.data;
518  float *magnitudes = magnitudeMatrix.data;
519  const int diff = width - 16;
520 
521  for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
522  {
523  for (int x = 0; x < 16; x++, input_offset++, offset++)
524  {
525  const int gx = input[input_offset + 1] - input[input_offset - 1];
526  const int gy = input[input_offset + width] - input[input_offset - width];
527 
528  angles[offset] = atan2f((float) gy, (float) gx);
529  magnitudes[offset] = sqrtf(float(gx * gx + gy * gy)); // weighting with Gaussian is ommited in this version
530  }
531  }
532 
533  // find dominating orientations
534  CDynamicArrayTemplate<float> orientations(20);
535  DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
536 
537  // create SIFT descriptor for each dominating orientation
538  const int nSize = orientations.GetSize();
539  for (int k = 0; k < nSize; k++)
540  {
541  int i;
542 
543  CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], scale);
544  float *feature_vector = pEntry->m_pFeature;
545 
546  for (i = 0; i < 128; i++)
547  feature_vector[i] = 0.0f;
548 
549  // create descriptor
550  const float angle = -pEntry->angle * FLOAT_DEG2RAD;
551  const float cosphi = cosf(angle);
552  const float sinphi = sinf(angle);
553 
554  for (int y = 0, offset = 0; y < 16; y++)
555  {
556  for (int x = 0; x < 16; x++, offset++)
557  {
558  const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
559  const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
560 
561  if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
562  {
563  const int offset_ = y_ * 16 + x_;
564 
565  float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
566  phi += angle / FLOAT_PI; // [-2, 2)
567  if (phi < 0.0f) phi += 2.0f; // [0, 2)
568  int d = int(4.0f * phi);
569  if (d > 7) d = 7;
570 
571  feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
572  }
573  }
574  }
575 
576  // normalize and cut off entries > 0.2f
577  bool bChanged = false;
578  float sum1 = 0.0f, sum2 = 0.0f;
579 
580  for (i = 0; i < 128; i++)
581  sum1 += feature_vector[i] * feature_vector[i];
582 
583  sum1 = 1.0f / sqrtf(sum1);
584 
585  for (i = 0; i < 128; i++)
586  {
587  feature_vector[i] *= sum1;
588 
589  if (feature_vector[i] > 0.2f)
590  {
591  feature_vector[i] = 0.2f;
592  bChanged = true;
593  }
594 
595  sum2 += feature_vector[i] * feature_vector[i];
596  }
597 
598  if (bChanged)
599  {
600  sum2 = 1.0f / sqrtf(sum2);
601 
602  for (int i = 0; i < 128; i++)
603  feature_vector[i] *= sum2;
604  }
605 
606  resultList.AddElement(pEntry);
607  }
608 }
609 
610 
611 static void ScaleDown(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
612 {
613  const float *input = pInputImage->data;
614  float *output = pOutputImage->data;
615 
616  const int output_width = pOutputImage->columns;
617  const int output_height = pOutputImage->rows;
618  const int width = pInputImage->columns;
619 
620  for (int v = 0, offset = 0, offset_ = 0; v < output_height; v++, offset_ += width)
621  {
622  for (int u = 0; u < output_width; u++, offset++, offset_ += 2)
623  output[offset] = input[offset_];
624  }
625 }
626 
627 static void Diff(const CFloatMatrix *pInputImage1, const CFloatMatrix *pInputImage2, CFloatMatrix *pOutputImage)
628 {
629  float *input1 = pInputImage1->data;
630  float *input2 = pInputImage2->data;
631  float *output = pOutputImage->data;
632 
633  const int nPixels = pInputImage1->rows * pInputImage1->columns;
634 
635  for (int i = 0; i < nPixels; i++)
636  *output++ = *input1++ - *input2++;
637 }
638 
639 
640 void CSIFTFeatureCalculator::FindScaleSpaceExtrema(const CFloatMatrix *pImage, float scale, int nOctave)
641 {
642  const int width = pImage->columns;
643  const int height = pImage->rows;
644 
645  if (nOctave == 0 || width < 40 || height < 40)
646  return;
647 
648  const int nBlurredImages = S + 3;
649  const int nDOGImages = nBlurredImages - 1;
650 
651  int i;
652 
653  CFloatMatrix** ppBlurredImages = new CFloatMatrix*[nBlurredImages];
654  CFloatMatrix** ppDOGImages = new CFloatMatrix*[nDOGImages];
655 
656  CFloatMatrix tempImage(height, width);
657 
658  // calculate Gaussians
659  ppBlurredImages[0] = new CFloatMatrix(width, height);
660  ImageProcessor::CopyMatrix(pImage, ppBlurredImages[0]);
661 
662  for (i = 1; i < nBlurredImages; i++)
663  {
664  ppBlurredImages[i] = new CFloatMatrix(width, height);
665  ImageProcessor::GaussianSmooth(ppBlurredImages[i - 1], ppBlurredImages[i], SIFTDiffSigmas[i] * SIFTDiffSigmas[i], 2 * SIFTKernelRadius[i] + 1);
666  }
667 
668  // halfsize image with doubled sigma for later
669  // ppBlurredImages[s] because ppBlurredImages[i] has (k^i * sigma)
670  // therefore k^s * sigma = 2 * sigma as k^s = 2
671  /*
672  the octave is from sigma to 2 * sigma or k^0*sigma to k^s * sigma
673  so we have s intervals from 0 to s having s+1 blurred images
674  but for extrema detection we always need one image before and one after
675  therefore if we want D(k^0*sigma) to D(k^s * sigma) we need
676  D(k^-1*sigma) to D(k^s+1*sigma) having s+3 images.
677  but we shift it to D(k^0*sigma) till D(k^s+2*digma)
678  therefore our doubled sigma is like said before at k^s*sigma.
679  but important is that we have to go from 0 to s+2.
680  */
681 
682  // calculate Difference of Gaussians (DoG)
683  for (i = 0; i < nDOGImages; i++)
684  {
685  ppDOGImages[i] = new CFloatMatrix(width, height);
686  Diff(ppBlurredImages[i + 1], ppBlurredImages[i], ppDOGImages[i]);
687  }
688 
689  // find scale space extrema
690  const float fThreshold = m_fThreshold * 255.0f;
691  for (i = 1; i < nDOGImages - 1; i++)
692  {
693  const float *dm = ppDOGImages[i - 1]->data;
694  const float *d = ppDOGImages[i]->data;
695  const float *dp = ppDOGImages[i + 1]->data;
696 
697  for (int y = 1, p = width + 1; y < height - 1; y++, p += 2)
698  {
699  for (int x = 1; x < width - 1; x++, p++)
700  {
701  const float dv = d[p];
702 
703  if (fabsf(dv) > fThreshold &&
704  ((
705  dv > dp[p] &&
706  dv > dp[p - width - 1] &&
707  dv > dp[p - width] &&
708  dv > dp[p - width + 1] &&
709  dv > dp[p - 1] &&
710  dv > dp[p + 1] &&
711  dv > dp[p + width - 1] &&
712  dv > dp[p + width] &&
713  dv > dp[p + width + 1] &&
714 
715  dv > dm[p] &&
716  dv > dm[p - width - 1] &&
717  dv > dm[p - width] &&
718  dv > dm[p - width + 1] &&
719  dv > dm[p - 1] &&
720  dv > dm[p + 1] &&
721  dv > dm[p + width - 1] &&
722  dv > dm[p + width] &&
723  dv > dm[p + width + 1] &&
724 
725  dv > d[p - width - 1] &&
726  dv > d[p - width] &&
727  dv > d[p - width + 1] &&
728  dv > d[p - 1] &&
729  dv > d[p + 1] &&
730  dv > d[p + width - 1] &&
731  dv > d[p + width] &&
732  dv > d[p + width + 1]
733  )
734  ||
735  (
736  dv < dp[p] &&
737  dv < dp[p - width - 1] &&
738  dv < dp[p - width] &&
739  dv < dp[p - width + 1] &&
740  dv < dp[p - 1] &&
741  dv < dp[p + 1] &&
742  dv < dp[p + width - 1] &&
743  dv < dp[p + width] &&
744  dv < dp[p + width + 1] &&
745 
746  dv < dm[p] &&
747  dv < dm[p - width - 1] &&
748  dv < dm[p - width] &&
749  dv < dm[p - width + 1] &&
750  dv < dm[p - 1] &&
751  dv < dm[p + 1] &&
752  dv < dm[p + width - 1] &&
753  dv < dm[p + width] &&
754  dv < dm[p + width + 1] &&
755 
756  dv < d[p - width - 1] &&
757  dv < d[p - width] &&
758  dv < d[p - width + 1] &&
759  dv < d[p - 1] &&
760  dv < d[p + 1] &&
761  dv < d[p + width - 1] &&
762  dv < d[p + width] &&
763  dv < d[p + width + 1]
764  ))
765  )
766  {
767  // eliminating edge responses
768  const float Dxx = (d[p + 1] + d[p - 1] - 2.0f * d[p]);
769  const float Dyy = (d[p + width] + d[p - width] - 2.0f * d[p]);
770  const float Dxy = 0.25f * (d[p + 1 + width] + d[p - 1 - width] - d[p - 1 + width] - d[p + 1 - width]);
771  const float score = (Dxx + Dyy) * (Dxx + Dyy) / (Dxx * Dyy - Dxy * Dxy);
772 
773  if (fabsf(score) < edgethreshold_)
774  CreateSIFTDescriptors(ppBlurredImages[i], m_pResultList, float(x), float(y), scale, SIFTSigmas[i], SIFTOrientationWeights + i * 256, m_bManageMemory);
775  }
776  }
777  }
778  }
779 
780  CFloatMatrix scaled_image(width / 2, height / 2);
781  ScaleDown(ppBlurredImages[S], &scaled_image);
782 
783  // free images
784  for (i = 0; i < nBlurredImages; i++)
785  delete ppBlurredImages[i];
786  for (i = 0; i < nDOGImages; i++)
787  delete ppDOGImages[i];
788 
789  FindScaleSpaceExtrema(&scaled_image, scale / 2, nOctave - 1);
790 }
static void Diff(const CFloatMatrix *pInputImage1, const CFloatMatrix *pInputImage2, CFloatMatrix *pOutputImage)
#define PRESCALE
int CalculateFeatures(const CByteImage *pImage, CDynamicArray *pResultList, bool bManageMemory=true)
static void CreateSIFTDescriptors(const CFloatMatrix *pImage, CDynamicArray *pResultList, float x, float y, float scale, float sigma, const float *pOrientationWeights, bool bManageMemory=true, bool bPerform80PercentCheck=true)
GLuint GLenum matrix
Definition: glext.h:5683
GLenum GLenum GLenum GLenum GLenum scale
Definition: glext.h:5308
#define SIGMA0
int width
The width of the image in pixels.
Definition: ByteImage.h:257
GLenum GLsizei GLenum GLenum const GLvoid * image
Definition: glext.h:3131
CSIFTFeatureCalculator(float fThreshold=0.05f, int nOctaves=3)
Data structure for the representation of 8-bit grayscale images and 24-bit RGB (or HSV) color images ...
Definition: ByteImage.h:80
static float SIFTDiffSigmas[MAX_SCALES]
GLintptr offset
Definition: glext.h:3389
void FindScaleSpaceExtrema(const CFloatMatrix *pImage, float scale, int nOctave)
unsigned char * pixels
The pointer to the the pixels.
Definition: ByteImage.h:283
Data structure for the representation of SIFT features.
bool AddElement(CDynamicArrayElement *pElement, bool bAddUniqueOnly=false, bool bManageMemory=true)
#define S
GLenum GLint x
Definition: glext.h:3125
bool GaussianSmooth(const CByteImage *pInputImage, CFloatMatrix *pOutputImage, float fVariance, int nKernelSize)
Applies a Gaussian filter to a CByteImage and writes the result to a CFloatMatrix.
static void ScaleDown(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
bool CopyMatrix(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
Copies one CFloatMatrix to another.
Data structure for the representation of a matrix of values of the data type float.
Definition: FloatMatrix.h:56
static float SIFTOrientationWeights[256 *(MAX_SCALES+1)]
#define EDGE_THRESHOLD
float * data
Definition: FloatMatrix.h:91
int height
The height of the image in pixels.
Definition: ByteImage.h:264
int GetSize() const
Definition: DynamicArray.h:102
static float SIFTSigmas[MAX_SCALES]
#define FLOAT_DEG2RAD
Definition: Constants.h:52
GLenum GLsizei width
Definition: glext.h:3122
GLenum GLsizei GLsizei height
Definition: glext.h:3132
#define FLOAT_PI
Definition: Constants.h:50
float * m_pFeature
Definition: FeatureEntry.h:264
GLenum GLenum GLenum input
Definition: glext.h:5307
ImageType type
The type of the image.
Definition: ByteImage.h:292
void AddElement(const T &element)
GLenum GLint GLint y
Definition: glext.h:3125
const GLdouble * v
Definition: glext.h:3212
static float SIFTDescriptorWeights[256]
static void DetermineDominatingOrientations(const CFloatMatrix *pAngleMatrix, const CFloatMatrix *pMagnitudeMatrix, CDynamicArrayTemplate< float > &orientations, bool bPerform80PercentCheck)
static int SIFTKernelRadius[MAX_SCALES]
GLfloat GLfloat p
Definition: glext.h:5178
#define MAX_SCALES
#define PRESIGMA
bool Resize(const CByteImage *pInputImage, CByteImage *pOutputImage, const MyRegion *pROI=0, bool bInterpolation=true)
Resizes a CByteImage and writes the result to a CByteImage.


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Mon Dec 2 2019 03:47:28