00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef __VCGLIB_POINT_SAMPLING
00036 #define __VCGLIB_POINT_SAMPLING
00037
00038
00039 #include <vcg/math/random_generator.h>
00040 #include <vcg/complex/algorithms/closest.h>
00041 #include <vcg/space/index/spatial_hashing.h>
00042 #include <vcg/complex/algorithms/hole.h>
00043 #include <vcg/complex/algorithms/stat.h>
00044 #include <vcg/complex/algorithms/create/platonic.h>
00045 #include <vcg/complex/algorithms/update/topology.h>
00046 #include <vcg/complex/algorithms/update/normal.h>
00047 #include <vcg/complex/algorithms/update/bounding.h>
00048 #include <vcg/complex/algorithms/update/flag.h>
00049 #include <vcg/space/segment2.h>
00050 #include <vcg/space/index/grid_static_ptr.h>
00051 namespace vcg
00052 {
00053 namespace tri
00054 {
00057
00071 template <class MeshType>
00072 class TrivialSampler
00073 {
00074 public:
00075 typedef typename MeshType::ScalarType ScalarType;
00076 typedef typename MeshType::CoordType CoordType;
00077 typedef typename MeshType::VertexType VertexType;
00078 typedef typename MeshType::EdgeType EdgeType;
00079 typedef typename MeshType::FaceType FaceType;
00080
00081 void reset()
00082 {
00083 sampleVec->clear();
00084 }
00085
00086 TrivialSampler()
00087 {
00088 sampleVec = new std::vector<CoordType>();
00089 vectorOwner=true;
00090 }
00091
00092 TrivialSampler(std::vector<CoordType> &Vec)
00093 {
00094 sampleVec = &Vec;
00095 vectorOwner=false;
00096 reset();
00097 }
00098
00099 ~TrivialSampler()
00100 {
00101 if(vectorOwner) delete sampleVec;
00102 }
00103
00104 private:
00105 std::vector<CoordType> *sampleVec;
00106 bool vectorOwner;
00107 public:
00108
00109 void AddVert(const VertexType &p)
00110 {
00111 sampleVec->push_back(p.cP());
00112 }
00113 void AddEdge(const EdgeType& e, ScalarType u )
00114 {
00115 sampleVec->push_back(e.cV(0)->cP()*(1.0-u)+e.cV(1)->cP()*u);
00116 }
00117
00118 void AddFace(const FaceType &f, const CoordType &p)
00119 {
00120 sampleVec->push_back(f.cP(0)*p[0] + f.cP(1)*p[1] +f.cP(2)*p[2] );
00121 }
00122
00123 void AddTextureSample(const FaceType &, const CoordType &, const Point2i &, float )
00124 {
00125
00126
00127
00128 }
00129 };
00130
00131 template <class MeshType>
00132 class TrivialPointerSampler
00133 {
00134 public:
00135 typedef typename MeshType::CoordType CoordType;
00136 typedef typename MeshType::VertexType VertexType;
00137 typedef typename MeshType::FaceType FaceType;
00138
00139 TrivialPointerSampler() {}
00140 ~TrivialPointerSampler() {}
00141
00142 void reset()
00143 {
00144 sampleVec.clear();
00145 }
00146
00147 public:
00148 std::vector<VertexType *> sampleVec;
00149
00150 void AddVert(VertexType &p)
00151 {
00152 sampleVec.push_back(&p);
00153 }
00154
00155 void AddFace(const FaceType &, const CoordType &) { assert(0); }
00156 void AddTextureSample(const FaceType &, const CoordType &, const Point2i &, float ) { assert(0); }
00157 };
00158
00159
00160 template <class MeshType>
00161 class MeshSampler
00162 {
00163 public:
00164 typedef typename MeshType::VertexType VertexType;
00165 typedef typename MeshType::FaceType FaceType;
00166 typedef typename MeshType::CoordType CoordType;
00167
00168 MeshSampler(MeshType &_m):m(_m){
00169 perFaceNormal = false;
00170 }
00171 MeshType &m;
00172
00173 bool perFaceNormal;
00174
00175 void reset()
00176 {
00177 m.Clear();
00178 }
00179
00180 void AddVert(const VertexType &p)
00181 {
00182 tri::Allocator<MeshType>::AddVertices(m,1);
00183 m.vert.back().ImportData(p);
00184 }
00185
00186 void AddFace(const FaceType &f, CoordType p)
00187 {
00188 tri::Allocator<MeshType>::AddVertices(m,1);
00189 m.vert.back().P() = f.cP(0)*p[0] + f.cP(1)*p[1] +f.cP(2)*p[2];
00190 if(perFaceNormal) m.vert.back().N() = f.cN();
00191 else m.vert.back().N() = f.cV(0)->N()*p[0] + f.cV(1)->N()*p[1] + f.cV(2)->N()*p[2];
00192 if(tri::HasPerVertexQuality(m) )
00193 m.vert.back().Q() = f.cV(0)->Q()*p[0] + f.cV(1)->Q()*p[1] + f.cV(2)->Q()*p[2];
00194 }
00195 };
00196
00197
00198
00199
00200
00201
00202
00203
00204 template <class MeshType>
00205 class HausdorffSampler
00206 {
00207 typedef typename MeshType::FaceType FaceType;
00208 typedef typename MeshType::VertexType VertexType;
00209 typedef typename MeshType::CoordType CoordType;
00210 typedef typename MeshType::ScalarType ScalarType;
00211 typedef GridStaticPtr<FaceType, ScalarType > MetroMeshFaceGrid;
00212 typedef GridStaticPtr<VertexType, ScalarType > MetroMeshVertexGrid;
00213
00214 public:
00215
00216 HausdorffSampler(MeshType* _m, MeshType* _sampleMesh=0, MeshType* _closestMesh=0 ) :markerFunctor(_m)
00217 {
00218 m=_m;
00219 init(_sampleMesh,_closestMesh);
00220 }
00221
00222 MeshType *m;
00223 MeshType *samplePtMesh;
00224 MeshType *closestPtMesh;
00225
00226 MetroMeshVertexGrid unifGridVert;
00227 MetroMeshFaceGrid unifGridFace;
00228
00229
00230 double min_dist;
00231 double max_dist;
00232 double mean_dist;
00233 double RMS_dist;
00234 double volume;
00235 double area_S1;
00236 Histogramf hist;
00237
00238 int n_total_samples;
00239 int n_samples;
00240 bool useVertexSampling;
00241 ScalarType dist_upper_bound;
00242 typedef typename tri::FaceTmark<MeshType> MarkerFace;
00243 MarkerFace markerFunctor;
00244
00245
00246 float getMeanDist() const { return mean_dist / n_total_samples; }
00247 float getMinDist() const { return min_dist ; }
00248 float getMaxDist() const { return max_dist ; }
00249 float getRMSDist() const { return sqrt(RMS_dist / n_total_samples); }
00250
00251 void init(MeshType* _sampleMesh=0, MeshType* _closestMesh=0 )
00252 {
00253 samplePtMesh =_sampleMesh;
00254 closestPtMesh = _closestMesh;
00255 if(m)
00256 {
00257 tri::UpdateNormal<MeshType>::PerFaceNormalized(*m);
00258 if(m->fn==0) useVertexSampling = true;
00259 else useVertexSampling = false;
00260
00261 if(useVertexSampling) unifGridVert.Set(m->vert.begin(),m->vert.end());
00262 else unifGridFace.Set(m->face.begin(),m->face.end());
00263 markerFunctor.SetMesh(m);
00264 hist.SetRange(0.0, m->bbox.Diag()/100.0, 100);
00265 }
00266 min_dist = std::numeric_limits<double>::max();
00267 max_dist = 0;
00268 mean_dist =0;
00269 RMS_dist = 0;
00270 n_total_samples = 0;
00271 }
00272
00273 void AddFace(const FaceType &f, CoordType interp)
00274 {
00275 CoordType startPt = f.cP(0)*interp[0] + f.cP(1)*interp[1] +f.cP(2)*interp[2];
00276 CoordType startN = f.cV(0)->cN()*interp[0] + f.cV(1)->cN()*interp[1] +f.cV(2)->cN()*interp[2];
00277 AddSample(startPt,startN);
00278 }
00279
00280 void AddVert(VertexType &p)
00281 {
00282 p.Q()=AddSample(p.cP(),p.cN());
00283 }
00284
00285
00286 float AddSample(const CoordType &startPt,const CoordType &startN)
00287 {
00288
00289 CoordType closestPt;
00290 ScalarType dist = dist_upper_bound;
00291
00292
00293 FaceType *nearestF=0;
00294 VertexType *nearestV=0;
00295 vcg::face::PointDistanceBaseFunctor<ScalarType> PDistFunct;
00296 dist=dist_upper_bound;
00297 if(useVertexSampling)
00298 nearestV = tri::GetClosestVertex<MeshType,MetroMeshVertexGrid>(*m,unifGridVert,startPt,dist_upper_bound,dist);
00299 else
00300 nearestF = unifGridFace.GetClosest(PDistFunct,markerFunctor,startPt,dist_upper_bound,dist,closestPt);
00301
00302
00303 if(dist == dist_upper_bound)
00304 return dist;
00305
00306 if(dist > max_dist) max_dist = dist;
00307 if(dist < min_dist) min_dist = dist;
00308
00309 mean_dist += dist;
00310 RMS_dist += dist*dist;
00311 n_total_samples++;
00312
00313 hist.Add((float)fabs(dist));
00314 if(samplePtMesh)
00315 {
00316 tri::Allocator<MeshType>::AddVertices(*samplePtMesh,1);
00317 samplePtMesh->vert.back().P() = startPt;
00318 samplePtMesh->vert.back().Q() = dist;
00319 samplePtMesh->vert.back().N() = startN;
00320 }
00321 if(closestPtMesh)
00322 {
00323 tri::Allocator<MeshType>::AddVertices(*closestPtMesh,1);
00324 closestPtMesh->vert.back().P() = closestPt;
00325 closestPtMesh->vert.back().Q() = dist;
00326 closestPtMesh->vert.back().N() = startN;
00327 }
00328 return dist;
00329 }
00330 };
00331
00332
00333
00334
00335
00336
00337 template <class MeshType>
00338 class RedetailSampler
00339 {
00340 typedef typename MeshType::FaceType FaceType;
00341 typedef typename MeshType::VertexType VertexType;
00342 typedef typename MeshType::CoordType CoordType;
00343 typedef typename MeshType::ScalarType ScalarType;
00344 typedef GridStaticPtr<FaceType, ScalarType > MetroMeshGrid;
00345 typedef GridStaticPtr<VertexType, ScalarType > VertexMeshGrid;
00346
00347 public:
00348
00349 RedetailSampler():m(0) {}
00350
00351 MeshType *m;
00352 CallBackPos *cb;
00353 int sampleNum;
00354 int sampleCnt;
00355 MetroMeshGrid unifGridFace;
00356 VertexMeshGrid unifGridVert;
00357 bool useVertexSampling;
00358
00359
00360 typedef tri::FaceTmark<MeshType> MarkerFace;
00361 MarkerFace markerFunctor;
00362
00363 bool coordFlag;
00364 bool colorFlag;
00365 bool normalFlag;
00366 bool qualityFlag;
00367 bool selectionFlag;
00368 bool storeDistanceAsQualityFlag;
00369 float dist_upper_bound;
00370 void init(MeshType *_m, CallBackPos *_cb=0, int targetSz=0)
00371 {
00372 coordFlag=false;
00373 colorFlag=false;
00374 qualityFlag=false;
00375 selectionFlag=false;
00376 storeDistanceAsQualityFlag=false;
00377 m=_m;
00378 tri::UpdateNormal<MeshType>::PerFaceNormalized(*m);
00379 if(m->fn==0) useVertexSampling = true;
00380 else useVertexSampling = false;
00381
00382 if(useVertexSampling) unifGridVert.Set(m->vert.begin(),m->vert.end());
00383 else unifGridFace.Set(m->face.begin(),m->face.end());
00384 markerFunctor.SetMesh(m);
00385
00386 cb=_cb;
00387 sampleNum = targetSz;
00388 sampleCnt = 0;
00389 }
00390
00391
00392
00393 void AddVert(VertexType &p)
00394 {
00395 assert(m);
00396
00397 CoordType closestPt, normf, bestq, ip;
00398 ScalarType dist = dist_upper_bound;
00399 const CoordType &startPt= p.cP();
00400
00401 if(useVertexSampling)
00402 {
00403 VertexType *nearestV=0;
00404 nearestV = tri::GetClosestVertex<MeshType,VertexMeshGrid>(*m,unifGridVert,startPt,dist_upper_bound,dist);
00405 if(cb) cb(sampleCnt++*100/sampleNum,"Resampling Vertex attributes");
00406 if(storeDistanceAsQualityFlag) p.Q() = dist;
00407 if(dist == dist_upper_bound) return ;
00408
00409 if(coordFlag) p.P()=nearestV->P();
00410 if(colorFlag) p.C() = nearestV->C();
00411 if(normalFlag) p.N() = nearestV->N();
00412 if(qualityFlag) p.Q()= nearestV->Q();
00413 if(selectionFlag) if(nearestV->IsS()) p.SetS();
00414 }
00415 else
00416 {
00417 FaceType *nearestF=0;
00418 vcg::face::PointDistanceBaseFunctor<ScalarType> PDistFunct;
00419 dist=dist_upper_bound;
00420 if(cb) cb(sampleCnt++*100/sampleNum,"Resampling Vertex attributes");
00421 nearestF = unifGridFace.GetClosest(PDistFunct,markerFunctor,startPt,dist_upper_bound,dist,closestPt);
00422 if(dist == dist_upper_bound) return ;
00423
00424 CoordType interp;
00425 InterpolationParameters(*nearestF,(*nearestF).cN(),closestPt, interp);
00426 interp[2]=1.0-interp[1]-interp[0];
00427
00428 if(coordFlag) p.P()=closestPt;
00429 if(colorFlag) p.C().lerp(nearestF->V(0)->C(),nearestF->V(1)->C(),nearestF->V(2)->C(),interp);
00430 if(normalFlag) p.N() = nearestF->V(0)->N()*interp[0] + nearestF->V(1)->N()*interp[1] + nearestF->V(2)->N()*interp[2];
00431 if(qualityFlag) p.Q()= nearestF->V(0)->Q()*interp[0] + nearestF->V(1)->Q()*interp[1] + nearestF->V(2)->Q()*interp[2];
00432 if(selectionFlag) if(nearestF->IsS()) p.SetS();
00433 }
00434 }
00435 };
00436
00437
00438
00439
00450 template <class MeshType, class VertexSampler = TrivialSampler< MeshType> >
00451 class SurfaceSampling
00452 {
00453 typedef typename MeshType::CoordType CoordType;
00454 typedef typename MeshType::BoxType BoxType;
00455 typedef typename MeshType::ScalarType ScalarType;
00456 typedef typename MeshType::VertexType VertexType;
00457 typedef typename MeshType::VertexPointer VertexPointer;
00458 typedef typename MeshType::VertexIterator VertexIterator;
00459 typedef typename MeshType::EdgeType EdgeType;
00460 typedef typename MeshType::EdgeIterator EdgeIterator;
00461 typedef typename MeshType::FaceType FaceType;
00462 typedef typename MeshType::FacePointer FacePointer;
00463 typedef typename MeshType::FaceIterator FaceIterator;
00464 typedef typename MeshType::FaceContainer FaceContainer;
00465
00466 typedef typename vcg::SpatialHashTable<FaceType, ScalarType> MeshSHT;
00467 typedef typename vcg::SpatialHashTable<FaceType, ScalarType>::CellIterator MeshSHTIterator;
00468 typedef typename vcg::SpatialHashTable<VertexType, ScalarType> MontecarloSHT;
00469 typedef typename vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator MontecarloSHTIterator;
00470 typedef typename vcg::SpatialHashTable<VertexType, ScalarType> SampleSHT;
00471 typedef typename vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator SampleSHTIterator;
00472
00473 typedef typename MeshType::template PerVertexAttributeHandle<float> PerVertexFloatAttribute;
00474
00475 public:
00476
00477 static math::MarsenneTwisterRNG &SamplingRandomGenerator()
00478 {
00479 static math::MarsenneTwisterRNG rnd;
00480 return rnd;
00481 }
00482
00483
00484
00485 static unsigned int RandomInt(unsigned int i)
00486 {
00487 return (SamplingRandomGenerator().generate(i));
00488 }
00489
00490
00491 static double RandomDouble01()
00492 {
00493 return SamplingRandomGenerator().generate01();
00494 }
00495
00496 #define FAK_LEN 1024
00497 static double LnFac(int n) {
00498
00499
00500
00501 static const double
00502 C0 = 0.918938533204672722,
00503 C1 = 1./12.,
00504 C3 = -1./360.;
00505
00506
00507
00508 static double fac_table[FAK_LEN];
00509 static bool initialized = false;
00510
00511
00512 if (n < FAK_LEN) {
00513 if (n <= 1) {
00514 if (n < 0) assert(0);
00515 return 0;
00516 }
00517 if (!initialized) {
00518
00519 double sum = fac_table[0] = 0.;
00520 for (int i=1; i<FAK_LEN; i++) {
00521 sum += log(double(i));
00522 fac_table[i] = sum;
00523 }
00524 initialized = true;
00525 }
00526 return fac_table[n];
00527 }
00528
00529 double n1, r;
00530 n1 = n; r = 1. / n1;
00531 return (n1 + 0.5)*log(n1) - n1 + C0 + r*(C1 + r*r*C3);
00532 }
00533
00534 static int PoissonRatioUniforms(double L) {
00535
00536
00537
00538
00539
00540
00541
00542
00543
00544
00545
00546
00547
00548
00549
00550
00551
00552
00553
00554
00555
00556 const double SHAT1 = 2.943035529371538573;
00557 const double SHAT2 = 0.8989161620588987408;
00558 double u;
00559 double lf;
00560 double x;
00561 int k;
00562
00563 double pois_a = L + 0.5;
00564 int mode = (int)L;
00565 double pois_g = log(L);
00566 double pois_f0 = mode * pois_g - LnFac(mode);
00567 double pois_h = sqrt(SHAT1 * (L+0.5)) + SHAT2;
00568 double pois_bound = (int)(pois_a + 6.0 * pois_h);
00569
00570 while(1) {
00571 u = RandomDouble01();
00572 if (u == 0) continue;
00573 x = pois_a + pois_h * (RandomDouble01() - 0.5) / u;
00574 if (x < 0 || x >= pois_bound) continue;
00575 k = (int)(x);
00576 lf = k * pois_g - LnFac(k) - pois_f0;
00577 if (lf >= u * (4.0 - u) - 3.0) break;
00578 if (u * (u - lf) > 1.0) continue;
00579 if (2.0 * log(u) <= lf) break;
00580 }
00581 return k;
00582 }
00583
00584
00596 static int Poisson(double lambda)
00597 {
00598 if(lambda>50) return PoissonRatioUniforms(lambda);
00599 double L = exp(-lambda);
00600 int k =0;
00601 double p = 1.0;
00602 do
00603 {
00604 k = k+1;
00605 p = p*RandomDouble01();
00606 } while (p>L);
00607
00608 return k -1;
00609 }
00610
00611
00612 static void AllVertex(MeshType & m, VertexSampler &ps)
00613 {
00614 AllVertex(m, ps, false);
00615 }
00616
00617 static void AllVertex(MeshType & m, VertexSampler &ps, bool onlySelected)
00618 {
00619 VertexIterator vi;
00620 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00621 if(!(*vi).IsD())
00622 if ((!onlySelected) || ((*vi).IsS()))
00623 {
00624 ps.AddVert(*vi);
00625 }
00626 }
00627
00635
00636 static void VertexWeighted(MeshType & m, VertexSampler &ps, int sampleNum)
00637 {
00638 ScalarType qSum = 0;
00639 VertexIterator vi;
00640 for(vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00641 if(!(*vi).IsD())
00642 qSum += (*vi).Q();
00643
00644 ScalarType samplePerUnit = sampleNum/qSum;
00645 ScalarType floatSampleNum =0;
00646 std::vector<VertexPointer> vertVec;
00647 FillAndShuffleVertexPointerVector(m,vertVec);
00648
00649 std::vector<bool> vertUsed(m.vn,false);
00650
00651 int i=0; int cnt=0;
00652 while(cnt < sampleNum)
00653 {
00654 if(vertUsed[i])
00655 {
00656 floatSampleNum += vertVec[i]->Q() * samplePerUnit;
00657 int vertSampleNum = (int) floatSampleNum;
00658 floatSampleNum -= (float) vertSampleNum;
00659
00660
00661 if(vertSampleNum > 1)
00662 {
00663 ps.AddVert(*vertVec[i]);
00664 cnt++;
00665 vertUsed[i]=true;
00666 }
00667 }
00668 i = (i+1)%m.vn;
00669 }
00670 }
00671
00674 static void VertexAreaUniform(MeshType & m, VertexSampler &ps, int sampleNum)
00675 {
00676 VertexIterator vi;
00677 for(vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00678 if(!(*vi).IsD())
00679 (*vi).Q() = 0;
00680
00681 FaceIterator fi;
00682 for(fi = m.face.begin(); fi != m.face.end(); ++fi)
00683 if(!(*fi).IsD())
00684 {
00685 ScalarType areaThird = DoubleArea(*fi)/6.0;
00686 (*fi).V(0)->Q()+=areaThird;
00687 (*fi).V(1)->Q()+=areaThird;
00688 (*fi).V(2)->Q()+=areaThird;
00689 }
00690
00691 VertexWeighted(m,ps,sampleNum);
00692 }
00693
00694 static void FillAndShuffleFacePointerVector(MeshType & m, std::vector<FacePointer> &faceVec)
00695 {
00696 for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi)
00697 if(!(*fi).IsD()) faceVec.push_back(&*fi);
00698
00699 assert((int)faceVec.size()==m.fn);
00700
00701 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
00702 std::random_shuffle(faceVec.begin(),faceVec.end(), p_myrandom);
00703 }
00704 static void FillAndShuffleVertexPointerVector(MeshType & m, std::vector<VertexPointer> &vertVec)
00705 {
00706 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00707 if(!(*vi).IsD()) vertVec.push_back(&*vi);
00708
00709 assert((int)vertVec.size()==m.vn);
00710
00711 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
00712 std::random_shuffle(vertVec.begin(),vertVec.end(), p_myrandom);
00713 }
00714
00716 static void VertexUniform(MeshType & m, VertexSampler &ps, int sampleNum, bool onlySelected)
00717 {
00718 if (sampleNum >= m.vn) {
00719 AllVertex(m, ps, onlySelected);
00720 return;
00721 }
00722
00723 std::vector<VertexPointer> vertVec;
00724 FillAndShuffleVertexPointerVector(m, vertVec);
00725
00726 int added = 0;
00727 for (int i = 0; ((i < m.vn) && (added < sampleNum)); ++i)
00728 if (!(*vertVec[i]).IsD())
00729 if ((!onlySelected) || (*vertVec[i]).IsS())
00730 {
00731 ps.AddVert(*vertVec[i]);
00732 added++;
00733 }
00734
00735 }
00736
00737
00738 static void VertexUniform(MeshType & m, VertexSampler &ps, int sampleNum)
00739 {
00740 VertexUniform(m, ps, sampleNum, false);
00741 }
00742
00743
00751 static void EdgeMeshUniform(MeshType &m, VertexSampler &ps, float radius, bool conservative = true)
00752 {
00753 tri::RequireEEAdjacency(m);
00754 tri::RequireCompactness(m);
00755 tri::RequirePerEdgeFlags(m);
00756 tri::RequirePerVertexFlags(m);
00757 tri::UpdateTopology<MeshType>::EdgeEdge(m);
00758 tri::UpdateFlags<MeshType>::EdgeClearV(m);
00759
00760 for (EdgeIterator ei = m.edge.begin(); ei != m.edge.end(); ++ei)
00761 {
00762 if (!ei->IsV())
00763 {
00764 edge::Pos<EdgeType> ep(&*ei,0);
00765 edge::Pos<EdgeType> startep = ep;
00766 VertexPointer startVertex = 0;
00767 do
00768 {
00769 ep.NextE();
00770 if (ep.IsBorder())
00771 break;
00772 } while (startep != ep);
00773 if (!ep.IsBorder())
00774 {
00775
00776 startVertex = ep.V();
00777 }
00778 else
00779 {
00780
00781
00782 edge::Pos<EdgeType> altEp = ep;
00783 do {
00784 altEp.NextE();
00785 } while (!altEp.IsBorder());
00786
00787 if (altEp.V()->cP() < ep.V()->cP())
00788 {
00789 ep = altEp;
00790 }
00791 }
00792
00793 ScalarType totalLen = 0;
00794 ep.FlipV();
00795
00796 do
00797 {
00798 ep.E()->SetV();
00799 totalLen += Distance(ep.V()->cP(), ep.VFlip()->cP());
00800 ep.NextE();
00801 } while (!ep.IsBorder() && ep.V() != startVertex);
00802 ep.E()->SetV();
00803 totalLen += Distance(ep.V()->cP(), ep.VFlip()->cP());
00804
00805
00806 int sampleNum = conservative ? floor(totalLen / radius) : ceil(totalLen / radius);
00807
00808 ScalarType sampleDist = totalLen / sampleNum;
00809
00810
00811 ScalarType curLen = 0;
00812 int sampleCnt = 1;
00813 ps.AddEdge(*(ep.E()), ep.VInd() == 0 ? 0.0 : 1.0);
00814 do
00815 {
00816 ep.NextE();
00817 assert(ep.E()->IsV());
00818 ScalarType edgeLen = Distance(ep.V()->cP(), ep.VFlip()->cP());
00819 ScalarType d0 = curLen;
00820 ScalarType d1 = d0 + edgeLen;
00821
00822 while (d1 > sampleCnt * sampleDist && sampleCnt < sampleNum)
00823 {
00824 ScalarType off = (sampleCnt * sampleDist - d0) / edgeLen;
00825
00826 ps.AddEdge(*(ep.E()), ep.VInd() == 0 ? 1.0 - off : off);
00827 sampleCnt++;
00828 }
00829 curLen += edgeLen;
00830 } while(!ep.IsBorder() && ep.V() != startVertex);
00831
00832 if(ep.V() != startVertex)
00833 ps.AddEdge(*(ep.E()), ep.VInd() == 0 ? 0.0 : 1.0);
00834 }
00835 }
00836 }
00837
00838
00844 static void VertexBorderCorner(MeshType & m, VertexSampler &ps, float angleRad)
00845 {
00846 typename MeshType::template PerVertexAttributeHandle <float> angleSumH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<float> (m);
00847
00848 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00849 angleSumH[vi]=0;
00850
00851 for(FaceIterator fi=m.face.begin();fi!=m.face.end();++fi)
00852 {
00853 for(int i=0;i<3;++i)
00854 {
00855 angleSumH[fi->V(i)] += vcg::Angle(fi->P2(i) - fi->P0(i),fi->P1(i) - fi->P0(i));
00856 }
00857 }
00858
00859 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00860 {
00861 if((angleSumH[vi]<angleRad && vi->IsB())||
00862 (angleSumH[vi]>(360-angleRad) && vi->IsB()))
00863 ps.AddVert(*vi);
00864 }
00865
00866 tri::Allocator<MeshType>:: template DeletePerVertexAttribute<float> (m,angleSumH);
00867 }
00868
00874 static void VertexBorder(MeshType & m, VertexSampler &ps)
00875 {
00876 VertexBorderCorner(m,ps,std::numeric_limits<ScalarType>::max());
00877 }
00878
00885 static void VertexCrease(MeshType & m, VertexSampler &ps)
00886 {
00887 typedef typename UpdateTopology<MeshType>::PEdge SimpleEdge;
00888 std::vector< SimpleEdge > Edges;
00889 typename std::vector< SimpleEdge >::iterator ei;
00890 UpdateTopology<MeshType>::FillUniqueEdgeVector(m,Edges,false);
00891
00892 typename MeshType::template PerVertexAttributeHandle <int> hv = tri::Allocator<MeshType>:: template GetPerVertexAttribute<int> (m);
00893
00894 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00895 {
00896 hv[ei->v[0]]++;
00897 hv[ei->v[1]]++;
00898 }
00899
00900 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00901 {
00902 if(hv[vi]>2)
00903 ps.AddVert(*vi);
00904 }
00905 }
00906
00907
00908 static void FaceUniform(MeshType & m, VertexSampler &ps, int sampleNum)
00909 {
00910 if(sampleNum>=m.fn) {
00911 AllFace(m,ps);
00912 return;
00913 }
00914
00915 std::vector<FacePointer> faceVec;
00916 FillAndShuffleFacePointerVector(m,faceVec);
00917
00918 for(int i =0; i< sampleNum; ++i)
00919 ps.AddFace(*faceVec[i],Barycenter(*faceVec[i]));
00920 }
00921
00922 static void AllFace(MeshType & m, VertexSampler &ps)
00923 {
00924 FaceIterator fi;
00925 for(fi=m.face.begin();fi!=m.face.end();++fi)
00926 if(!(*fi).IsD())
00927 {
00928 ps.AddFace(*fi,Barycenter(*fi));
00929 }
00930 }
00931
00932
00933 static void AllEdge(MeshType & m, VertexSampler &ps)
00934 {
00935
00936 typedef typename UpdateTopology<MeshType>::PEdge SimpleEdge;
00937 std::vector< SimpleEdge > Edges;
00938 typename std::vector< SimpleEdge >::iterator ei;
00939 UpdateTopology<MeshType>::FillUniqueEdgeVector(m,Edges);
00940
00941 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00942 ps.AddFace(*(*ei).f,ei->EdgeBarycentricToFaceBarycentric(0.5));
00943 }
00944
00945
00946
00947
00948
00949 static void EdgeUniform(MeshType & m, VertexSampler &ps,int sampleNum, bool sampleFauxEdge=true)
00950 {
00951 typedef typename UpdateTopology<MeshType>::PEdge SimpleEdge;
00952
00953 std::vector< SimpleEdge > Edges;
00954 UpdateTopology<MeshType>::FillUniqueEdgeVector(m,Edges,sampleFauxEdge);
00955
00956 float edgeSum=0;
00957 typename std::vector< SimpleEdge >::iterator ei;
00958 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00959 edgeSum+=Distance((*ei).v[0]->P(),(*ei).v[1]->P());
00960
00961 float sampleLen = edgeSum/sampleNum;
00962 float rest=0;
00963 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00964 {
00965 float len = Distance((*ei).v[0]->P(),(*ei).v[1]->P());
00966 float samplePerEdge = floor((len+rest)/sampleLen);
00967 rest = (len+rest) - samplePerEdge * sampleLen;
00968 float step = 1.0/(samplePerEdge+1);
00969 for(int i=0;i<samplePerEdge;++i)
00970 {
00971 CoordType interp(0,0,0);
00972 interp[ (*ei).z ]=step*(i+1);
00973 interp[((*ei).z+1)%3]=1.0-step*(i+1);
00974 ps.AddFace(*(*ei).f,interp);
00975 }
00976 }
00977 }
00978
00979
00980
00981
00982 static CoordType RandomBarycentric()
00983 {
00984 return math::GenerateBarycentricUniform<ScalarType>(SamplingRandomGenerator());
00985 }
00986
00987
00988 static CoordType RandomPointInTriangle(const FaceType &f)
00989 {
00990 CoordType u = RandomBarycentric();
00991 return f.cP(0)*u[0] + f.cP(1)*u[1] + f.cP(2)*u[2];
00992 }
00993
00994 static void StratifiedMontecarlo(MeshType & m, VertexSampler &ps,int sampleNum)
00995 {
00996 ScalarType area = Stat<MeshType>::ComputeMeshArea(m);
00997 ScalarType samplePerAreaUnit = sampleNum/area;
00998
00999 double floatSampleNum = 0.0;
01000
01001 FaceIterator fi;
01002 for(fi=m.face.begin(); fi != m.face.end(); fi++)
01003 if(!(*fi).IsD())
01004 {
01005
01006 floatSampleNum += 0.5*DoubleArea(*fi) * samplePerAreaUnit;
01007 int faceSampleNum = (int) floatSampleNum;
01008
01009
01010 for(int i=0; i < faceSampleNum; i++)
01011 ps.AddFace(*fi,RandomBarycentric());
01012 floatSampleNum -= (double) faceSampleNum;
01013 }
01014 }
01015
01030 static void MontecarloPoisson(MeshType & m, VertexSampler &ps,int sampleNum)
01031 {
01032 ScalarType area = Stat<MeshType>::ComputeMeshArea(m);
01033 ScalarType samplePerAreaUnit = sampleNum/area;
01034
01035 FaceIterator fi;
01036 for(fi=m.face.begin(); fi != m.face.end(); fi++)
01037 if(!(*fi).IsD())
01038 {
01039 float areaT=DoubleArea(*fi) * 0.5f;
01040 int faceSampleNum = Poisson(areaT*samplePerAreaUnit);
01041
01042
01043 for(int i=0; i < faceSampleNum; i++)
01044 ps.AddFace(*fi,RandomBarycentric());
01045
01046 }
01047 }
01048
01049
01056 static void EdgeMontecarlo(MeshType & m, VertexSampler &ps, int sampleNum, bool sampleAllEdges)
01057 {
01058 typedef typename UpdateTopology<MeshType>::PEdge SimpleEdge;
01059 std::vector< SimpleEdge > Edges;
01060 UpdateTopology<MeshType>::FillUniqueEdgeVector(m,Edges,sampleAllEdges);
01061
01062 assert(!Edges.empty());
01063
01064 typedef std::pair<ScalarType, SimpleEdge*> IntervalType;
01065 std::vector< IntervalType > intervals (Edges.size()+1);
01066 int i=0;
01067 intervals[i]=std::make_pair(0,(SimpleEdge*)(0));
01068
01069 typename std::vector< SimpleEdge >::iterator ei;
01070 for(ei=Edges.begin(); ei != Edges.end(); ei++)
01071 {
01072 intervals[i+1]=std::make_pair(intervals[i].first+Distance((*ei).v[0]->P(),(*ei).v[1]->P()), &*ei);
01073 ++i;
01074 }
01075
01076
01077 ScalarType edgeSum = intervals.back().first;
01078 for(i=0;i<sampleNum;++i)
01079 {
01080 ScalarType val = edgeSum * RandomDouble01();
01081
01082
01083 typename std::vector<IntervalType>::iterator it = lower_bound(intervals.begin(),intervals.end(),std::make_pair(val,(SimpleEdge*)(0)) );
01084 assert(it != intervals.end() && it != intervals.begin());
01085 assert( ( (*(it-1)).first < val ) && ((*(it)).first >= val) );
01086 SimpleEdge * ep=(*it).second;
01087 ps.AddFace( *(ep->f), ep->EdgeBarycentricToFaceBarycentric(RandomDouble01()) );
01088 }
01089 }
01090
01097 static void Montecarlo(MeshType & m, VertexSampler &ps,int sampleNum)
01098 {
01099 typedef std::pair<ScalarType, FacePointer> IntervalType;
01100 std::vector< IntervalType > intervals (m.fn+1);
01101 FaceIterator fi;
01102 int i=0;
01103 intervals[i]=std::make_pair(0,FacePointer(0));
01104
01105 for(fi=m.face.begin(); fi != m.face.end(); fi++)
01106 if(!(*fi).IsD())
01107 {
01108 intervals[i+1]=std::make_pair(intervals[i].first+0.5*DoubleArea(*fi), &*fi);
01109 ++i;
01110 }
01111 ScalarType meshArea = intervals.back().first;
01112 for(i=0;i<sampleNum;++i)
01113 {
01114 ScalarType val = meshArea * RandomDouble01();
01115
01116
01117 typename std::vector<IntervalType>::iterator it = lower_bound(intervals.begin(),intervals.end(),std::make_pair(val,FacePointer(0)) );
01118 assert(it != intervals.end());
01119 assert(it != intervals.begin());
01120 assert( (*(it-1)).first <val );
01121 assert( (*(it)).first >= val);
01122 ps.AddFace( *(*it).second, RandomBarycentric() );
01123 }
01124 }
01125
01126 static ScalarType WeightedArea(FaceType &f, PerVertexFloatAttribute &wH)
01127 {
01128 ScalarType averageQ = ( wH[f.V(0)] + wH[f.V(1)] + wH[f.V(2)] )/3.0;
01129 return averageQ*averageQ*DoubleArea(f)/2.0;
01130 }
01131
01140 static void WeightedMontecarlo(MeshType & m, VertexSampler &ps,int sampleNum, float variance)
01141 {
01142 tri::RequirePerVertexQuality(m);
01143 tri::RequireCompactness(m);
01144 PerVertexFloatAttribute rH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<float> (m,"radius");
01145 InitRadiusHandleFromQuality(m, rH, 1.0, variance, true);
01146
01147 ScalarType weightedArea = 0;
01148 for(FaceIterator fi = m.face.begin(); fi != m.face.end(); ++fi)
01149 weightedArea += WeightedArea(*fi,rH);
01150
01151 ScalarType samplePerAreaUnit = sampleNum/weightedArea;
01152
01153 double floatSampleNum = 0.0;
01154 for(FaceIterator fi=m.face.begin(); fi != m.face.end(); fi++)
01155 {
01156
01157 floatSampleNum += WeightedArea(*fi,rH) * samplePerAreaUnit;
01158 int faceSampleNum = (int) floatSampleNum;
01159
01160
01161 for(int i=0; i < faceSampleNum; i++)
01162 ps.AddFace(*fi,RandomBarycentric());
01163
01164 floatSampleNum -= (double) faceSampleNum;
01165 }
01166 }
01167
01168
01169
01170
01171
01172 static int SingleFaceSubdivision(int sampleNum, const CoordType & v0, const CoordType & v1, const CoordType & v2, VertexSampler &ps, FacePointer fp, bool randSample)
01173 {
01174
01175 if(sampleNum == 1)
01176 {
01177
01178 CoordType SamplePoint;
01179 if(randSample)
01180 {
01181 CoordType rb=RandomBarycentric();
01182 SamplePoint=v0*rb[0]+v1*rb[1]+v2*rb[2];
01183 }
01184 else SamplePoint=((v0+v1+v2)*(1.0f/3.0f));
01185
01186 ps.AddFace(*fp,SamplePoint);
01187 return 1;
01188 }
01189
01190 int s0 = sampleNum /2;
01191 int s1 = sampleNum-s0;
01192 assert(s0>0);
01193 assert(s1>0);
01194
01195 ScalarType w0 = ScalarType(s1)/ScalarType(sampleNum);
01196 ScalarType w1 = 1.0-w0;
01197
01198 ScalarType maxd01 = SquaredDistance(v0,v1);
01199 ScalarType maxd12 = SquaredDistance(v1,v2);
01200 ScalarType maxd20 = SquaredDistance(v2,v0);
01201 int res;
01202 if(maxd01 > maxd12)
01203 if(maxd01 > maxd20) res = 0;
01204 else res = 2;
01205 else
01206 if(maxd12 > maxd20) res = 1;
01207 else res = 2;
01208
01209 int faceSampleNum=0;
01210
01211 CoordType pp;
01212 switch(res)
01213 {
01214 case 0 : pp = v0*w0 + v1*w1;
01215 faceSampleNum+=SingleFaceSubdivision(s0,v0,pp,v2,ps,fp,randSample);
01216 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
01217 break;
01218 case 1 : pp = v1*w0 + v2*w1;
01219 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
01220 faceSampleNum+=SingleFaceSubdivision(s1,v0,pp,v2,ps,fp,randSample);
01221 break;
01222 case 2 : pp = v0*w0 + v2*w1;
01223 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
01224 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
01225 break;
01226 }
01227 return faceSampleNum;
01228 }
01229
01230
01232 static void FaceSubdivision(MeshType & m, VertexSampler &ps,int sampleNum, bool randSample)
01233 {
01234
01235 ScalarType area = Stat<MeshType>::ComputeMeshArea(m);
01236 ScalarType samplePerAreaUnit = sampleNum/area;
01237 std::vector<FacePointer> faceVec;
01238 FillAndShuffleFacePointerVector(m,faceVec);
01239 vcg::tri::UpdateNormal<MeshType>::PerFaceNormalized(m);
01240 double floatSampleNum = 0.0;
01241 int faceSampleNum;
01242
01243 typename std::vector<FacePointer>::iterator fi;
01244 for(fi=faceVec.begin(); fi!=faceVec.end(); fi++)
01245 {
01246 const CoordType b0(1.0, 0.0, 0.0);
01247 const CoordType b1(0.0, 1.0, 0.0);
01248 const CoordType b2(0.0, 0.0, 1.0);
01249
01250 floatSampleNum += 0.5*DoubleArea(**fi) * samplePerAreaUnit;
01251 faceSampleNum = (int) floatSampleNum;
01252 if(faceSampleNum>0)
01253 faceSampleNum = SingleFaceSubdivision(faceSampleNum,b0,b1,b2,ps,*fi,randSample);
01254 floatSampleNum -= (double) faceSampleNum;
01255 }
01256 }
01257
01258
01259
01260
01261 static int SingleFaceSubdivisionOld(int sampleNum, const CoordType & v0, const CoordType & v1, const CoordType & v2, VertexSampler &ps, FacePointer fp, bool randSample)
01262 {
01263
01264 if(sampleNum == 1)
01265 {
01266
01267 CoordType SamplePoint;
01268 if(randSample)
01269 {
01270 CoordType rb=RandomBarycentric();
01271 SamplePoint=v0*rb[0]+v1*rb[1]+v2*rb[2];
01272 }
01273 else SamplePoint=((v0+v1+v2)*(1.0f/3.0f));
01274
01275 CoordType SampleBary;
01276 InterpolationParameters(*fp,SamplePoint,SampleBary);
01277 ps.AddFace(*fp,SampleBary);
01278 return 1;
01279 }
01280
01281 int s0 = sampleNum /2;
01282 int s1 = sampleNum-s0;
01283 assert(s0>0);
01284 assert(s1>0);
01285
01286 ScalarType w0 = ScalarType(s1)/ScalarType(sampleNum);
01287 ScalarType w1 = 1.0-w0;
01288
01289 ScalarType maxd01 = SquaredDistance(v0,v1);
01290 ScalarType maxd12 = SquaredDistance(v1,v2);
01291 ScalarType maxd20 = SquaredDistance(v2,v0);
01292 int res;
01293 if(maxd01 > maxd12)
01294 if(maxd01 > maxd20) res = 0;
01295 else res = 2;
01296 else
01297 if(maxd12 > maxd20) res = 1;
01298 else res = 2;
01299
01300 int faceSampleNum=0;
01301
01302 CoordType pp;
01303 switch(res)
01304 {
01305 case 0 : pp = v0*w0 + v1*w1;
01306 faceSampleNum+=SingleFaceSubdivision(s0,v0,pp,v2,ps,fp,randSample);
01307 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
01308 break;
01309 case 1 : pp = v1*w0 + v2*w1;
01310 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
01311 faceSampleNum+=SingleFaceSubdivision(s1,v0,pp,v2,ps,fp,randSample);
01312 break;
01313 case 2 : pp = v0*w0 + v2*w1;
01314 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
01315 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
01316 break;
01317 }
01318 return faceSampleNum;
01319 }
01320
01321
01323 static void FaceSubdivisionOld(MeshType & m, VertexSampler &ps,int sampleNum, bool randSample)
01324 {
01325
01326 ScalarType area = Stat<MeshType>::ComputeMeshArea(m);
01327 ScalarType samplePerAreaUnit = sampleNum/area;
01328 std::vector<FacePointer> faceVec;
01329 FillAndShuffleFacePointerVector(m,faceVec);
01330 tri::UpdateNormal<MeshType>::PerFaceNormalized(m);
01331 double floatSampleNum = 0.0;
01332 int faceSampleNum;
01333
01334 typename std::vector<FacePointer>::iterator fi;
01335 for(fi=faceVec.begin(); fi!=faceVec.end(); fi++)
01336 {
01337
01338 floatSampleNum += 0.5*DoubleArea(**fi) * samplePerAreaUnit;
01339 faceSampleNum = (int) floatSampleNum;
01340 if(faceSampleNum>0)
01341 faceSampleNum = SingleFaceSubdivision(faceSampleNum,(**fi).V(0)->cP(), (**fi).V(1)->cP(), (**fi).V(2)->cP(),ps,*fi,randSample);
01342 floatSampleNum -= (double) faceSampleNum;
01343 }
01344 }
01345
01346
01347
01348
01349
01350
01351
01352
01353 static int SingleFaceSimilar(FacePointer fp, VertexSampler &ps, int n_samples_per_edge)
01354 {
01355 int n_samples=0;
01356 int i, j;
01357 float segmentNum=n_samples_per_edge -1 ;
01358 float segmentLen = 1.0/segmentNum;
01359
01360 for(i=1; i < n_samples_per_edge-1; i++)
01361 for(j=1; j < n_samples_per_edge-1-i; j++)
01362 {
01363
01364 CoordType sampleBary(i*segmentLen,j*segmentLen, 1.0 - (i*segmentLen+j*segmentLen) ) ;
01365 n_samples++;
01366 ps.AddFace(*fp,sampleBary);
01367 }
01368 return n_samples;
01369 }
01370 static int SingleFaceSimilarDual(FacePointer fp, VertexSampler &ps, int n_samples_per_edge, bool randomFlag)
01371 {
01372 int n_samples=0;
01373 float i, j;
01374 float segmentNum=n_samples_per_edge -1 ;
01375 float segmentLen = 1.0/segmentNum;
01376
01377 for(i=0; i < n_samples_per_edge-1; i++)
01378 for(j=0; j < n_samples_per_edge-1-i; j++)
01379 {
01380
01381 CoordType V0((i+0)*segmentLen,(j+0)*segmentLen, 1.0 - ((i+0)*segmentLen+(j+0)*segmentLen) ) ;
01382 CoordType V1((i+1)*segmentLen,(j+0)*segmentLen, 1.0 - ((i+1)*segmentLen+(j+0)*segmentLen) ) ;
01383 CoordType V2((i+0)*segmentLen,(j+1)*segmentLen, 1.0 - ((i+0)*segmentLen+(j+1)*segmentLen) ) ;
01384 n_samples++;
01385 if(randomFlag) {
01386 CoordType rb=RandomBarycentric();
01387 ps.AddFace(*fp, V0*rb[0]+V1*rb[1]+V2*rb[2]);
01388 } else ps.AddFace(*fp,(V0+V1+V2)/3.0);
01389
01390 if( j < n_samples_per_edge-i-2 )
01391 {
01392 CoordType V3((i+1)*segmentLen,(j+1)*segmentLen, 1.0 - ((i+1)*segmentLen+(j+1)*segmentLen) ) ;
01393 n_samples++;
01394 if(randomFlag) {
01395 CoordType rb=RandomBarycentric();
01396 ps.AddFace(*fp, V3*rb[0]+V1*rb[1]+V2*rb[2]);
01397 } else ps.AddFace(*fp,(V3+V1+V2)/3.0);
01398 }
01399 }
01400 return n_samples;
01401 }
01402
01403
01404
01405
01406
01407
01408
01409
01410
01411
01412
01413
01414
01415
01416
01417
01418
01419
01420
01421
01422
01423
01424
01425
01426
01427
01428
01429
01430
01431
01432 static void FaceSimilar(MeshType & m, VertexSampler &ps,int sampleNum, bool dualFlag, bool randomFlag)
01433 {
01434 ScalarType area = Stat<MeshType>::ComputeMeshArea(m);
01435 ScalarType samplePerAreaUnit = sampleNum/area;
01436
01437
01438 int n_samples_per_edge;
01439 double n_samples_decimal = 0.0;
01440 FaceIterator fi;
01441
01442 for(fi=m.face.begin(); fi != m.face.end(); fi++)
01443 {
01444
01445 n_samples_decimal += 0.5*DoubleArea(*fi) * samplePerAreaUnit;
01446 int n_samples = (int) n_samples_decimal;
01447 if(n_samples>0)
01448 {
01449
01450 if(dualFlag)
01451 {
01452 n_samples_per_edge = (int)((sqrt(1.0+8.0*(double)n_samples) +5.0)/2.0);
01453 n_samples = SingleFaceSimilar(&*fi,ps, n_samples_per_edge);
01454 } else {
01455 n_samples_per_edge = (int)(sqrt((double)n_samples) +1.0);
01456 n_samples = SingleFaceSimilarDual(&*fi,ps, n_samples_per_edge,randomFlag);
01457 }
01458 }
01459 n_samples_decimal -= (double) n_samples;
01460 }
01461 }
01462
01463
01464
01465
01466
01467
01468
01469
01470
01471
01472
01473 static void SingleFaceRaster(typename MeshType::FaceType &f, VertexSampler &ps,
01474 const Point2<typename MeshType::ScalarType> & v0,
01475 const Point2<typename MeshType::ScalarType> & v1,
01476 const Point2<typename MeshType::ScalarType> & v2,
01477 bool correctSafePointsBaryCoords=true)
01478 {
01479 typedef typename MeshType::ScalarType S;
01480
01481 Box2i bbox;
01482 Box2<S> bboxf;
01483 bboxf.Add(v0);
01484 bboxf.Add(v1);
01485 bboxf.Add(v2);
01486
01487 bbox.min[0] = floor(bboxf.min[0]);
01488 bbox.min[1] = floor(bboxf.min[1]);
01489 bbox.max[0] = ceil(bboxf.max[0]);
01490 bbox.max[1] = ceil(bboxf.max[1]);
01491
01492
01493 Point2<S> d10 = v1 - v0;
01494 Point2<S> d21 = v2 - v1;
01495 Point2<S> d02 = v0 - v2;
01496
01497
01498 S b0 = (bbox.min[0]-v0[0])*d10[1] - (bbox.min[1]-v0[1])*d10[0];
01499 S b1 = (bbox.min[0]-v1[0])*d21[1] - (bbox.min[1]-v1[1])*d21[0];
01500 S b2 = (bbox.min[0]-v2[0])*d02[1] - (bbox.min[1]-v2[1])*d02[0];
01501
01502 S db0 = d10[1];
01503 S db1 = d21[1];
01504 S db2 = d02[1];
01505
01506 S dn0 = -d10[0];
01507 S dn1 = -d21[0];
01508 S dn2 = -d02[0];
01509
01510
01511 bool flipped = !(d02 * vcg::Point2<S>(-d10[1], d10[0]) >= 0);
01512
01513
01514 Segment2<S> borderEdges[3];
01515 S edgeLength[3];
01516 unsigned char edgeMask = 0;
01517
01518 if (f.IsB(0)) {
01519 borderEdges[0] = Segment2<S>(v0, v1);
01520 edgeLength[0] = borderEdges[0].Length();
01521 edgeMask |= 1;
01522 }
01523 if (f.IsB(1)) {
01524 borderEdges[1] = Segment2<S>(v1, v2);
01525 edgeLength[1] = borderEdges[1].Length();
01526 edgeMask |= 2;
01527 }
01528 if (f.IsB(2)) {
01529 borderEdges[2] = Segment2<S>(v2, v0);
01530 edgeLength[2] = borderEdges[2].Length();
01531 edgeMask |= 4;
01532 }
01533
01534
01535 double de = v0[0]*v1[1]-v0[0]*v2[1]-v1[0]*v0[1]+v1[0]*v2[1]-v2[0]*v1[1]+v2[0]*v0[1];
01536
01537 for(int x=bbox.min[0]-1;x<=bbox.max[0]+1;++x)
01538 {
01539 bool in = false;
01540 S n[3] = { b0-db0-dn0, b1-db1-dn1, b2-db2-dn2};
01541 for(int y=bbox.min[1]-1;y<=bbox.max[1]+1;++y)
01542 {
01543 if( ((n[0]>=0 && n[1]>=0 && n[2]>=0) || (n[0]<=0 && n[1]<=0 && n[2]<=0)) && (de != 0))
01544 {
01545 typename MeshType::CoordType baryCoord;
01546 baryCoord[0] = double(-y*v1[0]+v2[0]*y+v1[1]*x-v2[0]*v1[1]+v1[0]*v2[1]-x*v2[1])/de;
01547 baryCoord[1] = -double( x*v0[1]-x*v2[1]-v0[0]*y+v0[0]*v2[1]-v2[0]*v0[1]+v2[0]*y)/de;
01548 baryCoord[2] = 1-baryCoord[0]-baryCoord[1];
01549
01550 ps.AddTextureSample(f, baryCoord, Point2i(x,y), 0);
01551 in = true;
01552 } else {
01553
01554 Point2<S> px(x, y);
01555 Point2<S> closePoint;
01556 int closeEdge = -1;
01557 S minDst = FLT_MAX;
01558
01559
01560 for (int i=0; i<3; ++i)
01561 {
01562 if (edgeMask & (1 << i))
01563 {
01564 Point2<S> close;
01565 S dst;
01566 if ( ((!flipped) && (n[i]<0)) ||
01567 ( flipped && (n[i]>0)) )
01568 {
01569 dst = ((close = ClosestPoint(borderEdges[i], px)) - px).Norm();
01570 if(dst < minDst &&
01571 close.X() > px.X()-1 && close.X() < px.X()+1 &&
01572 close.Y() > px.Y()-1 && close.Y() < px.Y()+1)
01573 {
01574 minDst = dst;
01575 closePoint = close;
01576 closeEdge = i;
01577 }
01578 }
01579 }
01580 }
01581
01582 if (closeEdge >= 0)
01583 {
01584 typename MeshType::CoordType baryCoord;
01585 if (correctSafePointsBaryCoords)
01586 {
01587
01588 baryCoord[closeEdge] = (closePoint - borderEdges[closeEdge].P1()).Norm()/edgeLength[closeEdge];
01589 baryCoord[(closeEdge+1)%3] = 1 - baryCoord[closeEdge];
01590 baryCoord[(closeEdge+2)%3] = 0;
01591 } else {
01592
01593 baryCoord[0] = double(-y*v1[0]+v2[0]*y+v1[1]*x-v2[0]*v1[1]+v1[0]*v2[1]-x*v2[1])/de;
01594 baryCoord[1] = -double( x*v0[1]-x*v2[1]-v0[0]*y+v0[0]*v2[1]-v2[0]*v0[1]+v2[0]*y)/de;
01595 baryCoord[2] = 1-baryCoord[0]-baryCoord[1];
01596 }
01597 ps.AddTextureSample(f, baryCoord, Point2i(x,y), minDst);
01598 in = true;
01599 }
01600 }
01601 n[0] += dn0;
01602 n[1] += dn1;
01603 n[2] += dn2;
01604 }
01605 b0 += db0;
01606 b1 += db1;
01607 b2 += db2;
01608 }
01609 }
01610
01611
01612 static bool checkPoissonDisk(SampleSHT & sht, const Point3<ScalarType> & p, ScalarType radius)
01613 {
01614
01615 std::vector<VertexType*> closests;
01616 typedef EmptyTMark<MeshType> MarkerVert;
01617 static MarkerVert mv;
01618
01619 Box3f bb(p-Point3f(radius,radius,radius),p+Point3f(radius,radius,radius));
01620 GridGetInBox(sht, mv, bb, closests);
01621
01622 ScalarType r2 = radius*radius;
01623 for(int i=0; i<closests.size(); ++i)
01624 if(SquaredDistance(p,closests[i]->cP()) < r2)
01625 return false;
01626
01627 return true;
01628 }
01629
01630 struct PoissonDiskParam
01631 {
01632 PoissonDiskParam()
01633 {
01634 adaptiveRadiusFlag = false;
01635 bestSampleChoiceFlag = true;
01636 bestSamplePoolSize = 10;
01637 radiusVariance =1;
01638 MAXLEVELS = 5;
01639 invertQuality = false;
01640 preGenFlag = false;
01641 preGenMesh = NULL;
01642 geodesicDistanceFlag = false;
01643 randomSeed = 0;
01644 }
01645
01646 struct Stat
01647 {
01648 int montecarloTime;
01649 int gridTime;
01650 int pruneTime;
01651 int totalTime;
01652 Point3i gridSize;
01653 int gridCellNum;
01654 size_t sampleNum;
01655 int montecarloSampleNum;
01656 };
01657
01658 bool geodesicDistanceFlag;
01659 bool bestSampleChoiceFlag;
01660 int bestSamplePoolSize;
01661 bool adaptiveRadiusFlag;
01662 float radiusVariance;
01663 bool invertQuality;
01664 bool preGenFlag;
01665
01666 MeshType *preGenMesh;
01667
01668 int MAXLEVELS;
01669 int randomSeed;
01670
01671 Stat pds;
01672 };
01673
01674
01675
01676
01677 static VertexPointer getSampleFromCell(Point3i &cell, MontecarloSHT & samplepool)
01678 {
01679 MontecarloSHTIterator cellBegin, cellEnd;
01680 samplepool.Grid(cell, cellBegin, cellEnd);
01681 return *cellBegin;
01682 }
01683
01684
01685
01686
01687 static VertexPointer getBestPrecomputedMontecarloSample(Point3i &cell, MontecarloSHT & samplepool, ScalarType diskRadius, const PoissonDiskParam &pp)
01688 {
01689 MontecarloSHTIterator cellBegin,cellEnd;
01690 samplepool.Grid(cell, cellBegin, cellEnd);
01691 VertexPointer bestSample=0;
01692 int minRemoveCnt = std::numeric_limits<int>::max();
01693 std::vector<typename MontecarloSHT::HashIterator> inSphVec;
01694 int i=0;
01695 for(MontecarloSHTIterator ci=cellBegin; ci!=cellEnd && i<pp.bestSamplePoolSize; ++ci,i++)
01696 {
01697 VertexPointer sp = *ci;
01698 if(pp.adaptiveRadiusFlag) diskRadius = sp->Q();
01699 int curRemoveCnt = samplepool.CountInSphere(sp->cP(),diskRadius,inSphVec);
01700 if(curRemoveCnt < minRemoveCnt)
01701 {
01702 bestSample = sp;
01703 minRemoveCnt = curRemoveCnt;
01704 }
01705 }
01706 return bestSample;
01707 }
01708
01711 static ScalarType ComputePoissonDiskRadius(MeshType &origMesh, int sampleNum)
01712 {
01713 ScalarType meshArea = Stat<MeshType>::ComputeMeshArea(origMesh);
01714
01715
01716 if(meshArea ==0)
01717 {
01718 meshArea = (origMesh.bbox.DimX()*origMesh.bbox.DimY() +
01719 origMesh.bbox.DimX()*origMesh.bbox.DimZ() +
01720 origMesh.bbox.DimY()*origMesh.bbox.DimZ());
01721 }
01722 ScalarType diskRadius = sqrt(meshArea / (0.7 * M_PI * sampleNum));
01723 return diskRadius;
01724 }
01725
01726 static int ComputePoissonSampleNum(MeshType &origMesh, ScalarType diskRadius)
01727 {
01728 ScalarType meshArea = Stat<MeshType>::ComputeMeshArea(origMesh);
01729 int sampleNum = meshArea / (diskRadius*diskRadius *M_PI *0.7) ;
01730 return sampleNum;
01731 }
01732
01739
01740 static void InitRadiusHandleFromQuality(MeshType &sampleMesh, PerVertexFloatAttribute &rH, ScalarType diskRadius, ScalarType radiusVariance, bool invert)
01741 {
01742 std::pair<float,float> minmax = tri::Stat<MeshType>::ComputePerVertexQualityMinMax( sampleMesh);
01743 float minRad = diskRadius ;
01744 float maxRad = diskRadius * radiusVariance;
01745 float deltaQ = minmax.second-minmax.first;
01746 float deltaRad = maxRad-minRad;
01747 for (VertexIterator vi = sampleMesh.vert.begin(); vi != sampleMesh.vert.end(); vi++)
01748 {
01749 rH[*vi] = minRad + deltaRad*((invert ? minmax.second - (*vi).Q() : (*vi).Q() - minmax.first )/deltaQ);
01750 }
01751 }
01752
01753
01754
01755
01756
01757
01758 static void InitSpatialHashTable(MeshType &montecarloMesh, MontecarloSHT &montecarloSHT, ScalarType diskRadius,
01759 struct PoissonDiskParam pp=PoissonDiskParam())
01760 {
01761 ScalarType cellsize = 2.0f* diskRadius / sqrt(3.0);
01762 float occupancyRatio=0;
01763 do
01764 {
01765
01766 BoxType bb=montecarloMesh.bbox;
01767 assert(!bb.IsNull());
01768 bb.Offset(cellsize);
01769
01770 int sizeX = std::max(1,int(bb.DimX() / cellsize));
01771 int sizeY = std::max(1,int(bb.DimY() / cellsize));
01772 int sizeZ = std::max(1,int(bb.DimZ() / cellsize));
01773 Point3i gridsize(sizeX, sizeY, sizeZ);
01774
01775 montecarloSHT.InitEmpty(bb, gridsize);
01776
01777 for (VertexIterator vi = montecarloMesh.vert.begin(); vi != montecarloMesh.vert.end(); vi++)
01778 if(!(*vi).IsD())
01779 {
01780 montecarloSHT.Add(&(*vi));
01781 }
01782
01783 montecarloSHT.UpdateAllocatedCells();
01784 pp.pds.gridSize = gridsize;
01785 pp.pds.gridCellNum = (int)montecarloSHT.AllocatedCells.size();
01786 cellsize/=2.0f;
01787 occupancyRatio = float(montecarloMesh.vn) / float(montecarloSHT.AllocatedCells.size());
01788
01789 }
01790 while( occupancyRatio> 100);
01791 }
01792
01793 static void PoissonDiskPruningByNumber(VertexSampler &ps, MeshType &m,
01794 size_t sampleNum, ScalarType &diskRadius,
01795 PoissonDiskParam &pp,
01796 float tolerance=0.04,
01797 int maxIter=20)
01798
01799 {
01800 size_t sampleNumMin = int(float(sampleNum)*(1.0f-tolerance));
01801 size_t sampleNumMax = int(float(sampleNum)*(1.0f+tolerance));
01802 float RangeMinRad = m.bbox.Diag()/50.0;
01803 float RangeMaxRad = m.bbox.Diag()/50.0;
01804 size_t RangeMinRadNum;
01805 size_t RangeMaxRadNum;
01806
01807
01808 do {
01809 ps.reset();
01810 RangeMinRad/=2.0f;
01811 PoissonDiskPruning(ps, m ,RangeMinRad,pp);
01812 RangeMinRadNum = pp.pds.sampleNum;
01813
01814 } while(RangeMinRadNum < sampleNum);
01815
01816 do {
01817 ps.reset();
01818 RangeMaxRad*=2.0f;
01819 PoissonDiskPruning(ps, m ,RangeMaxRad,pp);
01820 RangeMaxRadNum = pp.pds.sampleNum;
01821
01822 } while(RangeMaxRadNum > sampleNum);
01823
01824
01825 float curRadius=RangeMaxRad;
01826 int iterCnt=0;
01827 while(iterCnt<maxIter &&
01828 (pp.pds.sampleNum < sampleNumMin || pp.pds.sampleNum > sampleNumMax) )
01829 {
01830 iterCnt++;
01831 ps.reset();
01832 curRadius=(RangeMaxRad+RangeMinRad)/2.0f;
01833 PoissonDiskPruning(ps, m ,curRadius,pp);
01834
01835 if(pp.pds.sampleNum > sampleNum){
01836 RangeMinRad = curRadius;
01837 RangeMinRadNum = pp.pds.sampleNum;
01838 }
01839 if(pp.pds.sampleNum < sampleNum){
01840 RangeMaxRad = curRadius;
01841 RangeMaxRadNum = pp.pds.sampleNum;
01842 }
01843 }
01844 diskRadius = curRadius;
01845 }
01846
01847
01852 static void PoissonDiskPruning(VertexSampler &ps, MeshType &montecarloMesh,
01853 ScalarType diskRadius, PoissonDiskParam &pp)
01854 {
01855 tri::RequireCompactness(montecarloMesh);
01856 if(pp.randomSeed) SamplingRandomGenerator().initialize(pp.randomSeed);
01857 if(pp.adaptiveRadiusFlag)
01858 tri::RequirePerVertexQuality(montecarloMesh);
01859 int t0 = clock();
01860
01861 MontecarloSHT montecarloSHT;
01862 InitSpatialHashTable(montecarloMesh,montecarloSHT,diskRadius,pp);
01863
01864
01865
01866 PerVertexFloatAttribute rH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<float> (montecarloMesh,"radius");
01867 if(pp.adaptiveRadiusFlag)
01868 InitRadiusHandleFromQuality(montecarloMesh, rH, diskRadius, pp.radiusVariance, pp.invertQuality);
01869
01870 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
01871 std::random_shuffle(montecarloSHT.AllocatedCells.begin(),montecarloSHT.AllocatedCells.end(), p_myrandom);
01872 int t1 = clock();
01873 pp.pds.montecarloSampleNum = montecarloMesh.vn;
01874 pp.pds.sampleNum =0;
01875 int removedCnt=0;
01876
01877 if(pp.preGenFlag)
01878 {
01879 if(pp.preGenMesh==0)
01880 {
01881 typename MeshType::template PerVertexAttributeHandle<bool> fixed;
01882 fixed = tri::Allocator<MeshType>:: template GetPerVertexAttribute<bool> (montecarloMesh,"fixed");
01883 for(VertexIterator vi=montecarloMesh.vert.begin();vi!=montecarloMesh.vert.end();++vi)
01884 if(fixed[*vi]) {
01885 pp.pds.sampleNum++;
01886 ps.AddVert(*vi);
01887 removedCnt += montecarloSHT.RemoveInSphere(vi->cP(),diskRadius);
01888 }
01889 }
01890 else
01891 {
01892 for(VertexIterator vi =pp.preGenMesh->vert.begin(); vi!=pp.preGenMesh->vert.end();++vi)
01893 {
01894 ps.AddVert(*vi);
01895 pp.pds.sampleNum++;
01896 removedCnt += montecarloSHT.RemoveInSphere(vi->cP(),diskRadius);
01897 }
01898 }
01899 montecarloSHT.UpdateAllocatedCells();
01900 }
01901 vertex::ApproximateGeodesicDistanceFunctor<VertexType> GDF;
01902 while(!montecarloSHT.AllocatedCells.empty())
01903 {
01904 removedCnt=0;
01905 for (size_t i = 0; i < montecarloSHT.AllocatedCells.size(); i++)
01906 {
01907 if( montecarloSHT.EmptyCell(montecarloSHT.AllocatedCells[i]) ) continue;
01908 ScalarType currentRadius =diskRadius;
01909 VertexPointer sp;
01910 if(pp.bestSampleChoiceFlag)
01911 sp = getBestPrecomputedMontecarloSample(montecarloSHT.AllocatedCells[i], montecarloSHT, diskRadius, pp);
01912 else
01913 sp = getSampleFromCell(montecarloSHT.AllocatedCells[i], montecarloSHT);
01914
01915 if(pp.adaptiveRadiusFlag)
01916 currentRadius = rH[sp];
01917
01918 ps.AddVert(*sp);
01919 pp.pds.sampleNum++;
01920 if(pp.geodesicDistanceFlag) removedCnt += montecarloSHT.RemoveInSphereNormal(sp->cP(),sp->cN(),GDF,currentRadius);
01921 else removedCnt += montecarloSHT.RemoveInSphere(sp->cP(),currentRadius);
01922 }
01923 montecarloSHT.UpdateAllocatedCells();
01924 }
01925 int t2 = clock();
01926 pp.pds.gridTime = t1-t0;
01927 pp.pds.pruneTime = t2-t1;
01928 }
01929
01940 static void HierarchicalPoissonDisk(MeshType &origMesh, VertexSampler &ps, MeshType &montecarloMesh, ScalarType diskRadius, const struct PoissonDiskParam pp=PoissonDiskParam())
01941 {
01942
01943
01944 MontecarloSHT montecarloSHTVec[5];
01945
01946
01947
01948
01949
01950
01951 ScalarType cellsize = 2.0f* diskRadius / sqrt(3.0);
01952
01953
01954 BoxType bb=origMesh.bbox;
01955 bb.Offset(cellsize);
01956
01957 int sizeX = std::max(1.0f,bb.DimX() / cellsize);
01958 int sizeY = std::max(1.0f,bb.DimY() / cellsize);
01959 int sizeZ = std::max(1.0f,bb.DimZ() / cellsize);
01960 Point3i gridsize(sizeX, sizeY, sizeZ);
01961
01962
01963 SampleSHT checkSHT;
01964 checkSHT.InitEmpty(bb, gridsize);
01965
01966
01967
01968
01969
01970
01971
01972
01973
01974
01975
01976
01977 int level = 0;
01978
01979
01980 montecarloSHTVec[0].InitEmpty(bb, gridsize);
01981
01982 for (VertexIterator vi = montecarloMesh.vert.begin(); vi != montecarloMesh.vert.end(); vi++)
01983 montecarloSHTVec[0].Add(&(*vi));
01984 montecarloSHTVec[0].UpdateAllocatedCells();
01985
01986
01987 PerVertexFloatAttribute rH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<float> (montecarloMesh,"radius");
01988 if(pp.adaptiveRadiusFlag)
01989 InitRadiusHandleFromQuality(montecarloMesh, rH, diskRadius, pp.radiusVariance, pp.invertQuality);
01990
01991 do
01992 {
01993 MontecarloSHT &montecarloSHT = montecarloSHTVec[level];
01994
01995 if(level>0)
01996 {
01997 montecarloSHT.InitEmpty(bb, gridsize);
01998
01999 for (typename MontecarloSHT::HashIterator hi = montecarloSHTVec[level-1].hash_table.begin(); hi != montecarloSHTVec[level-1].hash_table.end(); hi++)
02000 montecarloSHT.Add((*hi).second);
02001 montecarloSHT.UpdateAllocatedCells();
02002 }
02003
02004 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
02005 std::random_shuffle(montecarloSHT.AllocatedCells.begin(),montecarloSHT.AllocatedCells.end(), p_myrandom);
02006
02007
02009 int removedCnt=montecarloSHT.hash_table.size();
02010 int addedCnt=checkSHT.hash_table.size();
02011 for (int i = 0; i < montecarloSHT.AllocatedCells.size(); i++)
02012 {
02013 for(int j=0;j<4;j++)
02014 {
02015 if( montecarloSHT.EmptyCell(montecarloSHT.AllocatedCells[i]) ) continue;
02016
02017
02018 typename MontecarloSHT::HashIterator hi = montecarloSHT.hash_table.find(montecarloSHT.AllocatedCells[i]);
02019
02020 if(hi==montecarloSHT.hash_table.end()) {break;}
02021 VertexPointer sp = (*hi).second;
02022
02023 ScalarType sampleRadius = diskRadius;
02024 if(pp.adaptiveRadiusFlag) sampleRadius = rH[sp];
02025 if (checkPoissonDisk(checkSHT, sp->cP(), sampleRadius))
02026 {
02027 ps.AddVert(*sp);
02028 montecarloSHT.RemoveCell(sp);
02029 checkSHT.Add(sp);
02030 break;
02031 }
02032 else
02033 montecarloSHT.RemovePunctual(sp);
02034 }
02035 }
02036 addedCnt = checkSHT.hash_table.size()-addedCnt;
02037 removedCnt = removedCnt-montecarloSHT.hash_table.size();
02038
02039
02040
02041 gridsize *= 2;
02042
02043
02044 level++;
02045 } while(level < 5);
02046 }
02047
02048
02049
02050
02051
02052
02053
02054
02055
02056
02057
02058
02059
02060
02061 static void Texture(MeshType & m, VertexSampler &ps, int textureWidth, int textureHeight, bool correctSafePointsBaryCoords=true)
02062 {
02063 typedef Point2<ScalarType> Point2x;
02064 printf("Similar Triangles face sampling\n");
02065 for(FaceIterator fi=m.face.begin(); fi != m.face.end(); fi++)
02066 if (!fi->IsD())
02067 {
02068 Point2x ti[3];
02069 for(int i=0;i<3;++i)
02070 ti[i]=Point2x((*fi).WT(i).U() * textureWidth - 0.5, (*fi).WT(i).V() * textureHeight - 0.5);
02071
02072
02073 SingleFaceRaster(*fi, ps, ti[0],ti[1],ti[2], correctSafePointsBaryCoords);
02074 }
02075 }
02076
02077 typedef GridStaticPtr<FaceType, ScalarType > TriMeshGrid;
02078
02079 class RRParam
02080 {
02081 public:
02082 float offset;
02083 float minDiag;
02084 tri::FaceTmark<MeshType> markerFunctor;
02085 TriMeshGrid gM;
02086 };
02087
02088 static void RegularRecursiveOffset(MeshType & m, std::vector<CoordType> &pvec, ScalarType offset, float minDiag)
02089 {
02090 Box3<ScalarType> bb=m.bbox;
02091 bb.Offset(offset*2.0);
02092
02093 RRParam rrp;
02094
02095 rrp.markerFunctor.SetMesh(&m);
02096
02097 rrp.gM.Set(m.face.begin(),m.face.end(),bb);
02098
02099
02100 rrp.offset=offset;
02101 rrp.minDiag=minDiag;
02102 SubdivideAndSample(m, pvec, bb, rrp, bb.Diag());
02103 }
02104
02105 static void SubdivideAndSample(MeshType & m, std::vector<CoordType> &pvec, const Box3<ScalarType> bb, RRParam &rrp, float curDiag)
02106 {
02107 CoordType startPt = bb.Center();
02108
02109 ScalarType dist;
02110
02111 FaceType *nearestF=0;
02112 ScalarType dist_upper_bound = curDiag+rrp.offset;
02113 CoordType closestPt;
02114 vcg::face::PointDistanceBaseFunctor<ScalarType> PDistFunct;
02115 dist=dist_upper_bound;
02116 nearestF = rrp.gM.GetClosest(PDistFunct,rrp.markerFunctor,startPt,dist_upper_bound,dist,closestPt);
02117 curDiag /=2;
02118 if(dist < dist_upper_bound)
02119 {
02120 if(curDiag/3 < rrp.minDiag)
02121 {
02122 if(rrp.offset==0)
02123 pvec.push_back(closestPt);
02124 else
02125 {
02126 if(dist>rrp.offset)
02127 {
02128 CoordType delta = startPt-closestPt;
02129 pvec.push_back(closestPt+delta*(rrp.offset/dist));
02130 }
02131 }
02132 }
02133 if(curDiag < rrp.minDiag) return;
02134 CoordType hs = (bb.max-bb.min)/2;
02135 for(int i=0;i<2;i++)
02136 for(int j=0;j<2;j++)
02137 for(int k=0;k<2;k++)
02138 SubdivideAndSample(m, pvec,
02139 BoxType(CoordType( bb.min[0]+i*hs[0], bb.min[1]+j*hs[1], bb.min[2]+k*hs[2]),
02140 CoordType(startPt[0]+i*hs[0], startPt[1]+j*hs[1], startPt[2]+k*hs[2]) ),
02141 rrp,curDiag
02142 );
02143
02144 }
02145 }
02146 };
02147
02148 template <class MeshType>
02149 typename MeshType::ScalarType ComputePoissonDiskRadius(MeshType &origMesh, int sampleNum)
02150 {
02151 typedef typename MeshType::ScalarType ScalarType;
02152 ScalarType meshArea = Stat<MeshType>::ComputeMeshArea(origMesh);
02153
02154
02155 if(meshArea ==0)
02156 {
02157 meshArea = (origMesh.bbox.DimX()*origMesh.bbox.DimY() +
02158 origMesh.bbox.DimX()*origMesh.bbox.DimZ() +
02159 origMesh.bbox.DimY()*origMesh.bbox.DimZ());
02160 }
02161 ScalarType diskRadius = sqrt(meshArea / (0.7 * M_PI * sampleNum));
02162 return diskRadius;
02163 }
02164
02165
02166
02167 template <class MeshType>
02168 void MontecarloSampling(MeshType &m,
02169 MeshType &mm,
02170 int sampleNum)
02171 {
02172 typedef tri::MeshSampler<MeshType> BaseSampler;
02173 MeshSampler<MeshType> mcSampler(&mm);
02174 tri::SurfaceSampling<MeshType,BaseSampler>::Montecarlo(m, mcSampler, sampleNum);
02175 }
02176
02177
02178 template <class MeshType>
02179 void MontecarloSampling(MeshType &m,
02180 std::vector<Point3f> &montercarloSamples,
02181 int sampleNum)
02182 {
02183 typedef tri::TrivialSampler<MeshType> BaseSampler;
02184 BaseSampler mcSampler(montercarloSamples);
02185 tri::SurfaceSampling<MeshType,BaseSampler>::Montecarlo(m, mcSampler, sampleNum);
02186 }
02187
02188
02189
02190 template <class MeshType>
02191 void PoissonSampling(MeshType &m,
02192 std::vector<typename MeshType::CoordType> &poissonSamples,
02193 int sampleNum,
02194 typename MeshType::ScalarType &radius,
02195 typename MeshType::ScalarType radiusVariance=1,
02196 typename MeshType::ScalarType PruningByNumberTolerance=0.04f,
02197 unsigned int randSeed=0)
02198
02199 {
02200 typedef tri::TrivialSampler<MeshType> BaseSampler;
02201 typedef tri::MeshSampler<MeshType> MontecarloSampler;
02202
02203 typename tri::SurfaceSampling<MeshType, BaseSampler>::PoissonDiskParam pp;
02204 int t0=clock();
02205
02206
02207 if(radius>0 && sampleNum==0) sampleNum = tri::SurfaceSampling<MeshType,BaseSampler>::ComputePoissonSampleNum(m,radius);
02208
02209 pp.pds.sampleNum = sampleNum;
02210 pp.randomSeed = randSeed;
02211 poissonSamples.clear();
02212
02213 MeshType MontecarloMesh;
02214
02215
02216 MontecarloSampler mcSampler(MontecarloMesh);
02217 BaseSampler pdSampler(poissonSamples);
02218
02219 if(randSeed) tri::SurfaceSampling<MeshType,MontecarloSampler>::SamplingRandomGenerator().initialize(randSeed);
02220 tri::SurfaceSampling<MeshType,MontecarloSampler>::Montecarlo(m, mcSampler, std::max(10000,sampleNum*40));
02221 tri::UpdateBounding<MeshType>::Box(MontecarloMesh);
02222
02223 int t1=clock();
02224 pp.pds.montecarloTime = t1-t0;
02225
02226 if(radiusVariance !=1)
02227 {
02228 pp.adaptiveRadiusFlag=true;
02229 pp.radiusVariance=radiusVariance;
02230 }
02231 if(sampleNum==0) tri::SurfaceSampling<MeshType,BaseSampler>::PoissonDiskPruning(pdSampler, MontecarloMesh, radius,pp);
02232 else tri::SurfaceSampling<MeshType,BaseSampler>::PoissonDiskPruningByNumber(pdSampler, MontecarloMesh, sampleNum, radius,pp,PruningByNumberTolerance);
02233 int t2=clock();
02234 pp.pds.totalTime = t2-t0;
02235 }
02236
02240
02241 template <class MeshType>
02242 void PoissonPruning(MeshType &m,
02243 std::vector<typename MeshType::VertexPointer> &poissonSamples,
02244 float radius, unsigned int randSeed=0)
02245 {
02246 typedef tri::TrivialPointerSampler<MeshType> BaseSampler;
02247 typename tri::SurfaceSampling<MeshType, BaseSampler>::PoissonDiskParam pp;
02248 pp.randomSeed = randSeed;
02249
02250 tri::UpdateBounding<MeshType>::Box(m);
02251 BaseSampler pdSampler;
02252 tri::SurfaceSampling<MeshType,BaseSampler>::PoissonDiskPruning(pdSampler, m, radius,pp);
02253 std::swap(pdSampler.sampleVec,poissonSamples);
02254 }
02255
02256
02261
02262 template <class MeshType>
02263 void PoissonPruning(MeshType &m,
02264 std::vector<Point3f> &poissonSamples,
02265 float radius, unsigned int randSeed=0)
02266 {
02267 std::vector<typename MeshType::VertexPointer> poissonSamplesVP;
02268 PoissonPruning(m,poissonSamplesVP,radius,randSeed);
02269 poissonSamples.resize(poissonSamplesVP.size());
02270 for(size_t i=0;i<poissonSamplesVP.size();++i)
02271 poissonSamples[i]=poissonSamplesVP[i]->P();
02272 }
02273
02274
02275
02281 template <class MeshType>
02282 void PoissonPruningExact(MeshType &m,
02283 std::vector<typename MeshType::VertexPointer> &poissonSamples,
02284 typename MeshType::ScalarType & radius,
02285 int sampleNum,
02286 float tolerance=0.04,
02287 int maxIter=20,
02288 unsigned int randSeed=0)
02289 {
02290 size_t sampleNumMin = int(float(sampleNum)*(1.0f-tolerance));
02291 size_t sampleNumMax = int(float(sampleNum)*(1.0f+tolerance));
02292 float RangeMinRad = m.bbox.Diag()/10.0f;
02293 float RangeMaxRad = m.bbox.Diag()/10.0f;
02294 size_t RangeMinSampleNum;
02295 size_t RangeMaxSampleNum;
02296 std::vector<typename MeshType::VertexPointer> poissonSamplesTmp;
02297
02298 do
02299 {
02300 RangeMinRad/=2.0f;
02301 PoissonPruning(m,poissonSamplesTmp,RangeMinRad,randSeed);
02302 RangeMinSampleNum = poissonSamplesTmp.size();
02303 } while(RangeMinSampleNum < sampleNumMin);
02304
02305 do
02306 {
02307 RangeMaxRad*=2.0f;
02308 PoissonPruning(m,poissonSamplesTmp,RangeMaxRad,randSeed);
02309 RangeMaxSampleNum = poissonSamplesTmp.size();
02310 } while(RangeMaxSampleNum > sampleNumMax);
02311
02312 float curRadius;
02313 int iterCnt=0;
02314 while(iterCnt<maxIter &&
02315 (poissonSamplesTmp.size() < sampleNumMin || poissonSamplesTmp.size() > sampleNumMax) )
02316 {
02317 curRadius=(RangeMaxRad+RangeMinRad)/2.0f;
02318 PoissonPruning(m,poissonSamplesTmp,curRadius,randSeed);
02319
02320 if(poissonSamplesTmp.size() > size_t(sampleNum))
02321 RangeMinRad = curRadius;
02322 if(poissonSamplesTmp.size() < size_t(sampleNum))
02323 RangeMaxRad = curRadius;
02324 }
02325
02326 swap(poissonSamples,poissonSamplesTmp);
02327 radius = curRadius;
02328 }
02329 }
02330 }
02331
02332 #endif
02333