HarrisSIFTFeatureCalculator.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:  HarrisSIFTFeatureCalculator.cpp
00037 // Author:    Pedram Azad
00038 // Date:      20.11.2007
00039 // ****************************************************************************
00040 
00041 // ******************************************************************************************************
00042 // Implementation of the paper:
00043 // P. Azad, T. Asfour, R. Dillmann,
00044 // "Combining Harris Interest Points and the SIFT Descriptor for Fast Scale-Invariant Object Recognition"
00045 // IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS),
00046 // St. Louis, USA, pp. 4275-4280, 2009.
00047 // ******************************************************************************************************
00048 
00049 #include "HarrisSIFTFeatureCalculator.h"
00050 
00051 #include "Image/ImageProcessor.h"
00052 #include "Image/ByteImage.h"
00053 #include "Math/FloatMatrix.h"
00054 
00055 #include "DataStructures/DynamicArray.h"
00056 #include "Features/SIFTFeatures/SIFTFeatureCalculator.h"
00057 #include "Features/SIFTFeatures/SIFTFeatureEntry.h"
00058 
00059 #include <math.h>
00060 
00061 
00062 
00063 static const float scale_factor = 0.75f;
00064 
00065 
00066 
00067 // ****************************************************************************
00068 // Constructor / Destructor
00069 // ****************************************************************************
00070 
00071 CHarrisSIFTFeatureCalculator::CHarrisSIFTFeatureCalculator(float fThreshold, int nLevels, int nMaxInterestPoints)
00072 {
00073         CSIFTFeatureCalculator::InitializeVariables();
00074 
00075         m_nMaxInterestPoints = nMaxInterestPoints;
00076         m_nLevels = nLevels;
00077         m_fThreshold = fThreshold;
00078         m_fMinDistance = 5.0f;
00079 
00080         m_bPerform80PercentCheck = true;
00081 
00082         m_pInterestPoints = new Vec2d[m_nMaxInterestPoints];
00083         m_nInterestPoints = 0;
00084 
00085         m_pResultList = 0;
00086         m_pResultListTemplate = 0;
00087         m_bTemplateList = true;
00088         m_bManageMemory = true;
00089 
00090         m_pImage = 0;
00091 }
00092 
00093 CHarrisSIFTFeatureCalculator::~CHarrisSIFTFeatureCalculator()
00094 {
00095         delete [] m_pInterestPoints;
00096 }
00097 
00098 
00099 // ****************************************************************************
00100 // Methods
00101 // ****************************************************************************
00102 
00103 CFeatureEntry* CHarrisSIFTFeatureCalculator::CreateCopy(const CFeatureEntry *pFeatureEntry)
00104 {
00105         return new CSIFTFeatureEntry(*((CSIFTFeatureEntry *) pFeatureEntry));
00106 }
00107 
00108 int CHarrisSIFTFeatureCalculator::CalculateFeatures(const CByteImage *pImage, CDynamicArray *pResultList, bool bManageMemory)
00109 {
00110         if (pImage->type != CByteImage::eGrayScale)
00111         {
00112                 printf("error: input image is not a grayscale image\n");
00113                 return -1;
00114         }
00115 
00116         m_bTemplateList = false;
00117         m_bManageMemory = bManageMemory;
00118 
00119         m_pResultList = pResultList;
00120         m_pImage = pImage;
00121         
00122         FindInterestPoints(pImage, 1, m_nLevels);
00123 
00124         return pResultList->GetSize();
00125 }
00126 
00127 int CHarrisSIFTFeatureCalculator::CalculateFeatures(const CByteImage *pImage, CDynamicArrayTemplatePointer<CFeatureEntry> &resultList)
00128 {
00129         if (pImage->type != CByteImage::eGrayScale)
00130         {
00131                 printf("error: input image is not a grayscale image\n");
00132                 return -1;
00133         }
00134 
00135         m_bTemplateList = true;
00136 
00137         m_pResultListTemplate = &resultList;
00138         m_pImage = pImage;
00139         
00140         FindInterestPoints(pImage, 1, m_nLevels);
00141 
00142         return resultList.GetSize();
00143 }
00144 
00145 void CHarrisSIFTFeatureCalculator::FindInterestPoints(const CByteImage *pImage, float scale, int nLevel)
00146 {
00147         // calculate feature points
00148         m_nInterestPoints = ImageProcessor::CalculateHarrisInterestPoints(pImage, m_pInterestPoints, m_nMaxInterestPoints, m_fThreshold, m_fMinDistance);
00149 
00150         if (m_bTemplateList)
00151         {
00152                 for (int i = 0; i < m_nInterestPoints; i++)
00153                         CSIFTFeatureCalculator::CreateSIFTDescriptors(pImage, *m_pResultListTemplate, m_pInterestPoints[i].x, m_pInterestPoints[i].y, scale, m_bPerform80PercentCheck);
00154         }
00155         else
00156         {
00157                 for (int i = 0; i < m_nInterestPoints; i++)
00158                         CSIFTFeatureCalculator::CreateSIFTDescriptors(pImage, m_pResultList, m_pInterestPoints[i].x, m_pInterestPoints[i].y, scale, m_bManageMemory, m_bPerform80PercentCheck);
00159         }
00160 
00161         if (nLevel > 1)
00162         {
00163                 // recursive call
00164                 CByteImage scaled_image(int(m_pImage->width * powf(scale_factor, float(m_nLevels - nLevel + 1)) + 0.5f), int(m_pImage->height * powf(scale_factor, float(m_nLevels - nLevel + 1.0f)) + 0.5f), CByteImage::eGrayScale);
00165                 ImageProcessor::Resize(m_pImage, &scaled_image);
00166                 FindInterestPoints(&scaled_image, scale * scale_factor, nLevel - 1);
00167         }
00168 }


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:57