SiftPyramid.h
Go to the documentation of this file.
00001 
00002 //      File:           SiftPyramid.h
00003 //      Author:         Changchang Wu
00004 //      Description : interface for the SiftPyramid class.
00005 //              SiftPyramid:                    data storage for SIFT
00006 //              |---PyramidGL:                  OpenGL based implementation
00007 //              |   |--PyramidNaive:    Unpacked version 
00008 //              |   |--PyramidPacked:   packed version 
00009 //              |--PyramidCU:                   CUDA-based implementation
00010 //
00011 //      Copyright (c) 2007 University of North Carolina at Chapel Hill
00012 //      All Rights Reserved
00013 //
00014 //      Permission to use, copy, modify and distribute this software and its
00015 //      documentation for educational, research and non-profit purposes, without
00016 //      fee, and without a written agreement is hereby granted, provided that the
00017 //      above copyright notice and the following paragraph appear in all copies.
00018 //      
00019 //      The University of North Carolina at Chapel Hill make no representations
00020 //      about the suitability of this software for any purpose. It is provided
00021 //      'as is' without express or implied warranty. 
00022 //
00023 //      Please send BUG REPORTS to ccwu@cs.unc.edu
00024 //
00026 
00027 
00028 
00029 #ifndef _SIFT_PYRAMID_H
00030 #define _SIFT_PYRAMID_H
00031 
00032 
00033 class GLTexImage;
00034 class GLTexInput;
00035 class SiftParam;
00036 class GlobalUtil;
00037 
00039 //class SiftPyramid
00040 //description: virutal class of SIFT data pyramid
00041 //                         provides functions for SiftPU to run steps of GPU SIFT
00042 //                         class PyramidNaive is the first implementation
00043 //                         class PyramidPacked is a better OpenGL implementation
00044 //                         class PyramidCU is a CUDA based implementation
00046 
00047 #define NO_DUPLICATE_DOWNLOAD
00048 
00049 class SiftPyramid : public GlobalUtil
00050 {
00051 public:
00052         enum{
00053                 DATA_GAUSSIAN   = 0,
00054                 DATA_DOG                = 1,
00055                 DATA_KEYPOINT   = 2,
00056                 DATA_GRAD               = 3,
00057                 DATA_ROT                = 4,
00058                 DATA_NUM                = 5
00059         };
00060         enum{
00061                 SIFT_SKIP_FILTERING             = 0x01,
00062                 SIFT_SKIP_DETECTION             = 0x02,
00063                 SIFT_SKIP_ORIENTATION   = 0x04,
00064         SIFT_RECT_DESCRIPTION   = 0x08
00065         };
00066 protected:
00067         SiftParam&      param;
00068         int                     _hpLevelNum;
00069         int*            _levelFeatureNum;
00070         int                     _featureNum;
00071         float*          _histo_buffer;
00072     //keypoint list
00073         int                     _existing_keypoints;
00074         vector<int>     _keypoint_index;
00075         //display vbo
00076         GLuint*     _featureDisplayVBO;
00077         GLuint*         _featurePointVBO;
00078 public:
00079         //
00080         float           _timing[8];
00081         //image size related
00082         //first octave
00083         int                     _octave_min;
00084         //how many octaves
00085         int                     _octave_num;
00086         //pyramid storage
00087         int                     _pyramid_octave_num;
00088         int                     _pyramid_octave_first;
00089         int                     _pyramid_width;
00090         int                     _pyramid_height;
00091         int                     _down_sample_factor;
00092         int                     _allocated; 
00093         int                 _alignment;
00094     int         _siftgpu_failed;
00095 public:
00096         vector<float>   _keypoint_buffer;
00097         vector<float>   _descriptor_buffer;
00098 private:
00099         inline  void PrepareBuffer();
00100         inline  void LimitFeatureCount(int have_keylist = 0);
00101 public:
00102         //shared by all implementations
00103         virtual void RunSIFT(GLTexInput*input);
00104         virtual void SaveSIFT(const char * szFileName);
00105         virtual void CopyFeatureVector(float*keys, float *descriptors);
00106         virtual void SetKeypointList(int num, const float * keys, int run_on_current, int skip_orientation);
00107         //implementation-dependent functions
00108         virtual void GetFeatureDescriptors() = 0;
00109         virtual void GenerateFeatureListTex() =0;
00110         virtual void ReshapeFeatureListCPU() =0;
00111         virtual void GenerateFeatureDisplayVBO() =0;
00112         virtual void DownloadKeypoints() = 0;
00113         virtual void GenerateFeatureListCPU()=0;
00114         virtual void GenerateFeatureList()=0;
00115         virtual GLTexImage* GetLevelTexture(int octave, int level)=0;
00116         virtual GLTexImage* GetLevelTexture(int octave, int level, int dataName) = 0;
00117         virtual void BuildPyramid(GLTexInput * input)=0;
00118         virtual void ResizePyramid(int w, int h) = 0;
00119         virtual void InitPyramid(int w, int h, int ds = 0)=0;
00120         virtual void DetectKeypointsEX() = 0;
00121         virtual void ComputeGradient() = 0;
00122         virtual void GetFeatureOrientations() = 0;
00123         virtual void GetSimplifiedOrientation() = 0;
00124 
00126     virtual void CleanUpAfterSIFT()  {}
00127     virtual int  IsUsingRectDescription() {return 0; } 
00128     static  int  GetRequiredOctaveNum(int inputsz); 
00129 
00131     inline void SetFailStatus() {_siftgpu_failed = 1; }
00132     inline int  GetSucessStatus() {return _siftgpu_failed == 0; }
00133         inline int GetFeatureNum(){return _featureNum;}
00134         inline int GetHistLevelNum(){return _hpLevelNum;}
00135         inline const GLuint * GetFeatureDipslayVBO(){return _featureDisplayVBO;}
00136         inline const GLuint * GetPointDisplayVBO(){return _featurePointVBO;}
00137         inline const int * GetLevelFeatureNum(){return _levelFeatureNum;}
00138         inline void     GetPyramidTiming(float * timing){       for(int i = 0; i < 8; i++) timing[i] = _timing[i];      }
00139     inline void CleanupBeforeSIFT() 
00140     {
00141         _siftgpu_failed = 0;
00142         for(int i = 0; i < 8; ++i) _timing[i] = 0; 
00143     } 
00144         SiftPyramid(SiftParam&sp):param(sp)
00145         {
00146                 _featureNum = 0;
00147                 _featureDisplayVBO = 0;
00148                 _featurePointVBO = 0;
00149                 _levelFeatureNum = NULL;
00150                 _histo_buffer = NULL;
00151                 _hpLevelNum = 0;
00152 
00153                 //image size
00154                 _octave_num = 0;
00155                 _octave_min = 0;
00156                 _alignment = 1;
00157                 _pyramid_octave_num = _pyramid_octave_first = 0;
00158                 _pyramid_width = _pyramid_height = 0;
00159                 _allocated = 0;
00160                 _down_sample_factor = 0;
00161 
00163                 _existing_keypoints = 0;
00164         }
00165         virtual ~SiftPyramid() {};      
00166 
00167 #ifdef DEBUG_SIFTGPU
00168 private:
00169         void StopDEBUG();
00170         void BeginDEBUG(const char* imagepath);
00171         void WriteTextureForDEBUG(GLTexImage * tex, const char * namet, ...);
00172 #endif
00173 };
00174 
00175 #define SIFTGPU_ENABLE_REVERSE_ORDER
00176 #ifdef SIFTGPU_ENABLE_REVERSE_ORDER
00177 #define FIRST_OCTAVE(R)            (R? _octave_num - 1 : 0)
00178 #define NOT_LAST_OCTAVE(i, R)      (R? (i >= 0) : (i < _octave_num))
00179 #define GOTO_NEXT_OCTAVE(i, R)     (R? (--i) : (++i))
00180 #define FIRST_LEVEL(R)             (R? param._dog_level_num - 1 : 0)   
00181 #define GOTO_NEXT_LEVEL(j, R)      (R? (--j) : (++j))
00182 #define NOT_LAST_LEVEL(j, R)       (R? (j >= 0) : (j < param._dog_level_num))
00183 #define FOR_EACH_OCTAVE(i, R)      for(int i = FIRST_OCTAVE(R); NOT_LAST_OCTAVE(i, R); GOTO_NEXT_OCTAVE(i, R))
00184 #define FOR_EACH_LEVEL(j, R)       for(int j = FIRST_LEVEL(R);  NOT_LAST_LEVEL(j, R);  GOTO_NEXT_LEVEL(j, R))
00185 #else
00186 #define FOR_EACH_OCTAVE(i, R) for(int i = 0; i < _octave_num; ++i)
00187 #define FOR_EACH_LEVEL(j, R)  for(int j = 0; j < param._dog_level_num; ++j)
00188 #endif
00189 
00190 #endif 


siftgpu
Author(s): Changchang Wu
autogenerated on Wed Aug 26 2015 15:24:06