KeypointDescriptor.hh
Go to the documentation of this file.
00001 
00006 #ifndef P_KEYPOINT_DESCRIPTOR_HH
00007 #define P_KEYPOINT_DESCRIPTOR_HH
00008 
00009 #include <iostream>
00010 #include <fstream>
00011 #include <float.h>
00012 //#include <opencv/cv.h>
00013 //#include <opencv/cxcore.h>
00014 #include <opencv2/opencv.hpp>
00015 #include <blort/Recognizer3D/PNamespace.hh>
00016 #include <blort/Recognizer3D/Keypoint.hh>
00017 #include <blort/Recognizer3D/Array.hh>
00018 #include <blort/Recognizer3D/Vector2.hh>
00019 #include <blort/Recognizer3D/SDraw.hh>
00020 
00021 
00022 //#define SAVE_PATCHES
00023 
00024 #define PATCH_MASK_SIZE 16 
00025 
00026 
00027 namespace P
00028 {
00029 
00030 
00031 //class ObjectModel;
00032 
00033 
00034 class KeypointDescriptor : public Keypoint
00035 {
00036 public:
00037   enum Type
00038   {
00039     DOG_SIFT,
00040     LOWE_DOG_SIFT,
00041     MSER_SIFT,
00042     UVMSER_SIFT,
00043     HESLAP_SIFT,
00044     MAX_TYPE,
00045     UNDEF = MAX_TYPE
00046   };
00047 
00048   static float DOG_SIFT_THR;
00049   static float LOWE_DOG_SIFT_THR;
00050   static float MSER_SIFT_THR;
00051   static float COL_THR;
00052   static float HESLAP_SIFT_THR;
00053 
00054 
00055 public:
00056   static const unsigned KEDE_DELETE;             //delete occurrence
00057   static const unsigned KEDE_INSERT;             //insert to codebook
00058   static const unsigned KEDE_DETECTED;           //keypoint detected flag
00059 
00060   unsigned flags;     //flags
00061 
00062   Type type;
00063   float *vec;
00064   unsigned size;
00065 
00066   CvMat *pos;
00067   unsigned cnt_pos;
00068   P::Vector2 p_rect;
00069 
00070   IplImage *mask;        //mask for segmentation
00071   IplImage *bgmask;
00072   IplImage *patch;       //normalised grey scale patch
00073 
00074   //some statistics....
00075   float reliability;     //mean number of detections
00076   unsigned cnt_rel;
00077   float mean_error;   //mean projection error
00078   float var_error;    //variance of projection error
00079   unsigned cnt_err;             //number of possible detections
00080 
00081   unsigned occNum;             //number of occurrences within codebook ...
00082                                //... or number of matches of image keypoints
00083   unsigned chainId;
00084   unsigned chainCnt;
00085 
00086   KeypointDescriptor();
00087   KeypointDescriptor(Type t);
00088   KeypointDescriptor(KeypointDescriptor *k);
00089   KeypointDescriptor(Type t, double x, double y, float s, float a);
00090   KeypointDescriptor(Type t, double x,double y,float s,float a,
00091                      float _m11,float _m12,float _m21,float _m22);
00092   ~KeypointDescriptor();
00093 
00094   static const char* TypeName(Type t);
00095   static Type EnumType(const char *type_name);
00096   bool GetVoteCenter(KeypointDescriptor *current, Vector2 &v, 
00097                      double &delta_angle, double &delta_scale);
00098   void SaveMask(IplImage *img);
00099   void ProjectMask(KeypointDescriptor *model,IplImage *img, float w);
00100   void ProjectBgMask(KeypointDescriptor *model,IplImage *img, float w);
00101   void ProjectOccl(P::Vector2 &center, float scale, float angle, 
00102                    IplImage *img, float w);
00103   void SavePatch(IplImage *img);
00104   void ProjectPatch(KeypointDescriptor *model,IplImage *img);
00105   float Match(KeypointDescriptor *k);
00106   void ReadKeypoint( ifstream &in );
00107   void ReadDescriptor( ifstream &in, unsigned size_in);
00108   void WriteKeypoint( ofstream &out );
00109   void WriteDescriptor(ofstream &out );
00110 
00111   void SetReliability(float f);
00112   void SetError(float e); 
00113   void Copy(KeypointDescriptor *k);
00114   void AllocVec(unsigned s);
00115   void CopyVec(KeypointDescriptor *k);
00116   inline float* GetVec(){return vec;}
00117   inline float GetVec(unsigned i){return (i<size?vec[i]:0);}
00118   inline Type GetType(){return type;}
00119   inline unsigned GetSize(){return size;} 
00120   inline bool Have3D(){return (pos!=0?true:false);}
00121   float DistSqr(float *desc1, float *desc2, unsigned cnt);
00122   void Add(float *desc);
00123   void Div(float num);
00124   void Mul(float num);
00125   void SetZero();
00126   void MatchSift(KeypointDescriptor *k, float thr, float &dist); 
00127   inline float GetThr();
00128   inline void SetPos(float x, float y, float z);
00129  
00130   static void Draw(IplImage *img, KeypointDescriptor &k, CvScalar col);  
00131   static void LoadAll(ifstream &is, KeypointDescriptor &k);
00132   static void SaveAll(ofstream &os, const KeypointDescriptor &k);
00133 };
00134 
00135 
00136 void CopyVec(float *svec, float *dvec, unsigned size);
00137 void WriteKeypoints(P::Array<KeypointDescriptor*> &ks, const char* file, int format=0);
00138 void LoadKeypoints(const char* file, P::Array<KeypointDescriptor*> &ks, int format=0);
00139 void LoadLoweKeypoints(const char* file, P::Array<Keypoint*> &ks, int format=0);
00140 void LoadLoweKeypoints(const char* file, P::Array<KeypointDescriptor*> &ks, int format=0);
00141 
00142 
00143 
00144 
00145 
00146 
00147 /*************************** INLINE METHODES **************************/
00148 inline void KeypointDescriptor::AllocVec(unsigned s)
00149 {
00150   if (vec!=0) delete[] vec;
00151   size=s;
00152   vec = new float[size];
00153 }
00154 
00155 inline void KeypointDescriptor::CopyVec(KeypointDescriptor *k)
00156 {
00157   if (k->vec!=0){
00158     AllocVec(k->size);
00159     for (unsigned i=0; i<size; i++){
00160       vec[i]=k->vec[i];
00161     }
00162   }
00163 }
00164 
00165 inline void KeypointDescriptor::Copy(KeypointDescriptor *k)
00166 {
00167   p=k->p;
00168   if (k->Have3D())
00169   {
00170     if (!Have3D()) pos = cvCreateMat(3,1, CV_32F);
00171     cvCopy(k->pos,pos);
00172   }
00173   p_rect=k->p_rect;
00174   cnt_pos=k->cnt_pos;
00175   scale=k->scale;
00176   angle=k->angle;
00177 
00178   mi11=k->mi11;
00179   mi12=k->mi12;
00180   mi21=k->mi21;
00181   mi22=k->mi22;
00182   
00183   chainId=k->chainId;
00184   chainCnt=k->chainCnt;
00185 
00186   type=k->type;
00187   CopyVec(k);
00188   
00189   if (k->mask!=0){ 
00190     if (mask==0) mask=cvCreateImage( cvSize(PATCH_MASK_SIZE,PATCH_MASK_SIZE), IPL_DEPTH_32F, 1 );
00191     cvCopy(k->mask, mask);
00192   }
00193   if (k->bgmask!=0){ 
00194     if (bgmask==0) bgmask=cvCreateImage( cvSize(PATCH_MASK_SIZE,PATCH_MASK_SIZE), IPL_DEPTH_32F, 1 );
00195     cvCopy(k->bgmask, bgmask);
00196   }
00197 
00198   if (k->patch!=0){ 
00199     if (patch==0) patch=cvCreateImage( cvSize(PATCH_MASK_SIZE,PATCH_MASK_SIZE), IPL_DEPTH_8U, 1 );
00200     cvCopy(k->patch, patch);
00201   }
00202   cnt_err=k->cnt_err;
00203   flags=k->flags;
00204   cnt_rel=k->cnt_rel;
00205   reliability=k->reliability;
00206   mean_error=k->mean_error;
00207   var_error=k->var_error;
00208   occNum=k->occNum;
00209 }
00210 
00214 inline float KeypointDescriptor::DistSqr(float *desc1, float *desc2, unsigned cnt)
00215 {
00216     register unsigned i;
00217     float dif;
00218     float distsq = 0;
00219 
00220     for (i = 0; i < cnt; i++) {
00221       dif = *desc1++ - *desc2++;
00222       distsq += dif * dif;
00223     }
00224     return distsq;
00225 }
00226 
00230 inline void KeypointDescriptor::Add(float *desc)
00231 {
00232   register unsigned i;
00233   register float *d = GetVec();
00234 
00235   for (i = 0; i < GetSize(); i++) {
00236     *d++ += *desc++;
00237   }
00238 }
00239 
00243 inline void KeypointDescriptor::SetZero()
00244 {
00245   register float *d=GetVec();
00246   register unsigned z;
00247 
00248   for (z=0; z< GetSize(); z++){
00249     *d++ = 0.;
00250   }
00251 }
00252 
00256 inline void KeypointDescriptor::Div(float num)
00257 {
00258   register float *d=GetVec();
00259   register unsigned z;
00260 
00261   for (z=0; z< GetSize(); z++){
00262     *d++ /= num;
00263   }
00264 }
00265 
00269 inline void KeypointDescriptor::Mul(float num)
00270 {
00271   register float *d=GetVec();
00272   register unsigned z;
00273 
00274   for (z=0; z< GetSize(); z++){
00275     *d++ *= num;
00276   }
00277 }
00278 
00279 
00284 inline void KeypointDescriptor::MatchSift(KeypointDescriptor *k, float thr, float &dist)
00285 {
00286   dist = DistSqr(vec, k->vec, GetSize());
00287   if (dist>=thr) dist=FLT_MAX;
00288 }
00289 
00294 inline void KeypointDescriptor::SetReliability(float f)
00295 {
00296   reliability = ((float)(cnt_rel*reliability + f))/((float)(cnt_rel+1));
00297   cnt_rel++;
00298 }
00299 
00303 inline void KeypointDescriptor::SetError(float e)
00304 {
00305   mean_error = ((float)cnt_err*mean_error + e)/((float)cnt_err+1.);
00306  
00307   var_error = 1./((float)cnt_err+1.) * ((float)cnt_err*var_error + 
00308                                     (float)cnt_err/((float)cnt_err+1.)*Sqr(mean_error - e));
00309   cnt_err++;
00310 }
00311 
00312 inline float KeypointDescriptor::GetThr()
00313 {
00314   switch(GetType())
00315   {
00316     case DOG_SIFT:
00317       return DOG_SIFT_THR;
00318       break;
00319     case LOWE_DOG_SIFT:
00320       return LOWE_DOG_SIFT_THR;
00321       break;
00322     case MSER_SIFT:
00323       return MSER_SIFT_THR;
00324       break;
00325     case UVMSER_SIFT:
00326       return MSER_SIFT_THR;
00327       break;
00328     case HESLAP_SIFT:
00329       return HESLAP_SIFT_THR;
00330       break;
00331     default:
00332       return FLT_MAX;
00333       break;        
00334   }
00335   return FLT_MAX;
00336 }
00337 
00338 inline void KeypointDescriptor::SetPos(float x, float y, float z)
00339 {
00340   if (!Have3D()) pos = cvCreateMat(3,1, CV_32F);
00341 
00342   pos->data.fl[0] = x;
00343   pos->data.fl[1] = y;
00344   pos->data.fl[2] = z;
00345 }
00346 
00350 inline void CopyVec(float *svec, float *dvec, unsigned size)
00351 {
00352   for (register unsigned i=0; i<size; i++){
00353     *dvec++=*svec++;
00354   }
00355 }
00356 
00357 inline float MatchKeypoint(KeypointDescriptor *k1, KeypointDescriptor *k2)
00358 {
00359   if (k1->GetType() != k2->GetType())
00360     return FLT_MAX;
00361   return k1->DistSqr(k1->vec, k2->vec, k1->GetSize()); 
00362 }
00363 
00364 
00365 } //--END--
00366 
00367 #endif
00368 


blort
Author(s): Thomas Mörwald , Michael Zillich , Andreas Richtsfeld , Johann Prankl , Markus Vincze , Bence Magyar
autogenerated on Wed Aug 26 2015 15:24:12