SIFTFeatureCalculator.cpp
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 // ****************************************************************************
00036 // Filename:  SIFTFeatureCalculator.cpp
00037 // Author:    Pedram Azad, Lars Paetzold
00038 // Date:      24.09.2008
00039 // ****************************************************************************
00040 
00041 #include <new> // for explicitly using correct new/delete operators on VC DSPs
00042 
00043 #include "SIFTFeatureCalculator.h"
00044 
00045 #include "Image/ImageProcessor.h"
00046 #include "Image/ByteImage.h"
00047 #include "Math/FloatMatrix.h"
00048 #include "Math/Constants.h"
00049 #include "DataStructures/DynamicArray.h"
00050 #include "SIFTFeatureEntry.h"
00051 
00052 #include <math.h>
00053 
00054 
00055 
00056 // ****************************************************************************
00057 // Defines
00058 // ****************************************************************************
00059 
00060 #define S                               3               // number of scales per octave
00061 #define SIGMA0                  1.0f    // initial sigma of each octave
00062 #define PRESIGMA                0.5f    // sigma of the input image
00063 #define PRESCALE                1.0f    // input will be prescaled, 2.0f doubles size, 0.5f half size
00064 #define EDGE_THRESHOLD  10.0f
00065 
00066 
00067 // ****************************************************************************
00068 // Static variables
00069 // ****************************************************************************
00070 
00071 float CSIFTFeatureCalculator::edgethreshold_ = (EDGE_THRESHOLD + 1) * (EDGE_THRESHOLD + 1) / EDGE_THRESHOLD;
00072 float CSIFTFeatureCalculator::k_ = powf(2.0f, 1.0f / S);
00073 float CSIFTFeatureCalculator::diffk_ = sqrtf(k_ * k_ - 1);
00074 float CSIFTFeatureCalculator::prescaledsigma_ = PRESIGMA * PRESCALE;
00075 float CSIFTFeatureCalculator::diffsigma0_ = SIGMA0 * SIGMA0 - prescaledsigma_ * prescaledsigma_;
00076 
00077 int CSIFTFeatureCalculator::m_bInitialized = false;
00078 int CSIFTFeatureCalculator::SIFTPointers[256]; 
00079 float CSIFTFeatureCalculator::SIFTWeights[256];
00080 float CSIFTFeatureCalculator::SIFTOrientationWeights[256 * (MAX_SCALES + 1)];
00081 float CSIFTFeatureCalculator::SIFTDescriptorWeights[256];
00082 float CSIFTFeatureCalculator::SIFTDiffSigmas[MAX_SCALES];
00083 float CSIFTFeatureCalculator::SIFTSigmas[MAX_SCALES];
00084 int       CSIFTFeatureCalculator::SIFTKernelRadius[MAX_SCALES];
00085 
00086 
00087 
00088 // ****************************************************************************
00089 // Constructor / Destructor
00090 // ****************************************************************************
00091 
00092 CSIFTFeatureCalculator::CSIFTFeatureCalculator(float fThreshold, int nOctaves)
00093 {
00094         m_fThreshold = fThreshold;
00095         m_nOctaves = nOctaves;
00096 
00097         m_pResultList = 0;
00098         m_bManageMemory = true;
00099         
00100         InitializeVariables();
00101 }
00102 
00103 CSIFTFeatureCalculator::~CSIFTFeatureCalculator()
00104 {
00105 }
00106 
00107 
00108 // ****************************************************************************
00109 // Methods
00110 // ****************************************************************************
00111 
00112 void CSIFTFeatureCalculator::InitializeVariables()
00113 {
00114         if (!m_bInitialized)
00115         {
00116                 int i, j, k, offset;
00117 
00118                 for (j = 0, offset = 0; j < 16; j++)
00119                 {
00120                         for (i = 0; i < 16; i++, offset++)
00121                         {
00122                                 // sigma = 8 according to paper (half of the window width, which is 16)
00123                                 // 2 * sigma * sigma = 128
00124                                 const int x = i / 4;
00125                                 const int y = j / 4;
00126                                 
00127                                 SIFTPointers[offset] = 8 * (4 * y + x);
00128                                 SIFTWeights[offset] = expf( -((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / 128.0f);
00129                         }
00130                 }
00131 
00132                 // sigmas, diffsigmas and kernel sizes
00133                 SIFTSigmas[0] = SIGMA0;
00134                 // calculate Gaussians
00135                 for (i = 1; i < S + 3; i++)
00136                 {
00137                         const float diffsigma = diffk_ * SIFTSigmas[i - 1];
00138                         const int nKernelRadius = int(ceil(3 * diffsigma));
00139                         const int nKernelSize = nKernelRadius * 2 + 1;
00140                         
00141                         SIFTSigmas[i] = SIFTSigmas[i - 1] * k_;
00142                         SIFTDiffSigmas[i] = diffsigma;
00143                         SIFTKernelRadius[i] = nKernelRadius;
00144                 }
00145 
00146                 // orientation weights
00147                 float sigma = 1.5f * SIGMA0;
00148                 for (k = 0, offset = 0; k <= MAX_SCALES; k++)
00149                 {
00150                         for (j = 0; j < 16; j++)
00151                                 for (i = 0; i < 16; i++)
00152                                         SIFTOrientationWeights[offset++] = expf(-((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / (2.0f * sigma * sigma));
00153 
00154                         sigma *= k_;
00155                 }
00156                 
00157                 // descriptor weights
00158                 sigma = 8.0f;
00159                 for (j = 0, offset = 0; j < 16; j++)
00160                         for (i = 0; i < 16; i++)
00161                                 SIFTDescriptorWeights[offset++] = expf(-((j - 7.5f) * (j - 7.5f) + (i - 7.5f) * (i - 7.5f)) / (2.0f * sigma * sigma));
00162                 
00163                 m_bInitialized = true;
00164         }
00165 }
00166 
00167 int CSIFTFeatureCalculator::CalculateFeatures(const CByteImage *pImage, CDynamicArray *pResultList, bool bManageMemory)
00168 {
00169         if (pImage->type != CByteImage::eGrayScale)
00170         {
00171                 printf("error: input image is not a grayscale image\n");
00172                 return -1;
00173         }
00174 
00175         m_pResultList = pResultList;
00176         m_bManageMemory = bManageMemory;
00177 
00178         if (PRESCALE == 1.0f)
00179         {
00180                 CFloatMatrix matrix(pImage->width, pImage->height);
00181                 
00182                 ImageProcessor::GaussianSmooth(pImage, &matrix, diffsigma0_ * diffsigma0_, 2 * int(ceil(3 * diffsigma0_)) + 1);
00183                 
00184                 FindScaleSpaceExtrema(&matrix, PRESCALE, m_nOctaves);
00185         }
00186         else
00187         {
00188                 const int newWidth = int(pImage->width * PRESCALE);
00189                 const int newHeight = int(pImage->height * PRESCALE);
00190 
00191                 CFloatMatrix matrix(newWidth, newHeight);
00192                 CByteImage image(newWidth, newHeight, CByteImage::eGrayScale);
00193                 
00194                 ImageProcessor::Resize(pImage, &image);
00195                 ImageProcessor::GaussianSmooth(&image, &matrix, diffsigma0_ * diffsigma0_, 2 * int(ceil(3 * diffsigma0_)) + 1);
00196                 
00197                 FindScaleSpaceExtrema(&matrix, PRESCALE, m_nOctaves);
00198         }
00199 
00200         return pResultList->GetSize();
00201 }
00202 
00203 
00204 void CSIFTFeatureCalculator::DetermineDominatingOrientations(const CFloatMatrix *pAngleMatrix, const CFloatMatrix *pMagnitudeMatrix, CDynamicArrayTemplate<float> &orientations, bool bPerform80PercentCheck)
00205 {
00206         const int nWindowSize = pAngleMatrix->columns;
00207         const int nPixels = nWindowSize * nWindowSize;
00208         int i;
00209         
00210         float histogram_space[36 + 2];
00211         float *histogram = histogram_space + 1;
00212   
00213         for (i = 0; i < 37; i++)
00214                 histogram[i] = 0.0f;
00215         
00216         const float *angles = pAngleMatrix->data;
00217         const float *magnitudes = pMagnitudeMatrix->data;
00218         const float factor = 18 / FLOAT_PI;
00219         
00220         for (i = 0; i < nPixels; i++)
00221         {
00222                 const int d = (int) (factor * angles[i] + 18);
00223                 histogram[d] += magnitudes[i];
00224         }
00225 
00226         // add hits in bin 36 to bin 0
00227         histogram[0] += histogram[36];
00228         
00229         // find highest peak
00230         float max = 0.0f;
00231         int best_i = -1;
00232         for (i = 0; i < 36; i++)
00233                 if (histogram[i] > max)
00234                 {
00235                         max = histogram[i];
00236                         best_i = i;
00237                 }
00238 
00239         // optimization trick
00240         histogram[-1] = histogram[35];
00241         histogram[36] = histogram[0];
00242 
00243         if (bPerform80PercentCheck)
00244         {
00245                 // prepare 80% check
00246                 max *= 0.8f;
00247                 
00248                 // store peaks
00249                 for (i = 0; i < 36; i++)
00250                 {
00251                         if (histogram[i] >= max && histogram[i] > histogram[i + 1] && histogram[i] > histogram[i - 1])
00252                         {
00253                                 // parabola fitting
00254                                 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;
00255               
00256                                 if (angle < 0.0f)
00257                                         angle += 360.0f;
00258               
00259                                 orientations.AddElement(angle);
00260                         }
00261                 }
00262         }
00263         else
00264         {
00265                 if (best_i != -1 && histogram[best_i] > histogram[best_i + 1] && histogram[best_i] > histogram[best_i - 1])
00266                 {
00267                         // parabola fitting
00268                         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;
00269       
00270                         if (angle < 0.0f)
00271                                 angle += 360.0f;
00272       
00273                         orientations.AddElement(angle);
00274                 }
00275         }
00276 }
00277 
00278 
00279 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CFloatMatrix *pImage, CDynamicArray *pResultList, float xp, float yp, float scale, float sigma, const float *pOrientationWeights, bool bManageMemory, bool bPerform80PercentCheck)
00280 {
00281         const int width = pImage->columns;
00282         const int height = pImage->rows;
00283         const float *input = pImage->data;
00284 
00285         // determine upper left corner of window and check boundaries
00286         int x0 = int(xp + 0.5f) - 9;
00287         int y0 = int(yp + 0.5f) - 9;
00288 
00289         if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height) 
00290                 return;
00291         
00292         // calculate gradients, angles and magnitude
00293         CFloatMatrix angleMatrix(16, 16);
00294         CFloatMatrix magnitudeMatrix(16, 16);
00295         float *angles = angleMatrix.data;
00296         float *magnitudes = magnitudeMatrix.data;
00297         const int diff = width - 16;
00298         
00299         for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
00300         {
00301                 for (int x = 0; x < 16; x++, input_offset++, offset++)
00302                 {
00303                         const float gx = input[input_offset + 1] - input[input_offset - 1];
00304                         const float gy = input[input_offset + width] - input[input_offset - width];
00305                         
00306                         angles[offset] = atan2f(gy, gx);
00307                         magnitudes[offset] = sqrtf(gx * gx + gy * gy) * pOrientationWeights[offset];
00308                 }
00309         }
00310         
00311         // find dominating orientations
00312         CDynamicArrayTemplate<float> orientations(20);
00313         DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
00314         
00315         // apply descriptor weights (undo orientation weights)
00316         for (int i = 0; i < 256; i++)
00317                 magnitudes[i] = magnitudes[i] / pOrientationWeights[i] * SIFTDescriptorWeights[i];
00318 
00319         // create SIFT descriptor for each dominating orientation
00320         const int nSize = orientations.GetSize();
00321         for (int k = 0; k < nSize; k++)
00322         {
00323                 int i;
00324                         
00325                 CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], sigma / scale);
00326                 float *feature_vector = pEntry->m_pFeature;
00327                 
00328                 for (i = 0; i < 128; i++)
00329                         feature_vector[i] = 0.0f;
00330 
00331                 // create descriptor
00332                 const float angle = -pEntry->angle * FLOAT_DEG2RAD;
00333                 const float cosphi = cosf(angle);
00334                 const float sinphi = sinf(angle);
00335 
00336                 for (int y = 0, offset = 0; y < 16; y++)
00337                 {
00338                         for (int x = 0; x < 16; x++, offset++)
00339                         {
00340                                 const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
00341                                 const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
00342                                 
00343                                 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
00344                                 {
00345                                         const int offset_ = y_ * 16 + x_;
00346 
00347                                         float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
00348                                         phi += angle / FLOAT_PI; // [-2, 2)
00349                                         if (phi < 0.0f) phi += 2.0f; // [0, 2)
00350                                         int d = int(4.0f * phi);
00351                                         if (d > 7) d = 7;
00352 
00353                                         feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
00354                                 }
00355                         }
00356                 }
00357                 
00358                 // normalize and cut off entries > 0.2
00359                 bool bChanged = false;
00360                 float sum1 = 0.0f, sum2 = 0.0f;
00361                 
00362                 for (i = 0; i < 128; i++) 
00363                         sum1 += feature_vector[i] * feature_vector[i];
00364                 
00365                 sum1 = sqrtf(sum1);
00366                 
00367                 for (i = 0; i < 128; i++)
00368                 {
00369                         feature_vector[i] /= sum1;
00370                         
00371                         if (feature_vector[i] > 0.2f)
00372                         { 
00373                                 feature_vector[i] = 0.2f;
00374                                 bChanged = true;
00375                         }
00376                         
00377                         sum2 += feature_vector[i] * feature_vector[i];
00378                 }
00379     
00380                 if (bChanged)
00381                 {
00382                         sum2 = sqrtf(sum2);
00383                         
00384                         for (int i = 0; i < 128; i++) 
00385                                 feature_vector[i] /= sum2;
00386                 }
00387 
00388                 pResultList->AddElement(pEntry, false, bManageMemory);
00389         }
00390 }
00391 
00392 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CByteImage *pImage, CDynamicArray *pResultList, float xp, float yp, float scale, bool bManageMemory, bool bPerform80PercentCheck)
00393 {
00394         const int width = pImage->width;
00395         const int height = pImage->height;
00396         const unsigned char *input = pImage->pixels;
00397 
00398         // determine upper left corner of window and check boundaries
00399         int x0 = int(xp + 0.5f) - 18 / 2;
00400         int y0 = int(yp + 0.5f) - 18 / 2;
00401 
00402         if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height) 
00403                 return;
00404         
00405         // calculate gradients, angles and magnitude
00406         CFloatMatrix angleMatrix(16, 16);
00407         CFloatMatrix magnitudeMatrix(16, 16);
00408         float *angles = angleMatrix.data;
00409         float *magnitudes = magnitudeMatrix.data;
00410         const int diff = width - 16;
00411 
00412         for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
00413         {
00414                 for (int x = 0; x < 16; x++, input_offset++, offset++)
00415                 {
00416                         const int gx = input[input_offset + 1] - input[input_offset - 1];
00417                         const int gy = input[input_offset + width] - input[input_offset - width];
00418                         
00419                         angles[offset] = atan2f((float) gy, (float) gx);
00420                         magnitudes[offset] = sqrtf(float(gx * gx + gy * gy)); // weighting with Gaussian is ommited in this version
00421                 }
00422         }
00423         
00424         // find dominating orientations
00425         CDynamicArrayTemplate<float> orientations(20);
00426         DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
00427 
00428         // create SIFT descriptor for each dominating orientation
00429         const int nSize = orientations.GetSize();
00430         for (int k = 0; k < nSize; k++)
00431         {
00432                 int i;
00433                         
00434                 CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], scale);
00435                 float *feature_vector = pEntry->m_pFeature;
00436                     
00437                 for (i = 0; i < 128; i++)
00438                         feature_vector[i] = 0.0f;
00439 
00440                 // create descriptor
00441                 const float angle = -pEntry->angle * FLOAT_DEG2RAD;
00442                 const float cosphi = cosf(angle);
00443                 const float sinphi = sinf(angle);
00444 
00445                 for (int y = 0, offset = 0; y < 16; y++)
00446                 {
00447                         for (int x = 0; x < 16; x++, offset++)
00448                         {
00449                                 const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
00450                                 const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
00451                                 
00452                                 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
00453                                 {
00454                                         const int offset_ = y_ * 16 + x_;
00455 
00456                                         float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
00457                                         phi += angle / FLOAT_PI; // [-2, 2)
00458                                         if (phi < 0.0f) phi += 2.0f; // [0, 2)
00459                                         int d = int(4.0f * phi);
00460                                         if (d > 7) d = 7;
00461 
00462                                         feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
00463                                 }
00464                         }
00465                 }
00466                 
00467                 // normalize and cut off entries > 0.2f
00468                 bool bChanged = false;
00469                 float sum1 = 0.0f, sum2 = 0.0f;
00470                 
00471                 for (i = 0; i < 128; i++) 
00472                         sum1 += feature_vector[i] * feature_vector[i];
00473                 
00474                 sum1 = 1.0f / sqrtf(sum1);
00475                 
00476                 for (i = 0; i < 128; i++)
00477                 {
00478                         feature_vector[i] *= sum1;
00479                         
00480                         if (feature_vector[i] > 0.2f)
00481                         { 
00482                                 feature_vector[i] = 0.2f;
00483                                 bChanged = true;
00484                         }
00485                         
00486                         sum2 += feature_vector[i] * feature_vector[i];
00487                 }
00488     
00489                 if (bChanged)
00490                 {
00491                         sum2 = 1.0f / sqrtf(sum2);
00492                         
00493                         for (int i = 0; i < 128; i++) 
00494                                 feature_vector[i] *= sum2;
00495                 }
00496 
00497                 pResultList->AddElement(pEntry, false, bManageMemory);
00498         }
00499 }
00500 
00501 void CSIFTFeatureCalculator::CreateSIFTDescriptors(const CByteImage *pImage, CDynamicArrayTemplatePointer<CFeatureEntry> &resultList, float xp, float yp, float scale, bool bPerform80PercentCheck)
00502 {
00503         const int width = pImage->width;
00504         const int height = pImage->height;
00505         const unsigned char *input = pImage->pixels;
00506 
00507         // determine upper left corner of window and check boundaries
00508         int x0 = int(xp + 0.5f) - 18 / 2;
00509         int y0 = int(yp + 0.5f) - 18 / 2;
00510 
00511         if (x0 < 0 || y0 < 0 || x0 + 17 >= width || y0 + 17 >= height) 
00512                 return;
00513         
00514         // calculate gradients, angles and magnitude
00515         CFloatMatrix angleMatrix(16, 16);
00516         CFloatMatrix magnitudeMatrix(16, 16);
00517         float *angles = angleMatrix.data;
00518         float *magnitudes = magnitudeMatrix.data;
00519         const int diff = width - 16;
00520 
00521         for (int y = 0, input_offset = (y0 + 1) * width + x0 + 1, offset = 0; y < 16; y++, input_offset += diff)
00522         {
00523                 for (int x = 0; x < 16; x++, input_offset++, offset++)
00524                 {
00525                         const int gx = input[input_offset + 1] - input[input_offset - 1];
00526                         const int gy = input[input_offset + width] - input[input_offset - width];
00527                         
00528                         angles[offset] = atan2f((float) gy, (float) gx);
00529                         magnitudes[offset] = sqrtf(float(gx * gx + gy * gy)); // weighting with Gaussian is ommited in this version
00530                 }
00531         }
00532         
00533         // find dominating orientations
00534         CDynamicArrayTemplate<float> orientations(20);
00535         DetermineDominatingOrientations(&angleMatrix, &magnitudeMatrix, orientations, bPerform80PercentCheck);
00536 
00537         // create SIFT descriptor for each dominating orientation
00538         const int nSize = orientations.GetSize();
00539         for (int k = 0; k < nSize; k++)
00540         {
00541                 int i;
00542                         
00543                 CSIFTFeatureEntry *pEntry = new CSIFTFeatureEntry(xp / scale, yp / scale, orientations[k], scale);
00544                 float *feature_vector = pEntry->m_pFeature;
00545                     
00546                 for (i = 0; i < 128; i++)
00547                         feature_vector[i] = 0.0f;
00548 
00549                 // create descriptor
00550                 const float angle = -pEntry->angle * FLOAT_DEG2RAD;
00551                 const float cosphi = cosf(angle);
00552                 const float sinphi = sinf(angle);
00553 
00554                 for (int y = 0, offset = 0; y < 16; y++)
00555                 {
00556                         for (int x = 0; x < 16; x++, offset++)
00557                         {
00558                                 const int x_ = int(8.0f + cosphi * (x - 7.5f) - sinphi * (y - 7.5f));
00559                                 const int y_ = int(8.0f + sinphi * (x - 7.5f) + cosphi * (y - 7.5f));
00560                                 
00561                                 if (x_ >= 0 && x_ < 16 && y_ >= 0 && y_ < 16)
00562                                 {
00563                                         const int offset_ = y_ * 16 + x_;
00564 
00565                                         float phi = 1 + angles[offset] / FLOAT_PI; // [0, 2)
00566                                         phi += angle / FLOAT_PI; // [-2, 2)
00567                                         if (phi < 0.0f) phi += 2.0f; // [0, 2)
00568                                         int d = int(4.0f * phi);
00569                                         if (d > 7) d = 7;
00570 
00571                                         feature_vector[SIFTPointers[offset_] + d] += SIFTWeights[offset_] * magnitudes[offset];
00572                                 }
00573                         }
00574                 }
00575                 
00576                 // normalize and cut off entries > 0.2f
00577                 bool bChanged = false;
00578                 float sum1 = 0.0f, sum2 = 0.0f;
00579                 
00580                 for (i = 0; i < 128; i++) 
00581                         sum1 += feature_vector[i] * feature_vector[i];
00582                 
00583                 sum1 = 1.0f / sqrtf(sum1);
00584                 
00585                 for (i = 0; i < 128; i++)
00586                 {
00587                         feature_vector[i] *= sum1;
00588                         
00589                         if (feature_vector[i] > 0.2f)
00590                         { 
00591                                 feature_vector[i] = 0.2f;
00592                                 bChanged = true;
00593                         }
00594                         
00595                         sum2 += feature_vector[i] * feature_vector[i];
00596                 }
00597     
00598                 if (bChanged)
00599                 {
00600                         sum2 = 1.0f / sqrtf(sum2);
00601                         
00602                         for (int i = 0; i < 128; i++) 
00603                                 feature_vector[i] *= sum2;
00604                 }
00605 
00606                 resultList.AddElement(pEntry);
00607         }
00608 }
00609 
00610 
00611 static void ScaleDown(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
00612 {
00613         const float *input = pInputImage->data;
00614         float *output = pOutputImage->data;
00615         
00616         const int output_width = pOutputImage->columns;
00617         const int output_height = pOutputImage->rows;
00618         const int width = pInputImage->columns;
00619         
00620         for (int v = 0, offset = 0, offset_ = 0; v < output_height; v++, offset_ += width)
00621         {
00622                 for (int u = 0; u < output_width; u++, offset++, offset_ += 2)
00623                         output[offset] = input[offset_];
00624         }
00625 }
00626 
00627 static void Diff(const CFloatMatrix *pInputImage1, const CFloatMatrix *pInputImage2, CFloatMatrix *pOutputImage)
00628 {
00629         float *input1 = pInputImage1->data;
00630         float *input2 = pInputImage2->data;
00631         float *output = pOutputImage->data;
00632   
00633         const int nPixels = pInputImage1->rows * pInputImage1->columns;
00634   
00635         for (int i = 0; i < nPixels; i++)
00636                 *output++ = *input1++ - *input2++;
00637 }
00638 
00639 
00640 void CSIFTFeatureCalculator::FindScaleSpaceExtrema(const CFloatMatrix *pImage, float scale, int nOctave)
00641 {
00642         const int width = pImage->columns;
00643         const int height = pImage->rows;
00644 
00645         if (nOctave == 0 || width < 40 || height < 40)
00646                 return;
00647 
00648         const int nBlurredImages = S + 3;
00649         const int nDOGImages = nBlurredImages - 1;
00650         
00651         int i;
00652 
00653         CFloatMatrix** ppBlurredImages = new CFloatMatrix*[nBlurredImages];
00654         CFloatMatrix** ppDOGImages = new CFloatMatrix*[nDOGImages];
00655 
00656         CFloatMatrix tempImage(height, width);
00657 
00658         // calculate Gaussians
00659         ppBlurredImages[0] = new CFloatMatrix(width, height);
00660         ImageProcessor::CopyMatrix(pImage, ppBlurredImages[0]);
00661         
00662         for (i = 1; i < nBlurredImages; i++)
00663         {
00664                 ppBlurredImages[i] = new CFloatMatrix(width, height);           
00665                 ImageProcessor::GaussianSmooth(ppBlurredImages[i - 1], ppBlurredImages[i], SIFTDiffSigmas[i] * SIFTDiffSigmas[i], 2 * SIFTKernelRadius[i] + 1);
00666         }
00667 
00668         // halfsize image with doubled sigma for later
00669         // ppBlurredImages[s] because ppBlurredImages[i] has (k^i * sigma)
00670         // therefore k^s * sigma = 2 * sigma as k^s = 2
00671         /*
00672         the octave is from sigma to 2 * sigma or k^0*sigma to k^s * sigma
00673         so we have s intervals from 0 to s having s+1 blurred images
00674         but for extrema detection we always need one image before and one after
00675         therefore if we want D(k^0*sigma) to D(k^s * sigma) we need
00676         D(k^-1*sigma) to D(k^s+1*sigma) having s+3 images.
00677         but we shift it to D(k^0*sigma) till D(k^s+2*digma)
00678         therefore our doubled sigma is like said before at k^s*sigma.
00679         but important is that we have to go from 0 to s+2.
00680         */
00681         
00682         // calculate Difference of Gaussians (DoG)
00683         for (i = 0; i < nDOGImages; i++)
00684         {
00685                 ppDOGImages[i] = new CFloatMatrix(width, height);
00686                 Diff(ppBlurredImages[i + 1], ppBlurredImages[i], ppDOGImages[i]);
00687         }
00688                 
00689         // find scale space extrema
00690         const float fThreshold = m_fThreshold * 255.0f;
00691         for (i = 1; i < nDOGImages - 1; i++)
00692         {
00693                 const float *dm = ppDOGImages[i - 1]->data;
00694                 const float *d  = ppDOGImages[i]->data;
00695                 const float *dp = ppDOGImages[i + 1]->data;
00696                 
00697                 for (int y = 1, p = width + 1; y < height - 1; y++, p += 2)
00698                 {
00699                         for (int x = 1; x < width - 1; x++, p++)
00700                         {
00701                                 const float dv = d[p];
00702                                 
00703                                 if (fabsf(dv) > fThreshold &&
00704                                         ((
00705                                         dv > dp[p] && 
00706                                         dv > dp[p - width - 1] && 
00707                                         dv > dp[p - width] && 
00708                                         dv > dp[p - width + 1] && 
00709                                         dv > dp[p - 1] && 
00710                                         dv > dp[p + 1] && 
00711                                         dv > dp[p + width - 1] && 
00712                                         dv > dp[p + width] && 
00713                                         dv > dp[p + width + 1] &&
00714 
00715                                         dv > dm[p] &&
00716                                         dv > dm[p - width - 1] && 
00717                                         dv > dm[p - width] && 
00718                                         dv > dm[p - width + 1] && 
00719                                         dv > dm[p - 1] && 
00720                                         dv > dm[p + 1] && 
00721                                         dv > dm[p + width - 1] && 
00722                                         dv > dm[p + width] && 
00723                                         dv > dm[p + width + 1] &&
00724 
00725                                         dv > d[p - width - 1] && 
00726                                         dv > d[p - width] && 
00727                                         dv > d[p - width + 1] && 
00728                                         dv > d[p - 1] && 
00729                                         dv > d[p + 1] && 
00730                                         dv > d[p + width - 1] && 
00731                                         dv > d[p + width] && 
00732                                         dv > d[p + width + 1]
00733                                         )
00734                                         ||
00735                                         (
00736                                         dv < dp[p] && 
00737                                         dv < dp[p - width - 1] && 
00738                                         dv < dp[p - width] && 
00739                                         dv < dp[p - width + 1] && 
00740                                         dv < dp[p - 1] && 
00741                                         dv < dp[p + 1] && 
00742                                         dv < dp[p + width - 1] && 
00743                                         dv < dp[p + width] && 
00744                                         dv < dp[p + width + 1] &&
00745 
00746                                         dv < dm[p] &&
00747                                         dv < dm[p - width - 1] && 
00748                                         dv < dm[p - width] && 
00749                                         dv < dm[p - width + 1] && 
00750                                         dv < dm[p - 1] && 
00751                                         dv < dm[p + 1] && 
00752                                         dv < dm[p + width - 1] && 
00753                                         dv < dm[p + width] && 
00754                                         dv < dm[p + width + 1] &&
00755 
00756                                         dv < d[p - width - 1] && 
00757                                         dv < d[p - width] && 
00758                                         dv < d[p - width + 1] && 
00759                                         dv < d[p - 1] && 
00760                                         dv < d[p + 1] && 
00761                                         dv < d[p + width - 1] && 
00762                                         dv < d[p + width] && 
00763                                         dv < d[p + width + 1]
00764                                         ))
00765                                         )
00766                                 {
00767                                          // eliminating edge responses
00768                                         const float Dxx = (d[p + 1] + d[p - 1] - 2.0f * d[p]);
00769                                         const float Dyy = (d[p + width] + d[p - width] - 2.0f * d[p]);
00770                                         const float Dxy = 0.25f * (d[p + 1 + width] + d[p - 1 - width] - d[p - 1 + width] - d[p + 1 - width]);
00771                                         const float score = (Dxx + Dyy) * (Dxx + Dyy) / (Dxx * Dyy - Dxy * Dxy); 
00772 
00773                                         if (fabsf(score) < edgethreshold_)      
00774                                                 CreateSIFTDescriptors(ppBlurredImages[i], m_pResultList, float(x), float(y), scale, SIFTSigmas[i], SIFTOrientationWeights + i * 256, m_bManageMemory);
00775                                 }
00776                         }
00777                 }
00778         }
00779 
00780         CFloatMatrix scaled_image(width / 2, height / 2);
00781         ScaleDown(ppBlurredImages[S], &scaled_image);
00782 
00783         // free images
00784         for (i = 0; i < nBlurredImages; i++)
00785                 delete ppBlurredImages[i];
00786         for (i = 0; i < nDOGImages; i++)
00787                 delete ppDOGImages[i];
00788         
00789         FindScaleSpaceExtrema(&scaled_image, scale / 2, nOctave - 1);
00790 }


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:58