$search
00001 /* 00002 * one_way_descriptor_base.cpp 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 #include <cstdio> 00011 00012 #include "outlet_pose_estimation/detail/features.h" 00013 #include "outlet_pose_estimation/detail/pca_features.h" 00014 #include "outlet_pose_estimation/detail/one_way_descriptor_base.h" 00015 00016 #include <cv.h> 00017 #include <highgui.h> 00018 00019 using namespace std; 00020 00021 CvMat* ConvertImageToMatrix(IplImage* patch) 00022 { 00023 CvRect roi = cvGetImageROI(patch); 00024 CvMat* mat = cvCreateMat(1, roi.width*roi.height, CV_32FC1); 00025 00026 if(patch->depth == 32) 00027 { 00028 for(int y = 0; y < roi.height; y++) 00029 { 00030 for(int x = 0; x < roi.width; x++) 00031 { 00032 mat->data.fl[y*roi.width + x] = *((float*)(patch->imageData + (y + roi.y)*patch->widthStep) + x + roi.x); 00033 } 00034 } 00035 } 00036 else if(patch->depth == 8) 00037 { 00038 for(int y = 0; y < roi.height; y++) 00039 { 00040 for(int x = 0; x < roi.width; x++) 00041 { 00042 mat->data.fl[y*roi.width + x] = (float)(unsigned char)patch->imageData[(y + roi.y)*patch->widthStep + x + roi.x]; 00043 } 00044 } 00045 } 00046 else 00047 { 00048 printf("Image depth %d is not supported\n", patch->depth); 00049 return 0; 00050 } 00051 00052 return mat; 00053 } 00054 00055 CvOneWayDescriptorBase::CvOneWayDescriptorBase(CvSize patch_size, int pose_count, const char* train_path, 00056 const char* pca_config, const char* pca_hr_config, 00057 const char* pca_desc_config, int pyr_levels, 00058 int pca_dim_high, int pca_dim_low) : m_pca_dim_high(pca_dim_high), m_pca_dim_low(pca_dim_low) 00059 { 00060 // m_pca_descriptors_matrix = 0; 00061 m_patch_size = patch_size; 00062 m_pose_count = pose_count; 00063 m_pyr_levels = pyr_levels; 00064 m_poses = 0; 00065 m_transforms = 0; 00066 00067 m_pca_avg = 0; 00068 m_pca_eigenvectors = 0; 00069 m_pca_hr_avg = 0; 00070 m_pca_hr_eigenvectors = 0; 00071 m_pca_descriptors = 0; 00072 00073 m_descriptors = 0; 00074 00075 if(train_path == 0 || strlen(train_path) == 0) 00076 { 00077 // skip pca loading 00078 return; 00079 } 00080 char pca_config_filename[1024]; 00081 sprintf(pca_config_filename, "%s/%s", train_path, pca_config); 00082 readPCAFeatures(pca_config_filename, &m_pca_avg, &m_pca_eigenvectors); 00083 if(pca_hr_config && strlen(pca_hr_config) > 0) 00084 { 00085 char pca_hr_config_filename[1024]; 00086 sprintf(pca_hr_config_filename, "%s/%s", train_path, pca_hr_config); 00087 readPCAFeatures(pca_hr_config_filename, &m_pca_hr_avg, &m_pca_hr_eigenvectors); 00088 } 00089 00090 m_pca_descriptors = new CvOneWayDescriptor[m_pca_dim_high + 1]; 00091 if(pca_desc_config && strlen(pca_desc_config) > 0) 00092 // if(0) 00093 { 00094 //printf("Loading the descriptors..."); 00095 char pca_desc_config_filename[1024]; 00096 sprintf(pca_desc_config_filename, "%s/%s", train_path, pca_desc_config); 00097 LoadPCADescriptors(pca_desc_config_filename); 00098 //printf("done.\n"); 00099 } 00100 else 00101 { 00102 printf("Initializing the descriptors...\n"); 00103 InitializePoseTransforms(); 00104 CreatePCADescriptors(); 00105 SavePCADescriptors("pca_descriptors.yml"); 00106 } 00107 // SavePCADescriptors("./pca_descriptors.yml"); 00108 00109 } 00110 00111 CvOneWayDescriptorBase::~CvOneWayDescriptorBase() 00112 { 00113 cvReleaseMat(&m_pca_avg); 00114 cvReleaseMat(&m_pca_eigenvectors); 00115 00116 if(m_pca_hr_eigenvectors) 00117 { 00118 delete[] m_pca_descriptors; 00119 cvReleaseMat(&m_pca_hr_avg); 00120 cvReleaseMat(&m_pca_hr_eigenvectors); 00121 } 00122 00123 00124 delete []m_descriptors; 00125 delete []m_poses; 00126 00127 for(int i = 0; i < m_pose_count; i++) 00128 { 00129 cvReleaseMat(&m_transforms[i]); 00130 } 00131 delete []m_transforms; 00132 00133 #if defined(_KDTREE) 00134 // if (m_pca_descriptors_matrix) 00135 // delete m_pca_descriptors_matrix; 00136 cvReleaseMat(&m_pca_descriptors_matrix); 00137 delete m_pca_descriptors_tree; 00138 #endif 00139 } 00140 00141 void CvOneWayDescriptorBase::InitializePoses() 00142 { 00143 m_poses = new CvAffinePose[m_pose_count]; 00144 for(int i = 0; i < m_pose_count; i++) 00145 { 00146 m_poses[i] = GenRandomAffinePose(); 00147 } 00148 } 00149 00150 void CvOneWayDescriptorBase::InitializeTransformsFromPoses() 00151 { 00152 m_transforms = new CvMat*[m_pose_count]; 00153 for(int i = 0; i < m_pose_count; i++) 00154 { 00155 m_transforms[i] = cvCreateMat(2, 3, CV_32FC1); 00156 GenerateAffineTransformFromPose(cvSize(m_patch_size.width*2, m_patch_size.height*2), m_poses[i], m_transforms[i]); 00157 } 00158 } 00159 00160 void CvOneWayDescriptorBase::InitializePoseTransforms() 00161 { 00162 InitializePoses(); 00163 InitializeTransformsFromPoses(); 00164 } 00165 00166 void CvOneWayDescriptorBase::InitializeDescriptor(int desc_idx, IplImage* train_image, const char* feature_label) 00167 { 00168 m_descriptors[desc_idx].SetPCADimHigh(m_pca_dim_high); 00169 m_descriptors[desc_idx].SetPCADimLow(m_pca_dim_low); 00170 m_descriptors[desc_idx].SetTransforms(m_poses, m_transforms); 00171 00172 if(!m_pca_hr_eigenvectors) 00173 { 00174 m_descriptors[desc_idx].Initialize(m_pose_count, train_image, feature_label); 00175 } 00176 else 00177 { 00178 m_descriptors[desc_idx].InitializeFast(m_pose_count, train_image, feature_label, 00179 m_pca_hr_avg, m_pca_hr_eigenvectors, m_pca_descriptors); 00180 } 00181 00182 if(m_pca_avg) 00183 { 00184 m_descriptors[desc_idx].InitializePCACoeffs(m_pca_avg, m_pca_eigenvectors); 00185 } 00186 } 00187 00188 void CvOneWayDescriptorBase::FindDescriptor(IplImage* src, cv::Point2f pt, int& desc_idx, int& pose_idx, float& distance) const 00189 { 00190 00191 CvRect roi = cvRect(pt.x - m_patch_size.width/4, pt.y - m_patch_size.height/4, m_patch_size.width/2, m_patch_size.height/2); 00192 cvSetImageROI(src, roi); 00193 00194 00195 FindDescriptor(src, desc_idx, pose_idx, distance); 00196 00197 cvResetImageROI(src); 00198 00199 } 00200 00201 void CvOneWayDescriptorBase::FindDescriptor(IplImage* patch, int& desc_idx, int& pose_idx, float& distance, float* _scale, float* scale_ranges) const 00202 { 00203 #if 0 00204 ::FindOneWayDescriptor(m_train_feature_count, m_descriptors, patch, desc_idx, pose_idx, distance, m_pca_avg, m_pca_eigenvectors); 00205 #else 00206 float scale_min = 0.7f; 00207 float scale_max = 2.0f; 00208 float scale_step = 1.2f; 00209 00210 if (scale_ranges) 00211 { 00212 scale_min = scale_ranges[0]; 00213 scale_max = scale_ranges[1]; 00214 } 00215 00216 float scale = 1.0f; 00217 00218 #if !defined(_KDTREE) 00219 ::FindOneWayDescriptorEx(m_train_feature_count, m_descriptors, patch, 00220 scale_min, scale_max, scale_step, desc_idx, pose_idx, distance, scale, 00221 m_pca_avg, m_pca_eigenvectors); 00222 #else 00223 ::FindOneWayDescriptorEx(m_pca_descriptors_tree, m_descriptors[0].GetPatchSize(), m_descriptors[0].GetPCADimLow(), m_pose_count, patch, 00224 scale_min, scale_max, scale_step, desc_idx, pose_idx, distance, scale, 00225 m_pca_avg, m_pca_eigenvectors); 00226 #endif 00227 00228 if (_scale) 00229 *_scale = scale; 00230 00231 #endif 00232 } 00233 00234 void CvOneWayDescriptorBase::FindDescriptor(IplImage* patch, int n, std::vector<int>& desc_idxs, std::vector<int>& pose_idxs, 00235 std::vector<float>& distances, std::vector<float>& _scales, float* scale_ranges) const 00236 { 00237 float scale_min = 0.7f; 00238 float scale_max = 2.5f; 00239 float scale_step = 1.2f; 00240 00241 if (scale_ranges) 00242 { 00243 scale_min = scale_ranges[0]; 00244 scale_max = scale_ranges[1]; 00245 } 00246 00247 distances.resize(n); 00248 _scales.resize(n); 00249 desc_idxs.resize(n); 00250 pose_idxs.resize(n); 00251 /*float scales = 1.0f;*/ 00252 00253 ::FindOneWayDescriptorEx(m_train_feature_count, m_descriptors, patch, 00254 scale_min, scale_max, scale_step ,n, desc_idxs, pose_idxs, distances, _scales, 00255 m_pca_avg, m_pca_eigenvectors); 00256 00257 } 00258 00259 void CvOneWayDescriptorBase::SetPCAHigh(CvMat* avg, CvMat* eigenvectors) 00260 { 00261 m_pca_hr_avg = cvCloneMat(avg); 00262 m_pca_hr_eigenvectors = cvCloneMat(eigenvectors); 00263 } 00264 00265 void CvOneWayDescriptorBase::SetPCALow(CvMat* avg, CvMat* eigenvectors) 00266 { 00267 m_pca_avg = cvCloneMat(avg); 00268 m_pca_eigenvectors = cvCloneMat(eigenvectors); 00269 } 00270 00271 void CvOneWayDescriptorBase::AllocatePCADescriptors() 00272 { 00273 m_pca_descriptors = new CvOneWayDescriptor[m_pca_dim_high + 1]; 00274 for(int i = 0; i < m_pca_dim_high + 1; i++) 00275 { 00276 m_pca_descriptors[i].SetPCADimHigh(m_pca_dim_high); 00277 m_pca_descriptors[i].SetPCADimLow(m_pca_dim_low); 00278 } 00279 } 00280 00281 void CvOneWayDescriptorBase::CreatePCADescriptors() 00282 { 00283 if(m_pca_descriptors == 0) 00284 { 00285 AllocatePCADescriptors(); 00286 } 00287 IplImage* frontal = cvCreateImage(m_patch_size, IPL_DEPTH_32F, 1); 00288 00289 eigenvector2image(m_pca_hr_avg, frontal); 00290 m_pca_descriptors[0].SetTransforms(m_poses, m_transforms); 00291 m_pca_descriptors[0].Initialize(m_pose_count, frontal, "", 0); 00292 00293 for(int j = 0; j < m_pca_dim_high; j++) 00294 { 00295 CvMat eigenvector; 00296 cvGetSubRect(m_pca_hr_eigenvectors, &eigenvector, cvRect(0, j, m_pca_hr_eigenvectors->cols, 1)); 00297 eigenvector2image(&eigenvector, frontal); 00298 00299 m_pca_descriptors[j + 1].SetTransforms(m_poses, m_transforms); 00300 m_pca_descriptors[j + 1].Initialize(m_pose_count, frontal, "", 0); 00301 00302 printf("Created descriptor for PCA component %d\n", j); 00303 } 00304 00305 cvReleaseImage(&frontal); 00306 } 00307 00308 00309 int CvOneWayDescriptorBase::LoadPCADescriptors(const char* filename) 00310 { 00311 CvMemStorage* storage = cvCreateMemStorage(); 00312 CvFileStorage* fs = cvOpenFileStorage(filename, storage, CV_STORAGE_READ); 00313 if(!fs) 00314 { 00315 cvReleaseMemStorage(&storage); 00316 printf("File %f not found...\n", filename); 00317 return 0; 00318 } 00319 00320 // read affine poses 00321 CvFileNode* node = cvGetFileNodeByName(fs, 0, "affine poses"); 00322 if(node != 0) 00323 { 00324 CvMat* poses = (CvMat*)cvRead(fs, node); 00325 //if(poses->rows != m_pose_count) 00326 //{ 00327 // printf("Inconsistency in the number of poses between the class instance and the file! Exiting...\n"); 00328 // cvReleaseMat(&poses); 00329 // cvReleaseFileStorage(&fs); 00330 // cvReleaseMemStorage(&storage); 00331 //} 00332 00333 if(m_poses) 00334 { 00335 delete m_poses; 00336 } 00337 m_poses = new CvAffinePose[m_pose_count]; 00338 for(int i = 0; i < m_pose_count; i++) 00339 { 00340 m_poses[i].phi = cvmGet(poses, i, 0); 00341 m_poses[i].theta = cvmGet(poses, i, 1); 00342 m_poses[i].lambda1 = cvmGet(poses, i, 2); 00343 m_poses[i].lambda2 = cvmGet(poses, i, 3); 00344 } 00345 cvReleaseMat(&poses); 00346 00347 // now initialize pose transforms 00348 InitializeTransformsFromPoses(); 00349 } 00350 else 00351 { 00352 printf("Node \"affine poses\" not found...\n"); 00353 } 00354 00355 node = cvGetFileNodeByName(fs, 0, "pca components number"); 00356 if(node != 0) 00357 { 00358 00359 m_pca_dim_high = cvReadInt(node); 00360 if(m_pca_descriptors) 00361 { 00362 delete []m_pca_descriptors; 00363 } 00364 AllocatePCADescriptors(); 00365 for(int i = 0; i < m_pca_dim_high + 1; i++) 00366 { 00367 m_pca_descriptors[i].Allocate(m_pose_count, m_patch_size, 1); 00368 m_pca_descriptors[i].SetTransforms(m_poses, m_transforms); 00369 char buf[1024]; 00370 sprintf(buf, "descriptor for pca component %d", i); 00371 m_pca_descriptors[i].ReadByName(fs, 0, buf); 00372 } 00373 } 00374 else 00375 { 00376 printf("Node \"pca components number\" not found...\n"); 00377 } 00378 00379 cvReleaseFileStorage(&fs); 00380 cvReleaseMemStorage(&storage); 00381 00382 printf("Successfully read %d pca components\n", m_pca_dim_high); 00383 00384 return 1; 00385 } 00386 00387 void CvOneWayDescriptorBase::SavePCADescriptors(const char* filename) 00388 { 00389 CvMemStorage* storage = cvCreateMemStorage(); 00390 CvFileStorage* fs = cvOpenFileStorage(filename, storage, CV_STORAGE_WRITE); 00391 00392 cvWriteInt(fs, "pca components number", m_pca_dim_high); 00393 cvWriteComment(fs, "The first component is the average Vector, so the total number of components is <pca components number> + 1", 0); 00394 cvWriteInt(fs, "patch width", m_patch_size.width); 00395 cvWriteInt(fs, "patch height", m_patch_size.height); 00396 00397 // pack the affine transforms into a single CvMat and write them 00398 CvMat* poses = cvCreateMat(m_pose_count, 4, CV_32FC1); 00399 for(int i = 0; i < m_pose_count; i++) 00400 { 00401 cvmSet(poses, i, 0, m_poses[i].phi); 00402 cvmSet(poses, i, 1, m_poses[i].theta); 00403 cvmSet(poses, i, 2, m_poses[i].lambda1); 00404 cvmSet(poses, i, 3, m_poses[i].lambda2); 00405 } 00406 cvWrite(fs, "affine poses", poses); 00407 cvReleaseMat(&poses); 00408 00409 for(int i = 0; i < m_pca_dim_high + 1; i++) 00410 { 00411 char buf[1024]; 00412 sprintf(buf, "descriptor for pca component %d", i); 00413 m_pca_descriptors[i].Write(fs, buf); 00414 } 00415 00416 cvReleaseMemStorage(&storage); 00417 cvReleaseFileStorage(&fs); 00418 } 00419 00420 void CvOneWayDescriptorBase::Allocate(int train_feature_count) 00421 { 00422 m_train_feature_count = train_feature_count; 00423 m_descriptors = new CvOneWayDescriptor[m_train_feature_count]; 00424 for(int i = 0; i < m_train_feature_count; i++) 00425 { 00426 m_descriptors[i].SetPCADimHigh(m_pca_dim_high); 00427 m_descriptors[i].SetPCADimLow(m_pca_dim_low); 00428 } 00429 } 00430 00431 void CvOneWayDescriptorBase::InitializeDescriptors(IplImage* train_image, const vector<KeyPointEx>& features, 00432 const char* feature_label, int desc_start_idx) 00433 { 00434 for(int i = 0; i < (int)features.size(); i++) 00435 { 00436 CvPoint center = features[i].pt; 00437 00438 CvRect roi = cvRect(center.x - m_patch_size.width/2, center.y - m_patch_size.height/2, m_patch_size.width, m_patch_size.height); 00439 cvResetImageROI(train_image); 00440 roi = fit_rect_fixedsize(roi, train_image); 00441 cvSetImageROI(train_image, roi); 00442 // roi = cvGetImageROI(train_image); 00443 if(roi.width != m_patch_size.width || roi.height != m_patch_size.height) 00444 { 00445 continue; 00446 } 00447 00448 InitializeDescriptor(desc_start_idx + i, train_image, feature_label); 00449 00450 // printf("Completed feature %d\n", i); 00451 00452 } 00453 cvResetImageROI(train_image); 00454 00455 } 00456 00457 void CvOneWayDescriptorBase::CreateDescriptorsFromImage(IplImage* src, const std::vector<KeyPointEx>& features) 00458 { 00459 m_train_feature_count = (int)features.size(); 00460 00461 m_descriptors = new CvOneWayDescriptor[m_train_feature_count]; 00462 00463 InitializeDescriptors(src, features); 00464 00465 } 00466 00467 #if defined(_KDTREE) 00468 void CvOneWayDescriptorBase::ConvertDescriptorsArrayToTree() 00469 { 00470 int n = this->GetDescriptorCount(); 00471 if (n<1) 00472 return; 00473 int pca_dim_low = this->GetDescriptor(0)->GetPCADimLow(); 00474 00475 //if (!m_pca_descriptors_matrix) 00476 // m_pca_descriptors_matrix = new ::flann::Matrix<float>(n*m_pose_count,pca_dim_low); 00477 //else 00478 //{ 00479 // if ((m_pca_descriptors_matrix->cols != pca_dim_low)&&(m_pca_descriptors_matrix->rows != n*m_pose_count)) 00480 // { 00481 // delete m_pca_descriptors_matrix; 00482 // m_pca_descriptors_matrix = new ::flann::Matrix<float>(n*m_pose_count,pca_dim_low); 00483 // } 00484 //} 00485 00486 m_pca_descriptors_matrix = cvCreateMat(n*m_pose_count,pca_dim_low,CV_32FC1); 00487 for (int i=0;i<n;i++) 00488 { 00489 CvMat** pca_coeffs = m_descriptors[i].GetPCACoeffs(); 00490 for (int j = 0;j<m_pose_count;j++) 00491 { 00492 for (int k=0;k<pca_dim_low;k++) 00493 { 00494 m_pca_descriptors_matrix->data.fl[(i*m_pose_count+j)*m_pca_dim_low + k] = pca_coeffs[j]->data.fl[k]; 00495 } 00496 } 00497 } 00498 cv::Mat pca_descriptors_mat(m_pca_descriptors_matrix,false); 00499 00500 //::flann::KDTreeIndexParams params; 00501 //params.trees = 1; 00502 //m_pca_descriptors_tree = new KDTree(pca_descriptors_mat); 00503 m_pca_descriptors_tree = new cv::flann::Index(pca_descriptors_mat,cv::flann::KDTreeIndexParams(1)); 00504 //cvReleaseMat(&m_pca_descriptors_matrix); 00505 //m_pca_descriptors_tree->buildIndex(); 00506 } 00507 #endif 00508 00509 void CvOneWayDescriptorObject::Allocate(int train_feature_count, int object_feature_count) 00510 { 00511 CvOneWayDescriptorBase::Allocate(train_feature_count); 00512 m_object_feature_count = object_feature_count; 00513 00514 m_part_id = new int[m_object_feature_count]; 00515 } 00516 00517 00518 void CvOneWayDescriptorObject::InitializeObjectDescriptors(IplImage* train_image, const vector<KeyPointEx>& features, 00519 const char* feature_label, int desc_start_idx, float scale, int is_background) 00520 { 00521 InitializeDescriptors(train_image, features, feature_label, desc_start_idx); 00522 00523 for(int i = 0; i < (int)features.size(); i++) 00524 { 00525 CvPoint center = features[i].pt; 00526 00527 if(!is_background) 00528 { 00529 // remember descriptor part id 00530 CvPoint center_scaled = cvPoint(round(center.x*scale), round(center.y*scale)); 00531 m_part_id[i + desc_start_idx] = MatchPointToPart(center_scaled); 00532 } 00533 } 00534 cvResetImageROI(train_image); 00535 } 00536 00537 int CvOneWayDescriptorObject::IsDescriptorObject(int desc_idx) const 00538 { 00539 return desc_idx < m_object_feature_count ? 1 : 0; 00540 } 00541 00542 int CvOneWayDescriptorObject::MatchPointToPart(CvPoint pt) const 00543 { 00544 int idx = -1; 00545 const int max_dist = 10; 00546 for(int i = 0; i < (int)m_train_features.size(); i++) 00547 { 00548 if(length(pt - m_train_features[i].pt) < max_dist) 00549 { 00550 idx = i; 00551 break; 00552 } 00553 } 00554 00555 return idx; 00556 } 00557 00558 int CvOneWayDescriptorObject::GetDescriptorPart(int desc_idx) const 00559 { 00560 // return MatchPointToPart(GetDescriptor(desc_idx)->GetCenter()); 00561 return desc_idx < m_object_feature_count ? m_part_id[desc_idx] : -1; 00562 } 00563 00564 CvOneWayDescriptorObject::CvOneWayDescriptorObject(CvSize patch_size, int pose_count, const char* train_path, 00565 const char* pca_config, const char* pca_hr_config, const char* pca_desc_config, int pyr_levels) : 00566 CvOneWayDescriptorBase(patch_size, pose_count, train_path, pca_config, pca_hr_config, pca_desc_config, pyr_levels) 00567 { 00568 m_part_id = 0; 00569 } 00570 00571 CvOneWayDescriptorObject::~CvOneWayDescriptorObject() 00572 { 00573 delete []m_part_id; 00574 } 00575 00576 vector<feature_t> CvOneWayDescriptorObject::_GetLabeledFeatures() const 00577 { 00578 vector<feature_t> features; 00579 for(size_t i = 0; i < m_train_features.size(); i++) 00580 { 00581 features.push_back(m_train_features[i]); 00582 } 00583 00584 return features; 00585 } 00586 00587 void eigenvector2image(CvMat* eigenvector, IplImage* img) 00588 { 00589 CvRect roi = cvGetImageROI(img); 00590 if(img->depth == 32) 00591 { 00592 for(int y = 0; y < roi.height; y++) 00593 { 00594 for(int x = 0; x < roi.width; x++) 00595 { 00596 float val = cvmGet(eigenvector, 0, roi.width*y + x); 00597 *((float*)(img->imageData + (roi.y + y)*img->widthStep) + roi.x + x) = val; 00598 } 00599 } 00600 } 00601 else 00602 { 00603 for(int y = 0; y < roi.height; y++) 00604 { 00605 for(int x = 0; x < roi.width; x++) 00606 { 00607 float val = cvmGet(eigenvector, 0, roi.width*y + x); 00608 img->imageData[(roi.y + y)*img->widthStep + roi.x + x] = (unsigned char)val; 00609 } 00610 } 00611 } 00612 } 00613 00614 void readPCAFeatures(const char* filename, CvMat** avg, CvMat** eigenvectors) 00615 { 00616 CvMemStorage* storage = cvCreateMemStorage(); 00617 CvFileStorage* fs = cvOpenFileStorage(filename, storage, CV_STORAGE_READ); 00618 if(!fs) 00619 { 00620 printf("Cannot open file %s! Exiting!", filename); 00621 cvReleaseMemStorage(&storage); 00622 } 00623 00624 CvFileNode* node = cvGetFileNodeByName(fs, 0, "avg"); 00625 CvMat* _avg = (CvMat*)cvRead(fs, node); 00626 node = cvGetFileNodeByName(fs, 0, "eigenvectors"); 00627 CvMat* _eigenvectors = (CvMat*)cvRead(fs, node); 00628 00629 *avg = cvCloneMat(_avg); 00630 *eigenvectors = cvCloneMat(_eigenvectors); 00631 00632 cvReleaseMat(&_avg); 00633 cvReleaseMat(&_eigenvectors); 00634 cvReleaseFileStorage(&fs); 00635 cvReleaseMemStorage(&storage); 00636 }