one_way_descriptor.h
Go to the documentation of this file.
00001 /*
00002  *  one_way_desctiptor.h
00003  *
00004  *
00005  *  Created by Victor  Eruhimov on 4/19/09.
00006  *  Copyright 2009 Argus Corp. All rights reserved.
00007  *
00008  */
00009 
00010 #if !defined(_ONE_WAY_DESCRIPTOR)
00011 #define _ONE_WAY_DESCRIPTOR
00012 
00013 #include <string>
00014 
00015 #include <cv.h>
00016 
00017 #if defined (_KDTREE)
00018 #include <cxcore.h>
00019 #endif
00020 
00021 inline int round(float value)
00022 {
00023     if(value > 0)
00024     {
00025         return int(value + 0.5f);
00026     }
00027     else
00028     {
00029         return int(value - 0.5f);
00030     }
00031 }
00032 
00033 inline CvRect resize_rect(CvRect rect, float alpha)
00034 {
00035         return cvRect(rect.x + round((float)(0.5*(1 - alpha)*rect.width)), rect.y + round((float)(0.5*(1 - alpha)*rect.height)),
00036                                   round(rect.width*alpha), round(rect.height*alpha));
00037 }
00038 
00039 /*
00040 inline CvRect fit_rect_roi(CvRect rect, CvRect roi)
00041 {
00042         CvRect fit = rect;
00043         fit.x = MAX(fit.x, roi.x);
00044         fit.y = MAX(fit.y, roi.y);
00045         fit.width = MIN(fit.width, roi.x + roi.width - fit.x - 1);
00046         fit.height = MIN(fit.height, roi.y + roi.height - fit.y - 1);
00047         assert(fit.width > 0);
00048         assert(fit.height > 0);
00049         return(fit);
00050 }
00051 
00052 inline CvRect fit_rect(CvRect rect, IplImage* img)
00053 {
00054         CvRect roi = cvGetImageROI(img);
00055         return fit_rect_roi(rect, roi);
00056 }
00057 
00058 inline CvRect double_rect(CvRect small_rect)
00059 {
00060         return cvRect(small_rect.x - small_rect.width/2, small_rect.y - small_rect.height/2,
00061                                   small_rect.width*2, small_rect.height*2);
00062 }*/
00063 CvMat* ConvertImageToMatrix(IplImage* patch);
00064 
00065 class CvCameraPose
00066 {
00067 public:
00068     CvCameraPose()
00069     {
00070         m_rotation = cvCreateMat(1, 3, CV_32FC1);
00071         m_translation = cvCreateMat(1, 3, CV_32FC1);
00072     };
00073 
00074     ~CvCameraPose()
00075     {
00076         cvReleaseMat(&m_rotation);
00077         cvReleaseMat(&m_translation);
00078     };
00079 
00080     void SetPose(CvMat* rotation, CvMat* translation)
00081     {
00082         cvCopy(rotation, m_rotation);
00083         cvCopy(translation, m_translation);
00084     };
00085 
00086     CvMat* GetRotation() {return m_rotation;};
00087     CvMat* GetTranslation() {return m_translation;};
00088 
00089 protected:
00090     CvMat* m_rotation;
00091     CvMat* m_translation;
00092 };
00093 
00094 // CvAffinePose: defines a parameterized affine transformation of an image patch.
00095 // An image patch is rotated on angle phi (in degrees), then scaled lambda1 times
00096 // along horizontal and lambda2 times along vertical direction, and then rotated again
00097 // on angle (theta - phi).
00098 class CvAffinePose
00099 {
00100 public:
00101     float phi;
00102     float theta;
00103     float lambda1;
00104     float lambda2;
00105 };
00106 
00107 // AffineTransformPatch: generates an affine transformed image patch.
00108 // - src: source image (roi is supported)
00109 // - dst: output image. ROI of dst image should be 2 times smaller than ROI of src.
00110 // - pose: parameters of an affine transformation
00111 void AffineTransformPatch(IplImage* src, IplImage* dst, CvAffinePose pose);
00112 
00113 // GenerateAffineTransformFromPose: generates an affine transformation matrix from CvAffinePose instance
00114 // - size: the size of image patch
00115 // - pose: affine transformation
00116 // - transform: 2x3 transformation matrix
00117 void GenerateAffineTransformFromPose(CvSize size, CvAffinePose pose, CvMat* transform);
00118 
00119 // Generates a random affine pose
00120 CvAffinePose GenRandomAffinePose();
00121 
00122 
00123 const static int num_mean_components = 500;
00124 const static float noise_intensity = 0.15f;
00125 
00126 // CvOneWayDescriptor: incapsulates a descriptor for a single point
00127 class CvOneWayDescriptor
00128 {
00129 public:
00130     CvOneWayDescriptor();
00131     ~CvOneWayDescriptor();
00132 
00133     // allocates memory for given descriptor parameters
00134     void Allocate(int pose_count, CvSize size, int nChannels);
00135 
00136     // GenerateSamples: generates affine transformed patches with averaging them over small transformation variations.
00137     // If external poses and transforms were specified, uses them instead of generating random ones
00138     // - pose_count: the number of poses to be generated
00139     // - frontal: the input patch (can be a roi in a larger image)
00140     // - norm: if nonzero, normalizes the output patch so that the sum of pixel intensities is 1
00141     void GenerateSamples(int pose_count, IplImage* frontal, int norm = 0);
00142 
00143     // GenerateSamplesFast: generates affine transformed patches with averaging them over small transformation variations.
00144     // Uses precalculated transformed pca components.
00145     // - frontal: the input patch (can be a roi in a larger image)
00146     // - pca_hr_avg: pca average vector
00147     // - pca_hr_eigenvectors: pca eigenvectors
00148     // - pca_descriptors: an array of precomputed descriptors of pca components containing their affine transformations
00149     //   pca_descriptors[0] corresponds to the average, pca_descriptors[1]-pca_descriptors[pca_dim] correspond to eigenvectors
00150     void GenerateSamplesFast(IplImage* frontal, CvMat* pca_hr_avg,
00151                     CvMat* pca_hr_eigenvectors, CvOneWayDescriptor* pca_descriptors);
00152 
00153     // sets the poses and corresponding transforms
00154     void SetTransforms(CvAffinePose* poses, CvMat** transforms);
00155 
00156     // Initialize: builds a descriptor.
00157     // - pose_count: the number of poses to build. If poses were set externally, uses them rather than generating random ones
00158     // - frontal: input patch. Can be a roi in a larger image
00159     // - feature_name: the feature name to be associated with the descriptor
00160     // - norm: if 1, the affine transformed patches are normalized so that their sum is 1
00161     void Initialize(int pose_count, IplImage* frontal, const char* feature_name = 0, int norm = 0);
00162 
00163     // InitializeFast: builds a descriptor using precomputed descriptors of pca components
00164     // - pose_count: the number of poses to build
00165     // - frontal: input patch. Can be a roi in a larger image
00166     // - feature_name: the feature name to be associated with the descriptor
00167     // - pca_hr_avg: average vector for PCA
00168     // - pca_hr_eigenvectors: PCA eigenvectors (one vector per row)
00169     // - pca_descriptors: precomputed descriptors of PCA components, the first descriptor for the average vector
00170     // followed by the descriptors for eigenvectors
00171     void InitializeFast(int pose_count, IplImage* frontal, const char* feature_name,
00172                                             CvMat* pca_hr_avg, CvMat* pca_hr_eigenvectors, CvOneWayDescriptor* pca_descriptors);
00173 
00174     // ProjectPCASample: unwarps an image patch into a vector and projects it into PCA space
00175     // - patch: input image patch
00176     // - avg: PCA average vector
00177     // - eigenvectors: PCA eigenvectors, one per row
00178     // - pca_coeffs: output PCA coefficients
00179     void ProjectPCASample(IplImage* patch, CvMat* avg, CvMat* eigenvectors, CvMat* pca_coeffs) const;
00180 
00181     // InitializePCACoeffs: projects all warped patches into PCA space
00182     // - avg: PCA average vector
00183     // - eigenvectors: PCA eigenvectors, one per row
00184     void InitializePCACoeffs(CvMat* avg, CvMat* eigenvectors);
00185 
00186     // EstimatePose: finds the closest match between an input patch and a set of patches with different poses
00187     // - patch: input image patch
00188     // - pose_idx: the output index of the closest pose
00189     // - distance: the distance to the closest pose (L2 distance)
00190     void EstimatePose(IplImage* patch, int& pose_idx, float& distance) const;
00191 
00192     // EstimatePosePCA: finds the closest match between an input patch and a set of patches with different poses.
00193     // The distance between patches is computed in PCA space
00194     // - patch: input image patch
00195     // - pose_idx: the output index of the closest pose
00196     // - distance: distance to the closest pose (L2 distance in PCA space)
00197     // - avg: PCA average vector. If 0, matching without PCA is used
00198     // - eigenvectors: PCA eigenvectors, one per row
00199     void EstimatePosePCA(CvArr* patch, int& pose_idx, float& distance, CvMat* avg, CvMat* eigenvalues) const;
00200 
00201     // GetPatchSize: returns the size of each image patch after warping (2 times smaller than the input patch)
00202     CvSize GetPatchSize() const
00203     {
00204         return m_patch_size;
00205     }
00206 
00207     // GetInputPatchSize: returns the required size of the patch that the descriptor is built from
00208     // (2 time larger than the patch after warping)
00209     CvSize GetInputPatchSize() const
00210     {
00211         return cvSize(m_patch_size.width*2, m_patch_size.height*2);
00212     }
00213 
00214     // GetPatch: returns a patch corresponding to specified pose index
00215     // - index: pose index
00216     // - return value: the patch corresponding to specified pose index
00217     IplImage* GetPatch(int index);
00218 
00219     // GetPose: returns a pose corresponding to specified pose index
00220     // - index: pose index
00221     // - return value: the pose corresponding to specified pose index
00222     CvAffinePose GetPose(int index) const;
00223 
00224     // Save: saves all patches with different poses to a specified path
00225     void Save(const char* path);
00226 
00227     // ReadByName: reads a descriptor from a file storage
00228     // - fs: file storage
00229     // - parent: parent node
00230     // - name: node name
00231     // - return value: 1 if succeeded, 0 otherwise
00232     int ReadByName(CvFileStorage* fs, CvFileNode* parent, const char* name);
00233 
00234     // Write: writes a descriptor into a file storage
00235     // - fs: file storage
00236     // - name: node name
00237     void Write(CvFileStorage* fs, const char* name);
00238 
00239     // GetFeatureName: returns a name corresponding to a feature
00240     const char* GetFeatureName() const;
00241 
00242     // GetCenter: returns the center of the feature
00243     CvPoint GetCenter() const;
00244 
00245     void SetPCADimHigh(int pca_dim_high) {m_pca_dim_high = pca_dim_high;};
00246     void SetPCADimLow(int pca_dim_low) {m_pca_dim_low = pca_dim_low;};
00247 
00248         int GetPCADimLow() const;
00249         int GetPCADimHigh() const;
00250 
00251         CvMat** GetPCACoeffs() const {return m_pca_coeffs;}
00252 
00253 protected:
00254     int m_pose_count; // the number of poses
00255     CvSize m_patch_size; // size of each image
00256     IplImage** m_samples; // an array of length m_pose_count containing the patch in different poses
00257     IplImage* m_input_patch;
00258     IplImage* m_train_patch;
00259     CvMat** m_pca_coeffs; // an array of length m_pose_count containing pca decomposition of the patch in different poses
00260     CvAffinePose* m_affine_poses; // an array of poses
00261     CvMat** m_transforms; // an array of affine transforms corresponding to poses
00262 
00263     std::string m_feature_name; // the name of the feature associated with the descriptor
00264     CvPoint m_center; // the coordinates of the feature (the center of the input image ROI)
00265 
00266     int m_pca_dim_high; // the number of descriptor pca components to use for generating affine poses
00267     int m_pca_dim_low; // the number of pca components to use for comparison
00268 };
00269 
00270 void FindOneWayDescriptor(int desc_count, const CvOneWayDescriptor* descriptors, IplImage* patch, int& desc_idx, int& pose_idx, float& distance,
00271                           CvMat* avg = 0, CvMat* eigenvalues = 0);
00272 
00273 void FindOneWayDescriptor(int desc_count, const CvOneWayDescriptor* descriptors, IplImage* patch, int n,
00274                     std::vector<int>& desc_idxs, std::vector<int>&  pose_idxs, std::vector<float>& distances,
00275                     CvMat* avg = 0, CvMat* eigenvalues = 0);
00276 
00277 #if defined(_KDTREE)
00278 void FindOneWayDescriptor(cv::flann::Index* m_pca_descriptors_tree, CvSize patch_size, int m_pca_dim_low, int m_pose_count, IplImage* patch, int& desc_idx, int& pose_idx, float& distance,
00279                           CvMat* avg = 0, CvMat* eigenvalues = 0);
00280 #endif
00281 
00282 void FindOneWayDescriptorEx(int desc_count, const CvOneWayDescriptor* descriptors, IplImage* patch,
00283                             float scale_min, float scale_max, float scale_step,
00284                             int& desc_idx, int& pose_idx, float& distance, float& scale,
00285                             CvMat* avg, CvMat* eigenvectors);
00286 
00287 void FindOneWayDescriptorEx(int desc_count, const CvOneWayDescriptor* descriptors, IplImage* patch,
00288                                                         float scale_min, float scale_max, float scale_step,
00289                                                         int n, std::vector<int>& desc_idxs, std::vector<int>& pose_idxs,
00290                                                         std::vector<float>& distances, std::vector<float>& scales,
00291                                                         CvMat* avg, CvMat* eigenvectors);
00292 
00293 #if defined(_KDTREE)
00294 void FindOneWayDescriptorEx(cv::flann::Index* m_pca_descriptors_tree, CvSize patch_size, int m_pca_dim_low, int m_pose_count, IplImage* patch,
00295                                                         float scale_min, float scale_max, float scale_step,
00296                                                         int& desc_idx, int& pose_idx, float& distance, float& scale,
00297                                                         CvMat* avg, CvMat* eigenvectors);
00298 #endif
00299 
00300 
00301 #endif //_ONE_WAY_DESCRIPTOR
00302 


outlet_pose_estimation
Author(s): Patrick Mihelich
autogenerated on Mon Dec 2 2013 13:21:49