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 118 for (j = 0, offset = 0; j < 16; j++)
120 for (i = 0; i < 16; i++, offset++)
128 SIFTWeights[
offset] = expf( -((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / 128.0f);
135 for (i = 1; i <
S + 3; i++)
138 const int nKernelRadius = int(ceil(3 * diffsigma));
139 const int nKernelSize = nKernelRadius * 2 + 1;
141 SIFTSigmas[i] = SIFTSigmas[i - 1] *
k_;
147 float sigma = 1.5f *
SIGMA0;
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));
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));
171 printf(
"error: input image is not a grayscale image\n");
178 if (PRESCALE == 1.0f)
188 const int newWidth = int(pImage->
width * PRESCALE);
189 const int newHeight = int(pImage->
height * PRESCALE);
206 const int nWindowSize = pAngleMatrix->
columns;
207 const int nPixels = nWindowSize * nWindowSize;
210 float histogram_space[36 + 2];
211 float *histogram = histogram_space + 1;
213 for (i = 0; i < 37; i++)
216 const float *angles = pAngleMatrix->
data;
217 const float *magnitudes = pMagnitudeMatrix->
data;
220 for (i = 0; i < nPixels; i++)
222 const int d = (int) (factor * angles[i] + 18);
223 histogram[d] += magnitudes[i];
227 histogram[0] += histogram[36];
232 for (i = 0; i < 36; i++)
233 if (histogram[i] > max)
240 histogram[-1] = histogram[35];
241 histogram[36] = histogram[0];
243 if (bPerform80PercentCheck)
249 for (i = 0; i < 36; i++)
251 if (histogram[i] >= max && histogram[i] > histogram[i + 1] && histogram[i] > histogram[i - 1])
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;
265 if (best_i != -1 && histogram[best_i] > histogram[best_i + 1] && histogram[best_i] > histogram[best_i - 1])
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;
286 int x0 = int(xp + 0.5f) - 9;
287 int y0 = int(yp + 0.5f) - 9;
289 if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
295 float *angles = angleMatrix.
data;
296 float *magnitudes = magnitudeMatrix.
data;
297 const int diff = width - 16;
299 for (
int y = 0, input_offset = (y0 + 1) * width + x0 + 1,
offset = 0;
y < 16;
y++, input_offset += diff)
301 for (
int x = 0;
x < 16;
x++, input_offset++,
offset++)
303 const float gx = input[input_offset + 1] - input[input_offset - 1];
304 const float gy = input[input_offset +
width] - input[input_offset -
width];
306 angles[
offset] = atan2f(gy, gx);
307 magnitudes[
offset] = sqrtf(gx * gx + gy * gy) * pOrientationWeights[
offset];
316 for (
int i = 0; i < 256; i++)
320 const int nSize = orientations.
GetSize();
321 for (
int k = 0; k < nSize; k++)
328 for (i = 0; i < 128; i++)
329 feature_vector[i] = 0.0f;
333 const float cosphi = cosf(angle);
334 const float sinphi = sinf(angle);
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));
343 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
345 const int offset_ = y_ * 16 + x_;
349 if (phi < 0.0f) phi += 2.0f;
350 int d = int(4.0f * phi);
359 bool bChanged =
false;
360 float sum1 = 0.0f, sum2 = 0.0f;
362 for (i = 0; i < 128; i++)
363 sum1 += feature_vector[i] * feature_vector[i];
367 for (i = 0; i < 128; i++)
369 feature_vector[i] /= sum1;
371 if (feature_vector[i] > 0.2f)
373 feature_vector[i] = 0.2f;
377 sum2 += feature_vector[i] * feature_vector[i];
384 for (
int i = 0; i < 128; i++)
385 feature_vector[i] /= sum2;
388 pResultList->
AddElement(pEntry,
false, bManageMemory);
399 int x0 = int(xp + 0.5f) - 18 / 2;
400 int y0 = int(yp + 0.5f) - 18 / 2;
402 if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
408 float *angles = angleMatrix.
data;
409 float *magnitudes = magnitudeMatrix.
data;
410 const int diff = width - 16;
412 for (
int y = 0, input_offset = (y0 + 1) * width + x0 + 1,
offset = 0;
y < 16;
y++, input_offset += diff)
414 for (
int x = 0;
x < 16;
x++, input_offset++,
offset++)
416 const int gx = input[input_offset + 1] - input[input_offset - 1];
417 const int gy = input[input_offset +
width] - input[input_offset -
width];
419 angles[
offset] = atan2f((
float) gy, (
float) gx);
420 magnitudes[
offset] = sqrtf(
float(gx * gx + gy * gy));
429 const int nSize = orientations.
GetSize();
430 for (
int k = 0; k < nSize; k++)
437 for (i = 0; i < 128; i++)
438 feature_vector[i] = 0.0f;
442 const float cosphi = cosf(angle);
443 const float sinphi = sinf(angle);
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));
452 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
454 const int offset_ = y_ * 16 + x_;
458 if (phi < 0.0f) phi += 2.0f;
459 int d = int(4.0f * phi);
468 bool bChanged =
false;
469 float sum1 = 0.0f, sum2 = 0.0f;
471 for (i = 0; i < 128; i++)
472 sum1 += feature_vector[i] * feature_vector[i];
474 sum1 = 1.0f / sqrtf(sum1);
476 for (i = 0; i < 128; i++)
478 feature_vector[i] *= sum1;
480 if (feature_vector[i] > 0.2f)
482 feature_vector[i] = 0.2f;
486 sum2 += feature_vector[i] * feature_vector[i];
491 sum2 = 1.0f / sqrtf(sum2);
493 for (
int i = 0; i < 128; i++)
494 feature_vector[i] *= sum2;
497 pResultList->
AddElement(pEntry,
false, bManageMemory);
508 int x0 = int(xp + 0.5f) - 18 / 2;
509 int y0 = int(yp + 0.5f) - 18 / 2;
511 if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height)
517 float *angles = angleMatrix.
data;
518 float *magnitudes = magnitudeMatrix.
data;
519 const int diff = width - 16;
521 for (
int y = 0, input_offset = (y0 + 1) * width + x0 + 1,
offset = 0;
y < 16;
y++, input_offset += diff)
523 for (
int x = 0;
x < 16;
x++, input_offset++,
offset++)
525 const int gx = input[input_offset + 1] - input[input_offset - 1];
526 const int gy = input[input_offset +
width] - input[input_offset -
width];
528 angles[
offset] = atan2f((
float) gy, (
float) gx);
529 magnitudes[
offset] = sqrtf(
float(gx * gx + gy * gy));
538 const int nSize = orientations.
GetSize();
539 for (
int k = 0; k < nSize; k++)
546 for (i = 0; i < 128; i++)
547 feature_vector[i] = 0.0f;
551 const float cosphi = cosf(angle);
552 const float sinphi = sinf(angle);
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));
561 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
563 const int offset_ = y_ * 16 + x_;
567 if (phi < 0.0f) phi += 2.0f;
568 int d = int(4.0f * phi);
577 bool bChanged =
false;
578 float sum1 = 0.0f, sum2 = 0.0f;
580 for (i = 0; i < 128; i++)
581 sum1 += feature_vector[i] * feature_vector[i];
583 sum1 = 1.0f / sqrtf(sum1);
585 for (i = 0; i < 128; i++)
587 feature_vector[i] *= sum1;
589 if (feature_vector[i] > 0.2f)
591 feature_vector[i] = 0.2f;
595 sum2 += feature_vector[i] * feature_vector[i];
600 sum2 = 1.0f / sqrtf(sum2);
602 for (
int i = 0; i < 128; i++)
603 feature_vector[i] *= sum2;
614 float *output = pOutputImage->
data;
616 const int output_width = pOutputImage->
columns;
617 const int output_height = pOutputImage->
rows;
620 for (
int v = 0,
offset = 0, offset_ = 0;
v < output_height;
v++, offset_ +=
width)
622 for (
int u = 0; u < output_width; u++,
offset++, offset_ += 2)
623 output[offset] = input[offset_];
629 float *input1 = pInputImage1->
data;
630 float *input2 = pInputImage2->
data;
631 float *output = pOutputImage->
data;
633 const int nPixels = pInputImage1->
rows * pInputImage1->
columns;
635 for (
int i = 0; i < nPixels; i++)
636 *output++ = *input1++ - *input2++;
645 if (nOctave == 0 || width < 40 || height < 40)
648 const int nBlurredImages =
S + 3;
649 const int nDOGImages = nBlurredImages - 1;
662 for (i = 1; i < nBlurredImages; i++)
683 for (i = 0; i < nDOGImages; i++)
686 Diff(ppBlurredImages[i + 1], ppBlurredImages[i], ppDOGImages[i]);
691 for (i = 1; i < nDOGImages - 1; i++)
693 const float *dm = ppDOGImages[i - 1]->
data;
694 const float *d = ppDOGImages[i]->
data;
695 const float *dp = ppDOGImages[i + 1]->
data;
697 for (
int y = 1,
p = width + 1;
y < height - 1;
y++,
p += 2)
699 for (
int x = 1;
x < width - 1;
x++, p++)
701 const float dv = d[
p];
703 if (fabsf(dv) > fThreshold &&
706 dv > dp[p - width - 1] &&
707 dv > dp[p - width] &&
708 dv > dp[p - width + 1] &&
711 dv > dp[p + width - 1] &&
712 dv > dp[p + width] &&
713 dv > dp[p + width + 1] &&
716 dv > dm[p - width - 1] &&
717 dv > dm[p - width] &&
718 dv > dm[p - width + 1] &&
721 dv > dm[p + width - 1] &&
722 dv > dm[p + width] &&
723 dv > dm[p + width + 1] &&
725 dv > d[p - width - 1] &&
727 dv > d[p - width + 1] &&
730 dv > d[p + width - 1] &&
732 dv > d[p + width + 1]
737 dv < dp[p - width - 1] &&
738 dv < dp[p - width] &&
739 dv < dp[p - width + 1] &&
742 dv < dp[p + width - 1] &&
743 dv < dp[p + width] &&
744 dv < dp[p + width + 1] &&
747 dv < dm[p - width - 1] &&
748 dv < dm[p - width] &&
749 dv < dm[p - width + 1] &&
752 dv < dm[p + width - 1] &&
753 dv < dm[p + width] &&
754 dv < dm[p + width + 1] &&
756 dv < d[p - width - 1] &&
758 dv < d[p - width + 1] &&
761 dv < d[p + width - 1] &&
763 dv < d[p + width + 1]
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);
784 for (i = 0; i < nBlurredImages; i++)
785 delete ppBlurredImages[i];
786 for (i = 0; i < nDOGImages; i++)
787 delete ppDOGImages[i];
static void Diff(const CFloatMatrix *pInputImage1, const CFloatMatrix *pInputImage2, CFloatMatrix *pOutputImage)
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)
GLenum GLenum GLenum GLenum GLenum scale
int width
The width of the image in pixels.
static int m_bInitialized
GLenum GLsizei GLenum GLenum const GLvoid * image
~CSIFTFeatureCalculator()
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 ...
static float SIFTDiffSigmas[MAX_SCALES]
void FindScaleSpaceExtrema(const CFloatMatrix *pImage, float scale, int nOctave)
unsigned char * pixels
The pointer to the the pixels.
Data structure for the representation of SIFT features.
bool AddElement(CDynamicArrayElement *pElement, bool bAddUniqueOnly=false, bool bManageMemory=true)
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 int SIFTPointers[256]
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.
static float SIFTOrientationWeights[256 *(MAX_SCALES+1)]
int height
The height of the image in pixels.
static float SIFTSigmas[MAX_SCALES]
static float SIFTWeights[256]
static float prescaledsigma_
GLenum GLsizei GLsizei height
GLenum GLenum GLenum input
ImageType type
The type of the image.
static void InitializeVariables()
void AddElement(const T &element)
static float SIFTDescriptorWeights[256]
static void DetermineDominatingOrientations(const CFloatMatrix *pAngleMatrix, const CFloatMatrix *pMagnitudeMatrix, CDynamicArrayTemplate< float > &orientations, bool bPerform80PercentCheck)
static int SIFTKernelRadius[MAX_SCALES]
static float edgethreshold_
void AddElement(T *pElement)
CDynamicArray * m_pResultList
bool Resize(const CByteImage *pInputImage, CByteImage *pOutputImage, const MyRegion *pROI=0, bool bInterpolation=true)
Resizes a CByteImage and writes the result to a CByteImage.