00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef __VCGLIB__SAMPLING
00025 #define __VCGLIB__SAMPLING
00026
00027 #include <time.h>
00028 #include <vcg/complex/algorithms/closest.h>
00029 #include <vcg/space/box3.h>
00030 #include <vcg/math/histogram.h>
00031 #include <vcg/space/color4.h>
00032 #include <vcg/simplex/face/distance.h>
00033 #include <vcg/complex/algorithms/update/color.h>
00034 #include <vcg/space/index/grid_static_ptr.h>
00035 #include <vcg/space/index/aabb_binary_tree/aabb_binary_tree.h>
00036 #include <vcg/space/index/octree.h>
00037 #include <vcg/space/index/spatial_hashing.h>
00038 namespace vcg
00039 {
00040
00041 struct SamplingFlags{
00042 enum{
00043 HIST = 0x0001,
00044 VERTEX_SAMPLING = 0x0002,
00045 EDGE_SAMPLING = 0x0004,
00046 FACE_SAMPLING = 0x0008,
00047 MONTECARLO_SAMPLING = 0x0010,
00048 SUBDIVISION_SAMPLING = 0x0020,
00049 SIMILAR_SAMPLING = 0x0040,
00050 NO_SAMPLING = 0x0070,
00051 SAVE_ERROR = 0x0100,
00052 INCLUDE_UNREFERENCED_VERTICES = 0x0200,
00053 USE_STATIC_GRID = 0x0400,
00054 USE_HASH_GRID = 0x0800,
00055 USE_AABB_TREE = 0x1000,
00056 USE_OCTREE = 0x2000
00057 };
00058 };
00059
00060 template <class MetroMesh>
00061 class Sampling
00062 {
00063 public:
00064
00065 private:
00066 typedef typename MetroMesh::CoordType CoordType;
00067 typedef typename MetroMesh::ScalarType ScalarType;
00068 typedef typename MetroMesh::VertexType VertexType;
00069 typedef typename MetroMesh::VertexPointer VertexPointer;
00070 typedef typename MetroMesh::VertexIterator VertexIterator;
00071 typedef typename MetroMesh::FaceIterator FaceIterator;
00072 typedef typename MetroMesh::FaceType FaceType;
00073 typedef typename MetroMesh::FaceContainer FaceContainer;
00074
00075 typedef GridStaticPtr <FaceType, typename MetroMesh::ScalarType > MetroMeshGrid;
00076 typedef SpatialHashTable <FaceType, typename MetroMesh::ScalarType > MetroMeshHash;
00077 typedef AABBBinaryTreeIndex <FaceType, typename MetroMesh::ScalarType, vcg::EmptyClass> MetroMeshAABB;
00078 typedef Octree <FaceType, typename MetroMesh::ScalarType > MetroMeshOctree;
00079
00080 typedef Point3<typename MetroMesh::ScalarType> Point3x;
00081
00082
00083
00084
00085
00086 MetroMesh &S1;
00087 MetroMesh &S2;
00088 MetroMeshGrid gS2;
00089 MetroMeshHash hS2;
00090 MetroMeshAABB tS2;
00091 MetroMeshOctree oS2;
00092
00093
00094 unsigned int n_samples_per_face ;
00095 float n_samples_edge_to_face_ratio ;
00096 float bbox_factor ;
00097 float inflate_percentage ;
00098 unsigned int min_size ;
00099 int n_hist_bins ;
00100 int print_every_n_elements ;
00101 int referredBit ;
00102
00103 double dist_upper_bound;
00104 double n_samples_per_area_unit;
00105 unsigned long n_samples_target;
00106 int Flags;
00107
00108
00109 Histogram<double> hist;
00110 unsigned long n_total_samples;
00111 unsigned long n_total_area_samples;
00112 unsigned long n_total_edge_samples;
00113 unsigned long n_total_vertex_samples;
00114 double max_dist;
00115 double mean_dist;
00116 double RMS_dist;
00117 double volume;
00118 double area_S1;
00119
00120
00121 int n_samples;
00122
00123
00124 inline double ComputeMeshArea(MetroMesh & mesh);
00125 float AddSample(const Point3x &p);
00126 inline void AddRandomSample(FaceIterator &T);
00127 inline void SampleEdge(const Point3x & v0, const Point3x & v1, int n_samples_per_edge);
00128 void VertexSampling();
00129 void EdgeSampling();
00130 void FaceSubdiv(const Point3x & v0, const Point3x &v1, const Point3x & v2, int maxdepth);
00131 void SimilarTriangles(const Point3x &v0, const Point3x &v1, const Point3x &v2, int n_samples_per_edge);
00132 void MontecarloFaceSampling();
00133 void SubdivFaceSampling();
00134 void SimilarFaceSampling();
00135
00136 public :
00137
00138 Sampling(MetroMesh &_s1, MetroMesh &_s2);
00139 ~Sampling();
00140 void Hausdorff();
00141 double GetArea() {return area_S1;}
00142 double GetDistMax() {return max_dist;}
00143 double GetDistMean() {return mean_dist;}
00144 double GetDistRMS() {return RMS_dist;}
00145 double GetDistVolume() {return volume;}
00146 unsigned long GetNSamples() {return n_total_samples;}
00147 unsigned long GetNAreaSamples() {return n_total_area_samples;}
00148 unsigned long GetNEdgeSamples() {return n_total_edge_samples;}
00149 unsigned long GetNVertexSamples() {return n_total_vertex_samples;}
00150 double GetNSamplesPerAreaUnit() {return n_samples_per_area_unit;}
00151 unsigned long GetNSamplesTarget() {return n_samples_target;}
00152 Histogram<double> &GetHist() {return hist;}
00153 void SetFlags(int flags) {Flags = flags;}
00154 void ClearFlag(int flag) {Flags &= (flag ^ -1);}
00155 void SetParam(double _n_samp) {n_samples_target = _n_samp;}
00156 void SetSamplesTarget(unsigned long _n_samp);
00157 void SetSamplesPerAreaUnit(double _n_samp);
00158 };
00159
00160
00161
00162
00163 template <class MetroMesh>
00164 Sampling<MetroMesh>::Sampling(MetroMesh &_s1, MetroMesh &_s2):S1(_s1),S2(_s2)
00165 {
00166 Flags = 0;
00167 area_S1 = ComputeMeshArea(_s1);
00168
00169 n_samples_per_face = 10;
00170 n_samples_edge_to_face_ratio = 0.1f;
00171 bbox_factor = 0.1f;
00172 inflate_percentage = 0.02f;
00173 min_size = 125;
00174 n_hist_bins = 256;
00175 print_every_n_elements = S1.fn/100;
00176
00177 if(print_every_n_elements <= 1)
00178 print_every_n_elements = 2;
00179
00180 referredBit = VertexType::NewBitFlag();
00181
00182 FaceIterator fi; VertexIterator vi; int i;
00183 for(fi = _s1.face.begin(); fi!= _s1.face.end(); ++fi)
00184 for(i=0;i<3;++i) (*fi).V(i)->SetUserBit(referredBit);
00185 }
00186
00187 template <class MetroMesh>
00188 Sampling<MetroMesh>::~Sampling()
00189 {
00190 VertexType::DeleteBitFlag(referredBit);
00191 }
00192
00193
00194
00195 template <class MetroMesh>
00196 void Sampling<MetroMesh>::SetSamplesTarget(unsigned long _n_samp)
00197 {
00198 n_samples_target = _n_samp;
00199 n_samples_per_area_unit = n_samples_target / (double)area_S1;
00200 }
00201
00202 template <class MetroMesh>
00203 void Sampling<MetroMesh>::SetSamplesPerAreaUnit(double _n_samp)
00204 {
00205 n_samples_per_area_unit = _n_samp;
00206 n_samples_target = (unsigned long)((double) n_samples_per_area_unit * area_S1);
00207 }
00208
00209
00210
00211 template <class MetroMesh>
00212 inline double Sampling<MetroMesh>::ComputeMeshArea(MetroMesh & mesh)
00213 {
00214 FaceIterator face;
00215 double area = 0.0;
00216
00217 for(face=mesh.face.begin(); face != mesh.face.end(); face++)
00218 if(!(*face).IsD())
00219 area += DoubleArea(*face);
00220
00221 return area/2.0;
00222 }
00223
00224 template <class MetroMesh>
00225 float Sampling<MetroMesh>::AddSample(const Point3x &p )
00226 {
00227 FaceType *f=0;
00228 Point3x normf, bestq, ip;
00229 ScalarType dist;
00230
00231 dist = dist_upper_bound;
00232
00233
00234 if(Flags & SamplingFlags::USE_AABB_TREE)
00235 f=tri::GetClosestFaceEP<MetroMesh,MetroMeshAABB>(S2, tS2, p, dist_upper_bound, dist, normf, bestq, ip);
00236 if(Flags & SamplingFlags::USE_HASH_GRID)
00237 f=tri::GetClosestFaceEP<MetroMesh,MetroMeshHash>(S2, hS2, p, dist_upper_bound, dist, normf, bestq, ip);
00238 if(Flags & SamplingFlags::USE_STATIC_GRID)
00239 f=tri::GetClosestFaceEP<MetroMesh,MetroMeshGrid>(S2, gS2, p, dist_upper_bound, dist, normf, bestq, ip);
00240 if (Flags & SamplingFlags::USE_OCTREE)
00241 f=tri::GetClosestFaceEP<MetroMesh,MetroMeshOctree>(S2, oS2, p, dist_upper_bound, dist, normf, bestq, ip);
00242
00243
00244 if(dist == dist_upper_bound)
00245 return -1.0;
00246
00247 if(dist > max_dist)
00248 max_dist = dist;
00249 mean_dist += dist;
00250 RMS_dist += dist*dist;
00251 n_total_samples++;
00252
00253 if(Flags & SamplingFlags::HIST)
00254 hist.Add((float)fabs(dist));
00255
00256 return (float)dist;
00257 }
00258
00259
00260
00261
00262
00263 template <class MetroMesh>
00264 void Sampling<MetroMesh>::VertexSampling()
00265 {
00266
00267 int cnt = 0;
00268 float error;
00269
00270 printf("Vertex sampling\n");
00271 VertexIterator vi;
00272 typename std::vector<VertexPointer>::iterator vif;
00273 for(vi=S1.vert.begin();vi!=S1.vert.end();++vi)
00274 if( (*vi).IsUserBit(referredBit) ||
00275 ((Flags&SamplingFlags::INCLUDE_UNREFERENCED_VERTICES) != 0) )
00276 {
00277 error = AddSample((*vi).cP());
00278
00279 n_total_vertex_samples++;
00280
00281
00282 if(Flags & SamplingFlags::SAVE_ERROR) (*vi).Q() = error;
00283
00284
00285 if(!(++cnt % print_every_n_elements))
00286 printf("Sampling vertices %d%%\r", (100 * cnt/S1.vn));
00287 }
00288 printf(" \r");
00289 }
00290
00291
00292
00293
00294
00295 template <class MetroMesh>
00296 inline void Sampling<MetroMesh>::SampleEdge(const Point3x & v0, const Point3x & v1, int n_samples_per_edge)
00297 {
00298
00299 Point3x e((v1-v0)/(double)(n_samples_per_edge+1));
00300 int i;
00301
00302 for(i=1; i <= n_samples_per_edge; i++)
00303 {
00304 AddSample(v0 + e*i);
00305 n_total_edge_samples++;
00306 }
00307 }
00308
00309
00310 template <class MetroMesh>
00311 void Sampling<MetroMesh>::EdgeSampling()
00312 {
00313
00314 typedef std::pair<VertexPointer, VertexPointer> pvv;
00315 std::vector< pvv > Edges;
00316
00317 printf("Edge sampling\n");
00318
00319
00320 FaceIterator fi;
00321 for(fi=S1.face.begin(); fi != S1.face.end(); fi++)
00322 for(int i=0; i<3; ++i)
00323 {
00324 Edges.push_back(std::make_pair((*fi).V0(i),(*fi).V1(i)));
00325 if(Edges.back().first > Edges.back().second)
00326 std::swap(Edges.back().first, Edges.back().second);
00327 }
00328 sort(Edges.begin(), Edges.end());
00329 typename std::vector< pvv>::iterator edgeend = unique(Edges.begin(), Edges.end());
00330 Edges.resize(edgeend-Edges.begin());
00331
00332
00333 typename std::vector<pvv>::iterator ei;
00334 double n_samples_per_length_unit;
00335 double n_samples_decimal = 0.0;
00336 int cnt=0;
00337 if(Flags & SamplingFlags::FACE_SAMPLING)
00338 n_samples_per_length_unit = sqrt((double)n_samples_per_area_unit);
00339 else
00340 n_samples_per_length_unit = n_samples_per_area_unit;
00341 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00342 {
00343 n_samples_decimal += Distance((*ei).first->cP(),(*ei).second->cP()) * n_samples_per_length_unit;
00344 n_samples = (int) n_samples_decimal;
00345 SampleEdge((*ei).first->cP(), (*ei).second->cP(), (int) n_samples);
00346 n_samples_decimal -= (double) n_samples;
00347
00348
00349 if(!(++cnt % print_every_n_elements))
00350 printf("Sampling edge %lu%%\r", (100 * cnt/Edges.size()));
00351 }
00352 printf(" \r");
00353 }
00354
00355
00356
00357
00358
00359
00360 template <class MetroMesh>
00361 inline void Sampling<MetroMesh>::AddRandomSample(FaceIterator &T)
00362 {
00363
00364 double rnd_1, rnd_2;
00365
00366
00367 Point3x p0(T->V(0)->cP());
00368 Point3x p1(T->V(1)->cP());
00369 Point3x p2(T->V(2)->cP());
00370
00371 Point3x v1(p1 - p0);
00372 Point3x v2(p2 - p0);
00373
00374
00375 rnd_1 = (double)rand() / (double)RAND_MAX;
00376 rnd_2 = (double)rand() / (double)RAND_MAX;
00377 if(rnd_1 + rnd_2 > 1.0)
00378 {
00379 rnd_1 = 1.0 - rnd_1;
00380 rnd_2 = 1.0 - rnd_2;
00381 }
00382
00383
00384 AddSample (p0 + (v1 * rnd_1 + v2 * rnd_2));
00385 n_total_area_samples++;
00386 }
00387
00388 template <class MetroMesh>
00389 void Sampling<MetroMesh>::MontecarloFaceSampling()
00390 {
00391
00392 double n_samples_decimal = 0.0;
00393 FaceIterator fi;
00394
00395 srand(clock());
00396
00397 for(fi=S1.face.begin(); fi != S1.face.end(); fi++)
00398 if(!(*fi).IsD())
00399 {
00400
00401 n_samples_decimal += 0.5*DoubleArea(*fi) * n_samples_per_area_unit;
00402 n_samples = (int) n_samples_decimal;
00403
00404
00405 for(int i=0; i < n_samples; i++)
00406 AddRandomSample(fi);
00407
00408 n_samples_decimal -= (double) n_samples;
00409
00410
00411
00412
00413 }
00414
00415 }
00416
00417
00418
00419 template <class MetroMesh>
00420 void Sampling<MetroMesh>::FaceSubdiv(const Point3x & v0, const Point3x & v1, const Point3x & v2, int maxdepth)
00421 {
00422
00423 if(maxdepth == 0)
00424 {
00425
00426 AddSample((v0+v1+v2)/3.0f);
00427 n_total_area_samples++;
00428 n_samples++;
00429 return;
00430 }
00431
00432
00433 double maxd01 = SquaredDistance(v0,v1);
00434 double maxd12 = SquaredDistance(v1,v2);
00435 double maxd20 = SquaredDistance(v2,v0);
00436 int res;
00437 if(maxd01 > maxd12)
00438 if(maxd01 > maxd20) res = 0;
00439 else res = 2;
00440 else
00441 if(maxd12 > maxd20) res = 1;
00442 else res = 2;
00443
00444
00445 Point3x pp;
00446 switch(res)
00447 {
00448 case 0 : pp = (v0+v1)/2;
00449 FaceSubdiv(v0,pp,v2,maxdepth-1);
00450 FaceSubdiv(pp,v1,v2,maxdepth-1);
00451 break;
00452 case 1 : pp = (v1+v2)/2;
00453 FaceSubdiv(v0,v1,pp,maxdepth-1);
00454 FaceSubdiv(v0,pp,v2,maxdepth-1);
00455 break;
00456 case 2 : pp = (v2+v0)/2;
00457 FaceSubdiv(v0,v1,pp,maxdepth-1);
00458 FaceSubdiv(pp,v1,v2,maxdepth-1);
00459 break;
00460 }
00461 }
00462
00463 template <class MetroMesh>
00464 void Sampling<MetroMesh>::SubdivFaceSampling()
00465 {
00466
00467 int cnt = 0, maxdepth;
00468 double n_samples_decimal = 0.0;
00469 typename MetroMesh::FaceIterator fi;
00470
00471 printf("Subdivision face sampling\n");
00472 for(fi=S1.face.begin(); fi != S1.face.end(); fi++)
00473 {
00474
00475 n_samples_decimal += 0.5*DoubleArea(*fi) * n_samples_per_area_unit;
00476 n_samples = (int) n_samples_decimal;
00477 if(n_samples)
00478 {
00479
00480 maxdepth = ((int)(log((double)n_samples)/log(2.0)));
00481 n_samples = 0;
00482 FaceSubdiv((*fi).V(0)->cP(), (*fi).V(1)->cP(), (*fi).V(2)->cP(), maxdepth);
00483 }
00484 n_samples_decimal -= (double) n_samples;
00485
00486
00487 if(!(++cnt % print_every_n_elements))
00488 printf("Sampling face %d%%\r", (100 * cnt/S1.fn));
00489 }
00490 printf(" \r");
00491 }
00492
00493
00494
00495 template <class MetroMesh>
00496 void Sampling<MetroMesh>::SimilarTriangles(const Point3x & v0, const Point3x & v1, const Point3x & v2, int n_samples_per_edge)
00497 {
00498 Point3x V1((v1-v0)/(double)(n_samples_per_edge-1));
00499 Point3x V2((v2-v0)/(double)(n_samples_per_edge-1));
00500 int i, j;
00501
00502
00503 for(i=1; i < n_samples_per_edge-1; i++)
00504 for(j=1; j < n_samples_per_edge-1-i; j++)
00505 {
00506 AddSample( v0 + (V1*(double)i + V2*(double)j) );
00507 n_total_area_samples++;
00508 n_samples++;
00509 }
00510 }
00511
00512 template <class MetroMesh>
00513 void Sampling<MetroMesh>::SimilarFaceSampling()
00514 {
00515
00516 int cnt = 0, n_samples_per_edge;
00517 double n_samples_decimal = 0.0;
00518 FaceIterator fi;
00519
00520 printf("Similar Triangles face sampling\n");
00521 for(fi=S1.face.begin(); fi != S1.face.end(); fi++)
00522 {
00523
00524 n_samples_decimal += 0.5*DoubleArea(*fi) * n_samples_per_area_unit;
00525 n_samples = (int) n_samples_decimal;
00526 if(n_samples)
00527 {
00528
00529 n_samples_per_edge = (int)((sqrt(1.0+8.0*(double)n_samples) +5.0)/2.0);
00530 n_samples = 0;
00531 SimilarTriangles((*fi).V(0)->cP(), (*fi).V(1)->cP(), (*fi).V(2)->cP(), n_samples_per_edge);
00532 }
00533 n_samples_decimal -= (double) n_samples;
00534
00535
00536 if(!(++cnt % print_every_n_elements))
00537 printf("Sampling face %d%%\r", (100 * cnt/S1.fn));
00538 }
00539 printf(" \r");
00540 }
00541
00542
00543
00544
00545
00546 template <class MetroMesh>
00547 void Sampling<MetroMesh>::Hausdorff()
00548 {
00549 Box3< ScalarType> bbox;
00550
00551 typedef typename std::vector<FaceType>::iterator FaceVecIterator;
00552
00553 if(Flags & SamplingFlags::USE_HASH_GRID) hS2.Set(S2.face.begin(),S2.face.end());
00554 if(Flags & SamplingFlags::USE_AABB_TREE) tS2.Set(S2.face.begin(),S2.face.end());
00555 if(Flags & SamplingFlags::USE_STATIC_GRID) gS2.Set(S2.face.begin(),S2.face.end());
00556 if(Flags & SamplingFlags::USE_OCTREE) oS2.Set(S2.face.begin(),S2.face.end());
00557
00558
00559 bbox = S2.bbox;
00560 dist_upper_bound = bbox.Diag();
00561 if(Flags & SamplingFlags::HIST)
00562 hist.SetRange(0.0, dist_upper_bound/100.0, n_hist_bins);
00563
00564
00565 n_total_area_samples = n_total_edge_samples = n_total_vertex_samples = n_total_samples = n_samples = 0;
00566 max_dist = -HUGE_VAL;
00567 mean_dist = RMS_dist = 0;
00568
00569
00570 if(Flags & SamplingFlags::VERTEX_SAMPLING)
00571 VertexSampling();
00572
00573 if(n_samples_target > n_total_samples)
00574 {
00575 n_samples_target -= (int) n_total_samples;
00576 n_samples_per_area_unit = n_samples_target / area_S1;
00577 if(Flags & SamplingFlags::EDGE_SAMPLING)
00578 {
00579 EdgeSampling();
00580 if(n_samples_target > n_total_samples) n_samples_target -= (int) n_total_samples;
00581 else n_samples_target=0;
00582 }
00583
00584 if((Flags & SamplingFlags::FACE_SAMPLING) && (n_samples_target > 0))
00585 {
00586 n_samples_per_area_unit = n_samples_target / area_S1;
00587 if(Flags & SamplingFlags::MONTECARLO_SAMPLING) MontecarloFaceSampling();
00588 if(Flags & SamplingFlags::SUBDIVISION_SAMPLING) SubdivFaceSampling();
00589 if(Flags & SamplingFlags::SIMILAR_SAMPLING) SimilarFaceSampling();
00590 }
00591 }
00592
00593
00594 if(Flags & SamplingFlags::SAVE_ERROR)
00595 vcg::tri::UpdateColor<MetroMesh>::PerVertexQualityRamp(S1);
00596
00597
00598 n_samples_per_area_unit = (double) n_total_samples / area_S1;
00599 volume = mean_dist / n_samples_per_area_unit / 2.0;
00600 mean_dist /= n_total_samples;
00601 RMS_dist = sqrt(RMS_dist / n_total_samples);
00602 }
00603 }
00604 #endif