00001
00002
00003
00004
00005
00006
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
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
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
00095
00096
00097
00098 class CvAffinePose
00099 {
00100 public:
00101 float phi;
00102 float theta;
00103 float lambda1;
00104 float lambda2;
00105 };
00106
00107
00108
00109
00110
00111 void AffineTransformPatch(IplImage* src, IplImage* dst, CvAffinePose pose);
00112
00113
00114
00115
00116
00117 void GenerateAffineTransformFromPose(CvSize size, CvAffinePose pose, CvMat* transform);
00118
00119
00120 CvAffinePose GenRandomAffinePose();
00121
00122
00123 const static int num_mean_components = 500;
00124 const static float noise_intensity = 0.15f;
00125
00126
00127 class CvOneWayDescriptor
00128 {
00129 public:
00130 CvOneWayDescriptor();
00131 ~CvOneWayDescriptor();
00132
00133
00134 void Allocate(int pose_count, CvSize size, int nChannels);
00135
00136
00137
00138
00139
00140
00141 void GenerateSamples(int pose_count, IplImage* frontal, int norm = 0);
00142
00143
00144
00145
00146
00147
00148
00149
00150 void GenerateSamplesFast(IplImage* frontal, CvMat* pca_hr_avg,
00151 CvMat* pca_hr_eigenvectors, CvOneWayDescriptor* pca_descriptors);
00152
00153
00154 void SetTransforms(CvAffinePose* poses, CvMat** transforms);
00155
00156
00157
00158
00159
00160
00161 void Initialize(int pose_count, IplImage* frontal, const char* feature_name = 0, int norm = 0);
00162
00163
00164
00165
00166
00167
00168
00169
00170
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
00175
00176
00177
00178
00179 void ProjectPCASample(IplImage* patch, CvMat* avg, CvMat* eigenvectors, CvMat* pca_coeffs) const;
00180
00181
00182
00183
00184 void InitializePCACoeffs(CvMat* avg, CvMat* eigenvectors);
00185
00186
00187
00188
00189
00190 void EstimatePose(IplImage* patch, int& pose_idx, float& distance) const;
00191
00192
00193
00194
00195
00196
00197
00198
00199 void EstimatePosePCA(CvArr* patch, int& pose_idx, float& distance, CvMat* avg, CvMat* eigenvalues) const;
00200
00201
00202 CvSize GetPatchSize() const
00203 {
00204 return m_patch_size;
00205 }
00206
00207
00208
00209 CvSize GetInputPatchSize() const
00210 {
00211 return cvSize(m_patch_size.width*2, m_patch_size.height*2);
00212 }
00213
00214
00215
00216
00217 IplImage* GetPatch(int index);
00218
00219
00220
00221
00222 CvAffinePose GetPose(int index) const;
00223
00224
00225 void Save(const char* path);
00226
00227
00228
00229
00230
00231
00232 int ReadByName(CvFileStorage* fs, CvFileNode* parent, const char* name);
00233
00234
00235
00236
00237 void Write(CvFileStorage* fs, const char* name);
00238
00239
00240 const char* GetFeatureName() const;
00241
00242
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;
00255 CvSize m_patch_size;
00256 IplImage** m_samples;
00257 IplImage* m_input_patch;
00258 IplImage* m_train_patch;
00259 CvMat** m_pca_coeffs;
00260 CvAffinePose* m_affine_poses;
00261 CvMat** m_transforms;
00262
00263 std::string m_feature_name;
00264 CvPoint m_center;
00265
00266 int m_pca_dim_high;
00267 int m_pca_dim_low;
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