one_way_descriptor_base.h
Go to the documentation of this file.
00001 /*
00002  *  one_way_descriptor_base.h
00003  *  outlet_detection
00004  *
00005  *  Created by Victor  Eruhimov on 7/9/09.
00006  *  Copyright 2009 Argus Corp. All rights reserved.
00007  *
00008  */
00009 
00010 #if !defined(_ONE_WAY_DESCRIPTOR_BASE)
00011 #define _ONE_WAY_DESCRIPTOR_BASE
00012 
00013 #include <vector>
00014 #include <cv.h>
00015 #include <outlet_pose_estimation/detail/one_way_descriptor.h>
00016 
00017 #if defined (_KDTREE)
00018 #include <cxcore.h>
00019 #endif
00020 
00021 inline CvRect fit_rect_roi_fixedsize(CvRect rect, CvRect roi)
00022 {
00023         CvRect fit = rect;
00024         fit.x = MAX(fit.x, roi.x);
00025         fit.y = MAX(fit.y, roi.y);
00026     fit.x = MIN(fit.x, roi.x + roi.width - fit.width - 1);
00027     fit.y = MIN(fit.y, roi.y + roi.height - fit.height - 1);
00028         return(fit);
00029 }
00030 
00031 inline CvRect fit_rect_fixedsize(CvRect rect, IplImage* img)
00032 {
00033         CvRect roi = cvGetImageROI(img);
00034         return fit_rect_roi_fixedsize(rect, roi);
00035 }
00036 
00037 class CV_EXPORTS KeyPointEx : public cv::KeyPoint
00038 {
00039 public:
00040     KeyPointEx(CvPoint _center = cvPoint(-1, -1), float _scale = 1, int _class_id = -1) :
00041         cv::KeyPoint(_center.x, _center.y, _scale, 0.0f, 0.0f, 0)
00042     {
00043         class_id = _class_id;
00044     };
00045 
00046     KeyPointEx(const cv::KeyPoint& keypoint) : cv::KeyPoint(keypoint)
00047     {
00048     };
00049 
00050     ~KeyPointEx() {};
00051 
00052     int class_id;
00053 };
00054 
00055 typedef KeyPointEx feature_t;
00056 
00057 // CvOneWayDescriptorBase: encapsulates functionality for training/loading a set of one way descriptors
00058 // and finding the nearest closest descriptor to an input feature
00059 class CvOneWayDescriptorBase
00060     {
00061     public:
00062 
00063         // creates an instance of CvOneWayDescriptor from a set of training files
00064         // - patch_size: size of the input (large) patch
00065         // - pose_count: the number of poses to generate for each descriptor
00066         // - train_path: path to training files
00067         // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
00068         // than patch_size each dimension
00069         // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
00070         // - pca_desc_config: the name of the file that contains descriptors of PCA components
00071         CvOneWayDescriptorBase(CvSize patch_size, int pose_count, const char* train_path = 0, const char* pca_config = 0,
00072                                const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1,
00073                                 int pca_dim_high = 100, int pca_dim_low = 100);
00074 
00075         ~CvOneWayDescriptorBase();
00076 
00077         // Allocate: allocates memory for a given number of descriptors
00078         void Allocate(int train_feature_count);
00079 
00080         // AllocatePCADescriptors: allocates memory for pca descriptors
00081         void AllocatePCADescriptors();
00082 
00083         // returns patch size
00084         CvSize GetPatchSize() const {return m_patch_size;};
00085         // returns the number of poses for each descriptor
00086         int GetPoseCount() const {return m_pose_count;};
00087 
00088         // returns the number of pyramid levels
00089         int GetPyrLevels() const {return m_pyr_levels;};
00090 
00091         // returns the number of descriptors
00092         int GetDescriptorCount() const {return m_train_feature_count;};
00093 
00094         // CreateDescriptorsFromImage: creates descriptors for each of the input features
00095         // - src: input image
00096         // - features: input features
00097         // - pyr_levels: the number of pyramid levels
00098         void CreateDescriptorsFromImage(IplImage* src, const std::vector<KeyPointEx>& features);
00099 
00100         // CreatePCADescriptors: generates descriptors for PCA components, needed for fast generation of feature descriptors
00101         void CreatePCADescriptors();
00102 
00103         // returns a feature descriptor by feature index
00104         const CvOneWayDescriptor* GetDescriptor(int desc_idx) const {return &m_descriptors[desc_idx];};
00105 
00106         // FindDescriptor: finds the closest descriptor
00107         // - patch: input image patch
00108         // - desc_idx: output index of the closest descriptor to the input patch
00109         // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
00110         // - distance: distance from the input patch to the closest feature pose
00111                 // - _scales: scales of the input patch for each descriptor
00112                 // - scale_ranges: input scales variation (float[2])
00113         void FindDescriptor(IplImage* patch, int& desc_idx, int& pose_idx, float& distance, float* _scale = 0, float* scale_ranges = 0) const;
00114 
00115         // - patch: input image patch
00116                 // - n: number of the closest indexes
00117         // - desc_idxs: output indexes of the closest descriptor to the input patch (n)
00118         // - pose_idx: output indexes of the closest pose of the closest descriptor to the input patch (n)
00119         // - distances: distance from the input patch to the closest feature pose (n)
00120                 // - _scales: scales of the input patch
00121                 // - scale_ranges: input scales variation (float[2])
00122                 void FindDescriptor(IplImage* patch, int n, std::vector<int>& desc_idxs, std::vector<int>& pose_idxs,
00123             std::vector<float>& distances, std::vector<float>& _scales, float* scale_ranges = 0) const;
00124 
00125         // FindDescriptor: finds the closest descriptor
00126         // - src: input image
00127         // - pt: center of the feature
00128         // - desc_idx: output index of the closest descriptor to the input patch
00129         // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
00130         // - distance: distance from the input patch to the closest feature pose
00131         void FindDescriptor(IplImage* src, cv::Point2f pt, int& desc_idx, int& pose_idx, float& distance) const;
00132 
00133         // InitializePoses: generates random poses
00134         void InitializePoses();
00135 
00136         // InitializeTransformsFromPoses: generates 2x3 affine matrices from poses (initializes m_transforms)
00137         void InitializeTransformsFromPoses();
00138 
00139         // InitializePoseTransforms: subsequently calls InitializePoses and InitializeTransformsFromPoses
00140         void InitializePoseTransforms();
00141 
00142         // InitializeDescriptor: initializes a descriptor
00143         // - desc_idx: descriptor index
00144         // - train_image: image patch (ROI is supported)
00145         // - feature_label: feature textual label
00146         void InitializeDescriptor(int desc_idx, IplImage* train_image, const char* feature_label);
00147 
00148         // InitializeDescriptors: load features from an image and create descriptors for each of them
00149         void InitializeDescriptors(IplImage* train_image, const std::vector<KeyPointEx>& features,
00150                               const char* feature_label = "", int desc_start_idx = 0);
00151 
00152         // LoadPCADescriptors: loads PCA descriptors from a file
00153         // - filename: input filename
00154         int LoadPCADescriptors(const char* filename);
00155 
00156         // SavePCADescriptors: saves PCA descriptors to a file
00157         // - filename: output filename
00158         void SavePCADescriptors(const char* filename);
00159 
00160         // SetPCAHigh: sets the high resolution pca matrices (copied to internal structures)
00161         void SetPCAHigh(CvMat* avg, CvMat* eigenvectors);
00162 
00163         // SetPCALow: sets the low resolution pca matrices (copied to internal structures)
00164         void SetPCALow(CvMat* avg, CvMat* eigenvectors);
00165 
00166         int GetLowPCA(CvMat** avg, CvMat** eigenvectors)
00167         {
00168             *avg = m_pca_avg;
00169             *eigenvectors = m_pca_eigenvectors;
00170                         return m_pca_dim_low;
00171         };
00172 
00173 #if defined (_KDTREE)
00174                 void ConvertDescriptorsArrayToTree(); // Converting pca_descriptors array to KD tree
00175 #endif
00176 
00177 
00178     protected:
00179         CvSize m_patch_size; // patch size
00180         int m_pose_count; // the number of poses for each descriptor
00181         int m_train_feature_count; // the number of the training features
00182         CvOneWayDescriptor* m_descriptors; // array of train feature descriptors
00183         CvMat* m_pca_avg; // PCA average Vector for small patches
00184         CvMat* m_pca_eigenvectors; // PCA eigenvectors for small patches
00185         CvMat* m_pca_hr_avg; // PCA average Vector for large patches
00186         CvMat* m_pca_hr_eigenvectors; // PCA eigenvectors for large patches
00187         CvOneWayDescriptor* m_pca_descriptors; // an array of PCA descriptors
00188 
00189 #if defined (_KDTREE)
00190                 cv::flann::Index* m_pca_descriptors_tree;
00191                 CvMat* m_pca_descriptors_matrix;
00192                 //KDTree* m_pca_descriptors_tree; //PCA descriptors stored in the KD tree
00193                 //::flann::Matrix<float>* m_pca_descriptors_matrix; // Matrix with pca descriptors vectors
00194 #endif
00195 
00196         CvAffinePose* m_poses; // array of poses
00197         CvMat** m_transforms; // array of affine transformations corresponding to poses
00198 
00199         int m_pca_dim_high;
00200         int m_pca_dim_low;
00201 
00202         int m_pyr_levels;
00203 
00204 };
00205 
00206 class CvOneWayDescriptorObject : public CvOneWayDescriptorBase
00207 {
00208     public:
00209         // creates an instance of CvOneWayDescriptorObject from a set of training files
00210         // - patch_size: size of the input (large) patch
00211         // - pose_count: the number of poses to generate for each descriptor
00212         // - train_path: path to training files
00213         // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
00214         // than patch_size each dimension
00215         // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
00216         // - pca_desc_config: the name of the file that contains descriptors of PCA components
00217         CvOneWayDescriptorObject(CvSize patch_size, int pose_count, const char* train_path, const char* pca_config,
00218                                  const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1);
00219 
00220         ~CvOneWayDescriptorObject();
00221 
00222         // Allocate: allocates memory for a given number of features
00223         // - train_feature_count: the total number of features
00224         // - object_feature_count: the number of features extracted from the object
00225         void Allocate(int train_feature_count, int object_feature_count);
00226 
00227 
00228         void SetLabeledFeatures(const std::vector<KeyPointEx>& features) {m_train_features = features;};
00229         std::vector<KeyPointEx>& GetLabeledFeatures() {return m_train_features;};
00230         const std::vector<KeyPointEx>& GetLabeledFeatures() const {return m_train_features;};
00231         std::vector<feature_t> _GetLabeledFeatures() const;
00232 
00233         // IsDescriptorObject: returns 1 if descriptor with specified index is positive, otherwise 0
00234         int IsDescriptorObject(int desc_idx) const;
00235 
00236         // MatchPointToPart: returns the part number of a feature if it matches one of the object parts, otherwise -1
00237         int MatchPointToPart(CvPoint pt) const;
00238 
00239         // GetDescriptorPart: returns the part number of the feature corresponding to a specified descriptor
00240         // - desc_idx: descriptor index
00241         int GetDescriptorPart(int desc_idx) const;
00242 
00243 
00244         void InitializeObjectDescriptors(IplImage* train_image, const std::vector<KeyPointEx>& features,
00245                                          const char* feature_label, int desc_start_idx = 0, float scale = 1.0f,
00246                                         int is_background = 0);
00247 
00248         // GetObjectFeatureCount: returns the number of object features
00249         int GetObjectFeatureCount() const {return m_object_feature_count;};
00250 
00251     protected:
00252         int* m_part_id; // contains part id for each of object descriptors
00253         std::vector<KeyPointEx> m_train_features; // train features
00254         int m_object_feature_count; // the number of the positive features
00255 
00256 };
00257 
00258 void readPCAFeatures(const char* filename, CvMat** avg, CvMat** eigenvectors);
00259 void eigenvector2image(CvMat* eigenvector, IplImage* img);
00260 
00261 #endif // _ONE_WAY_DESCRIPTOR_BASE


outlet_pose_estimation
Author(s): Patrick Mihelich
autogenerated on Thu Aug 27 2015 14:29:52