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 #include <vcg/math/random_generator.h>
00039 #include <vcg/complex/trimesh/closest.h>
00040 #include <vcg/space/index/spatial_hashing.h>
00041 #include <vcg/complex/trimesh/stat.h>
00042 #include <vcg/complex/trimesh/update/topology.h>
00043 #include <vcg/complex/trimesh/update/normal.h>
00044 #include <vcg/complex/trimesh/update/flag.h>
00045 #include <vcg/space/box2.h>
00046 #include <vcg/space/segment2.h>
00047 namespace vcg
00048 {
00049 namespace tri
00050 {
00051
00055
00056
00057
00058
00059
00060
00061
00062
00063 template <class MeshType>
00064 class TrivialSampler
00065 {
00066 public:
00067 typedef typename MeshType::CoordType CoordType;
00068 typedef typename MeshType::VertexType VertexType;
00069 typedef typename MeshType::FaceType FaceType;
00070
00071 TrivialSampler()
00072 {
00073 sampleVec = new std::vector<CoordType>();
00074 vectorOwner=true;
00075 };
00076
00077 TrivialSampler(std::vector<CoordType> &Vec)
00078 {
00079 sampleVec = &Vec;
00080 sampleVec->clear();
00081 vectorOwner=false;
00082 };
00083
00084 ~TrivialSampler()
00085 {
00086 if(vectorOwner) delete sampleVec;
00087 }
00088
00089 private:
00090 std::vector<CoordType> *sampleVec;
00091 bool vectorOwner;
00092 public:
00093
00094 void AddVert(const VertexType &p)
00095 {
00096 sampleVec->push_back(p.cP());
00097 }
00098 void AddFace(const FaceType &f, const CoordType &p)
00099 {
00100 sampleVec->push_back(f.P(0)*p[0] + f.P(1)*p[1] +f.P(2)*p[2] );
00101 }
00102
00103 void AddTextureSample(const FaceType &, const CoordType &, const Point2i &, float )
00104 {
00105
00106
00107
00108 }
00109 };
00110
00111 template <class MetroMesh, class VertexSampler>
00112 class SurfaceSampling
00113 {
00114 typedef typename MetroMesh::CoordType CoordType;
00115 typedef typename MetroMesh::ScalarType ScalarType;
00116 typedef typename MetroMesh::VertexType VertexType;
00117 typedef typename MetroMesh::VertexPointer VertexPointer;
00118 typedef typename MetroMesh::VertexIterator VertexIterator;
00119 typedef typename MetroMesh::FacePointer FacePointer;
00120 typedef typename MetroMesh::FaceIterator FaceIterator;
00121 typedef typename MetroMesh::FaceType FaceType;
00122 typedef typename MetroMesh::FaceContainer FaceContainer;
00123
00124 typedef typename vcg::SpatialHashTable<FaceType, ScalarType> MeshSHT;
00125 typedef typename vcg::SpatialHashTable<FaceType, ScalarType>::CellIterator MeshSHTIterator;
00126 typedef typename vcg::SpatialHashTable<VertexType, ScalarType> MontecarloSHT;
00127 typedef typename vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator MontecarloSHTIterator;
00128 typedef typename vcg::SpatialHashTable<VertexType, ScalarType> SampleSHT;
00129 typedef typename vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator SampleSHTIterator;
00130
00131 public:
00132
00133 static math::MarsenneTwisterRNG &SamplingRandomGenerator()
00134 {
00135 static math::MarsenneTwisterRNG rnd;
00136 return rnd;
00137 }
00138
00139
00140 static unsigned int RandomInt(unsigned int i)
00141 {
00142 return (SamplingRandomGenerator().generate(0) % i);
00143 }
00144
00145
00146 static double RandomDouble01()
00147 {
00148 return SamplingRandomGenerator().generate01();
00149 }
00150
00151
00152 static double RandomDouble01closed()
00153 {
00154 return SamplingRandomGenerator().generate01closed();
00155 }
00156
00157 static void AllVertex(MetroMesh & m, VertexSampler &ps)
00158 {
00159 VertexIterator vi;
00160 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00161 {
00162 if(!(*vi).IsD())
00163 {
00164 ps.AddVert(*vi);
00165 }
00166 }
00167 }
00168
00176
00177 static void VertexWeighted(MetroMesh & m, VertexSampler &ps, int sampleNum)
00178 {
00179 ScalarType qSum = 0;
00180 VertexIterator vi;
00181 for(vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00182 if(!(*vi).IsD())
00183 qSum += (*vi).Q();
00184
00185 ScalarType samplePerUnit = sampleNum/qSum;
00186 ScalarType floatSampleNum =0;
00187 std::vector<VertexPointer> vertVec;
00188 FillAndShuffleVertexPointerVector(m,vertVec);
00189
00190 std::vector<bool> vertUsed(m.vn,false);
00191
00192 int i=0; int cnt=0;
00193 while(cnt < sampleNum)
00194 {
00195 if(vertUsed[i])
00196 {
00197 floatSampleNum += vertVec[i]->Q() * samplePerUnit;
00198 int vertSampleNum = (int) floatSampleNum;
00199 floatSampleNum -= (float) vertSampleNum;
00200
00201
00202 if(vertSampleNum > 1)
00203 {
00204 ps.AddVert(*vertVec[i]);
00205 cnt++;
00206 vertUsed[i]=true;
00207 }
00208 }
00209 i = (i+1)%m.vn;
00210 }
00211 }
00212
00215 static void VertexAreaUniform(MetroMesh & m, VertexSampler &ps, int sampleNum)
00216 {
00217 VertexIterator vi;
00218 for(vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00219 if(!(*vi).IsD())
00220 (*vi).Q() = 0;
00221
00222 FaceIterator fi;
00223 for(fi = m.face.begin(); fi != m.face.end(); ++fi)
00224 if(!(*fi).IsD())
00225 {
00226 ScalarType areaThird = DoubleArea(*fi)/6.0;
00227 (*fi).V(0).Q()+=areaThird;
00228 (*fi).V(1).Q()+=areaThird;
00229 (*fi).V(2).Q()+=areaThird;
00230 }
00231
00232 VertexWeighted(m,ps,sampleNum);
00233 }
00234
00235 static void FillAndShuffleFacePointerVector(MetroMesh & m, std::vector<FacePointer> &faceVec)
00236 {
00237 FaceIterator fi;
00238 for(fi=m.face.begin();fi!=m.face.end();++fi)
00239 if(!(*fi).IsD()) faceVec.push_back(&*fi);
00240
00241 assert((int)faceVec.size()==m.fn);
00242
00243 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
00244 std::random_shuffle(faceVec.begin(),faceVec.end(), p_myrandom);
00245 }
00246 static void FillAndShuffleVertexPointerVector(MetroMesh & m, std::vector<VertexPointer> &vertVec)
00247 {
00248 VertexIterator vi;
00249 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00250 if(!(*vi).IsD()) vertVec.push_back(&*vi);
00251
00252 assert((int)vertVec.size()==m.vn);
00253
00254 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
00255 std::random_shuffle(vertVec.begin(),vertVec.end(), p_myrandom);
00256 }
00257
00259 static void VertexUniform(MetroMesh & m, VertexSampler &ps, int sampleNum)
00260 {
00261 if(sampleNum>=m.vn) {
00262 AllVertex(m,ps);
00263 return;
00264 }
00265
00266 std::vector<VertexPointer> vertVec;
00267 FillAndShuffleVertexPointerVector(m,vertVec);
00268
00269 for(int i =0; i< sampleNum; ++i)
00270 ps.AddVert(*vertVec[i]);
00271 }
00272
00273
00274 static void FaceUniform(MetroMesh & m, VertexSampler &ps, int sampleNum)
00275 {
00276 if(sampleNum>=m.fn) {
00277 AllFace(m,ps);
00278 return;
00279 }
00280
00281 std::vector<FacePointer> faceVec;
00282 FillAndShuffleFacePointerVector(m,faceVec);
00283
00284 for(int i =0; i< sampleNum; ++i)
00285 ps.AddFace(*faceVec[i],Barycenter(*faceVec[i]));
00286 }
00287
00288 static void AllFace(MetroMesh & m, VertexSampler &ps)
00289 {
00290 FaceIterator fi;
00291 for(fi=m.face.begin();fi!=m.face.end();++fi)
00292 if(!(*fi).IsD())
00293 {
00294 ps.AddFace(*fi,Barycenter(*fi));
00295 }
00296 }
00297
00298
00299 static void AllEdge(MetroMesh & m, VertexSampler &ps)
00300 {
00301
00302 typedef typename UpdateTopology<MetroMesh>::PEdge SimpleEdge;
00303 std::vector< SimpleEdge > Edges;
00304 typename std::vector< SimpleEdge >::iterator ei;
00305 UpdateTopology<MetroMesh>::FillUniqueEdgeVector(m,Edges);
00306
00307 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00308 {
00309 Point3f interp(0,0,0);
00310 interp[ (*ei).z ]=.5;
00311 interp[((*ei).z+1)%3]=.5;
00312 ps.AddFace(*(*ei).f,interp);
00313 }
00314 }
00315
00316
00317
00318
00319
00320 static void EdgeUniform(MetroMesh & m, VertexSampler &ps,int sampleNum, bool sampleFauxEdge=true)
00321 {
00322 typedef typename UpdateTopology<MetroMesh>::PEdge SimpleEdge;
00323 std::vector< SimpleEdge > Edges;
00324 UpdateTopology<MetroMesh>::FillUniqueEdgeVector(m,Edges,sampleFauxEdge);
00325
00326 float edgeSum=0;
00327 typename std::vector< SimpleEdge >::iterator ei;
00328 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00329 edgeSum+=Distance((*ei).v[0]->P(),(*ei).v[1]->P());
00330
00331
00332 float sampleLen = edgeSum/sampleNum;
00333
00334 float rest=0;
00335 for(ei=Edges.begin(); ei!=Edges.end(); ++ei)
00336 {
00337 float len = Distance((*ei).v[0]->P(),(*ei).v[1]->P());
00338 float samplePerEdge = floor((len+rest)/sampleLen);
00339 rest = (len+rest) - samplePerEdge * sampleLen;
00340 float step = 1.0/(samplePerEdge+1);
00341 for(int i=0;i<samplePerEdge;++i)
00342 {
00343 Point3f interp(0,0,0);
00344 interp[ (*ei).z ]=step*(i+1);
00345 interp[((*ei).z+1)%3]=1.0-step*(i+1);
00346 ps.AddFace(*(*ei).f,interp);
00347 }
00348 }
00349 }
00350
00351
00352
00353
00354 static CoordType RandomBaricentric()
00355 {
00356 CoordType interp;
00357 interp[1] = RandomDouble01();
00358 interp[2] = RandomDouble01();
00359 if(interp[1] + interp[2] > 1.0)
00360 {
00361 interp[1] = 1.0 - interp[1];
00362 interp[2] = 1.0 - interp[2];
00363 }
00364
00365 assert(interp[1] + interp[2] <= 1.0);
00366 interp[0]=1.0-(interp[1] + interp[2]);
00367 return interp;
00368 }
00369
00370 static void StratifiedMontecarlo(MetroMesh & m, VertexSampler &ps,int sampleNum)
00371 {
00372 ScalarType area = Stat<MetroMesh>::ComputeMeshArea(m);
00373 ScalarType samplePerAreaUnit = sampleNum/area;
00374
00375
00376 double floatSampleNum = 0.0;
00377
00378 FaceIterator fi;
00379 for(fi=m.face.begin(); fi != m.face.end(); fi++)
00380 if(!(*fi).IsD())
00381 {
00382
00383 floatSampleNum += 0.5*DoubleArea(*fi) * samplePerAreaUnit;
00384 int faceSampleNum = (int) floatSampleNum;
00385
00386
00387 for(int i=0; i < faceSampleNum; i++)
00388 ps.AddFace(*fi,RandomBaricentric());
00389 floatSampleNum -= (double) faceSampleNum;
00390 }
00391 }
00392
00393 static void Montecarlo(MetroMesh & m, VertexSampler &ps,int sampleNum)
00394 {
00395 typedef std::pair<ScalarType, FacePointer> IntervalType;
00396 std::vector< IntervalType > intervals (m.fn+1);
00397 FaceIterator fi;
00398 int i=0;
00399 intervals[i]=std::make_pair(0,FacePointer(0));
00400
00401 for(fi=m.face.begin(); fi != m.face.end(); fi++)
00402 if(!(*fi).IsD())
00403 {
00404 intervals[i+1]=std::make_pair(intervals[i].first+0.5*DoubleArea(*fi), &*fi);
00405 ++i;
00406 }
00407 ScalarType meshArea = intervals.back().first;
00408 for(i=0;i<sampleNum;++i)
00409 {
00410 ScalarType val = meshArea * RandomDouble01();
00411
00412
00413 typename std::vector<IntervalType>::iterator it = lower_bound(intervals.begin(),intervals.end(),std::make_pair(val,FacePointer(0)) );
00414 assert(it != intervals.end());
00415 assert(it != intervals.begin());
00416 assert( (*(it-1)).first <val );
00417 assert( (*(it)).first >= val);
00418 ps.AddFace( *(*it).second, RandomBaricentric() );
00419 }
00420 }
00421
00422 static ScalarType WeightedArea(FaceType f)
00423 {
00424 ScalarType averageQ = ( f.V(0)->Q() + f.V(1)->Q() + f.V(2)->Q() ) /3.0;
00425 return DoubleArea(f)*averageQ/2.0;
00426 }
00427
00431 static void WeightedMontecarlo(MetroMesh & m, VertexSampler &ps, int sampleNum)
00432 {
00433 assert(tri::HasPerVertexQuality(m));
00434
00435 ScalarType weightedArea = 0;
00436 FaceIterator fi;
00437 for(fi = m.face.begin(); fi != m.face.end(); ++fi)
00438 if(!(*fi).IsD())
00439 weightedArea += WeightedArea(*fi);
00440
00441 ScalarType samplePerAreaUnit = sampleNum/weightedArea;
00442
00443
00444 double floatSampleNum = 0.0;
00445 for(fi=m.face.begin(); fi != m.face.end(); fi++)
00446 if(!(*fi).IsD())
00447 {
00448
00449 floatSampleNum += WeightedArea(*fi) * samplePerAreaUnit;
00450 int faceSampleNum = (int) floatSampleNum;
00451
00452
00453 for(int i=0; i < faceSampleNum; i++)
00454 ps.AddFace(*fi,RandomBaricentric());
00455
00456 floatSampleNum -= (double) faceSampleNum;
00457 }
00458 }
00459
00460
00461
00462
00463
00464 static int SingleFaceSubdivision(int sampleNum, const CoordType & v0, const CoordType & v1, const CoordType & v2, VertexSampler &ps, FacePointer fp, bool randSample)
00465 {
00466
00467 if(sampleNum == 1)
00468 {
00469
00470 CoordType SamplePoint;
00471 if(randSample)
00472 {
00473 CoordType rb=RandomBaricentric();
00474 SamplePoint=v0*rb[0]+v1*rb[1]+v2*rb[2];
00475 }
00476 else SamplePoint=((v0+v1+v2)*(1.0f/3.0f));
00477
00478 ps.AddFace(*fp,SamplePoint);
00479 return 1;
00480 }
00481
00482 int s0 = sampleNum /2;
00483 int s1 = sampleNum-s0;
00484 assert(s0>0);
00485 assert(s1>0);
00486
00487 ScalarType w0 = ScalarType(s1)/ScalarType(sampleNum);
00488 ScalarType w1 = 1.0-w0;
00489
00490 ScalarType maxd01 = SquaredDistance(v0,v1);
00491 ScalarType maxd12 = SquaredDistance(v1,v2);
00492 ScalarType maxd20 = SquaredDistance(v2,v0);
00493 int res;
00494 if(maxd01 > maxd12)
00495 if(maxd01 > maxd20) res = 0;
00496 else res = 2;
00497 else
00498 if(maxd12 > maxd20) res = 1;
00499 else res = 2;
00500
00501 int faceSampleNum=0;
00502
00503 CoordType pp;
00504 switch(res)
00505 {
00506 case 0 : pp = v0*w0 + v1*w1;
00507 faceSampleNum+=SingleFaceSubdivision(s0,v0,pp,v2,ps,fp,randSample);
00508 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
00509 break;
00510 case 1 : pp = v1*w0 + v2*w1;
00511 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
00512 faceSampleNum+=SingleFaceSubdivision(s1,v0,pp,v2,ps,fp,randSample);
00513 break;
00514 case 2 : pp = v0*w0 + v2*w1;
00515 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
00516 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
00517 break;
00518 }
00519 return faceSampleNum;
00520 }
00521
00522
00524 static void FaceSubdivision(MetroMesh & m, VertexSampler &ps,int sampleNum, bool randSample)
00525 {
00526
00527 ScalarType area = Stat<MetroMesh>::ComputeMeshArea(m);
00528 ScalarType samplePerAreaUnit = sampleNum/area;
00529
00530 std::vector<FacePointer> faceVec;
00531 FillAndShuffleFacePointerVector(m,faceVec);
00532 vcg::tri::UpdateNormals<MetroMesh>::PerFaceNormalized(m);
00533 vcg::tri::UpdateFlags<MetroMesh>::FaceProjection(m);
00534 double floatSampleNum = 0.0;
00535 int faceSampleNum;
00536
00537 typename std::vector<FacePointer>::iterator fi;
00538 for(fi=faceVec.begin(); fi!=faceVec.end(); fi++)
00539 {
00540 const CoordType b0(1.0, 0.0, 0.0);
00541 const CoordType b1(0.0, 1.0, 0.0);
00542 const CoordType b2(0.0, 0.0, 1.0);
00543
00544 floatSampleNum += 0.5*DoubleArea(**fi) * samplePerAreaUnit;
00545 faceSampleNum = (int) floatSampleNum;
00546 if(faceSampleNum>0)
00547 faceSampleNum = SingleFaceSubdivision(faceSampleNum,b0,b1,b2,ps,*fi,randSample);
00548 floatSampleNum -= (double) faceSampleNum;
00549 }
00550 }
00551
00552
00553
00554
00555 static int SingleFaceSubdivisionOld(int sampleNum, const CoordType & v0, const CoordType & v1, const CoordType & v2, VertexSampler &ps, FacePointer fp, bool randSample)
00556 {
00557
00558 if(sampleNum == 1)
00559 {
00560
00561 CoordType SamplePoint;
00562 if(randSample)
00563 {
00564 CoordType rb=RandomBaricentric();
00565 SamplePoint=v0*rb[0]+v1*rb[1]+v2*rb[2];
00566 }
00567 else SamplePoint=((v0+v1+v2)*(1.0f/3.0f));
00568
00569 CoordType SampleBary;
00570
00571
00572
00573
00574
00575
00576
00577
00578 InterpolationParameters(*fp,SamplePoint,SampleBary[0],SampleBary[1],SampleBary[2]);
00579 ps.AddFace(*fp,SampleBary);
00580 return 1;
00581 }
00582
00583 int s0 = sampleNum /2;
00584 int s1 = sampleNum-s0;
00585 assert(s0>0);
00586 assert(s1>0);
00587
00588 ScalarType w0 = ScalarType(s1)/ScalarType(sampleNum);
00589 ScalarType w1 = 1.0-w0;
00590
00591 ScalarType maxd01 = SquaredDistance(v0,v1);
00592 ScalarType maxd12 = SquaredDistance(v1,v2);
00593 ScalarType maxd20 = SquaredDistance(v2,v0);
00594 int res;
00595 if(maxd01 > maxd12)
00596 if(maxd01 > maxd20) res = 0;
00597 else res = 2;
00598 else
00599 if(maxd12 > maxd20) res = 1;
00600 else res = 2;
00601
00602 int faceSampleNum=0;
00603
00604 CoordType pp;
00605 switch(res)
00606 {
00607 case 0 : pp = v0*w0 + v1*w1;
00608 faceSampleNum+=SingleFaceSubdivision(s0,v0,pp,v2,ps,fp,randSample);
00609 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
00610 break;
00611 case 1 : pp = v1*w0 + v2*w1;
00612 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
00613 faceSampleNum+=SingleFaceSubdivision(s1,v0,pp,v2,ps,fp,randSample);
00614 break;
00615 case 2 : pp = v0*w0 + v2*w1;
00616 faceSampleNum+=SingleFaceSubdivision(s0,v0,v1,pp,ps,fp,randSample);
00617 faceSampleNum+=SingleFaceSubdivision(s1,pp,v1,v2,ps,fp,randSample);
00618 break;
00619 }
00620 return faceSampleNum;
00621 }
00622
00623
00625 static void FaceSubdivisionOld(MetroMesh & m, VertexSampler &ps,int sampleNum, bool randSample)
00626 {
00627
00628 ScalarType area = Stat<MetroMesh>::ComputeMeshArea(m);
00629 ScalarType samplePerAreaUnit = sampleNum/area;
00630
00631 std::vector<FacePointer> faceVec;
00632 FillAndShuffleFacePointerVector(m,faceVec);
00633 tri::UpdateNormals<MetroMesh>::PerFaceNormalized(m);
00634 tri::UpdateFlags<MetroMesh>::FaceProjection(m);
00635 double floatSampleNum = 0.0;
00636 int faceSampleNum;
00637
00638 typename std::vector<FacePointer>::iterator fi;
00639 for(fi=faceVec.begin(); fi!=faceVec.end(); fi++)
00640 {
00641
00642 floatSampleNum += 0.5*DoubleArea(**fi) * samplePerAreaUnit;
00643 faceSampleNum = (int) floatSampleNum;
00644 if(faceSampleNum>0)
00645 faceSampleNum = SingleFaceSubdivision(faceSampleNum,(**fi).V(0)->cP(), (**fi).V(1)->cP(), (**fi).V(2)->cP(),ps,*fi,randSample);
00646 floatSampleNum -= (double) faceSampleNum;
00647 }
00648 }
00649
00650
00651
00652
00653
00654
00655
00656
00657 static int SingleFaceSimilar(FacePointer fp, VertexSampler &ps, int n_samples_per_edge)
00658 {
00659 int n_samples=0;
00660 int i, j;
00661 float segmentNum=n_samples_per_edge -1 ;
00662 float segmentLen = 1.0/segmentNum;
00663
00664 for(i=1; i < n_samples_per_edge-1; i++)
00665 for(j=1; j < n_samples_per_edge-1-i; j++)
00666 {
00667
00668 CoordType sampleBary(i*segmentLen,j*segmentLen, 1.0 - (i*segmentLen+j*segmentLen) ) ;
00669 n_samples++;
00670 ps.AddFace(*fp,sampleBary);
00671 }
00672 return n_samples;
00673 }
00674 static int SingleFaceSimilarDual(FacePointer fp, VertexSampler &ps, int n_samples_per_edge, bool randomFlag)
00675 {
00676 int n_samples=0;
00677 float i, j;
00678 float segmentNum=n_samples_per_edge -1 ;
00679 float segmentLen = 1.0/segmentNum;
00680
00681 for(i=0; i < n_samples_per_edge-1; i++)
00682 for(j=0; j < n_samples_per_edge-1-i; j++)
00683 {
00684
00685 CoordType V0((i+0)*segmentLen,(j+0)*segmentLen, 1.0 - ((i+0)*segmentLen+(j+0)*segmentLen) ) ;
00686 CoordType V1((i+1)*segmentLen,(j+0)*segmentLen, 1.0 - ((i+1)*segmentLen+(j+0)*segmentLen) ) ;
00687 CoordType V2((i+0)*segmentLen,(j+1)*segmentLen, 1.0 - ((i+0)*segmentLen+(j+1)*segmentLen) ) ;
00688 n_samples++;
00689 if(randomFlag) {
00690 CoordType rb=RandomBaricentric();
00691 ps.AddFace(*fp, V0*rb[0]+V1*rb[1]+V2*rb[2]);
00692 } else ps.AddFace(*fp,(V0+V1+V2)/3.0);
00693
00694 if( j < n_samples_per_edge-i-2 )
00695 {
00696 CoordType V3((i+1)*segmentLen,(j+1)*segmentLen, 1.0 - ((i+1)*segmentLen+(j+1)*segmentLen) ) ;
00697 n_samples++;
00698 if(randomFlag) {
00699 CoordType rb=RandomBaricentric();
00700 ps.AddFace(*fp, V3*rb[0]+V1*rb[1]+V2*rb[2]);
00701 } else ps.AddFace(*fp,(V3+V1+V2)/3.0);
00702 }
00703 }
00704 return n_samples;
00705 }
00706
00707
00708
00709
00710
00711
00712
00713
00714
00715
00716
00717
00718
00719
00720
00721
00722
00723
00724
00725
00726
00727
00728
00729
00730
00731
00732
00733
00734
00735
00736 static void FaceSimilar(MetroMesh & m, VertexSampler &ps,int sampleNum, bool dualFlag, bool randomFlag)
00737 {
00738 ScalarType area = Stat<MetroMesh>::ComputeMeshArea(m);
00739 ScalarType samplePerAreaUnit = sampleNum/area;
00740
00741
00742 int n_samples_per_edge;
00743 double n_samples_decimal = 0.0;
00744 FaceIterator fi;
00745
00746 for(fi=m.face.begin(); fi != m.face.end(); fi++)
00747 {
00748
00749 n_samples_decimal += 0.5*DoubleArea(*fi) * samplePerAreaUnit;
00750 int n_samples = (int) n_samples_decimal;
00751 if(n_samples>0)
00752 {
00753
00754 if(dualFlag)
00755 {
00756 n_samples_per_edge = (int)((sqrt(1.0+8.0*(double)n_samples) +5.0)/2.0);
00757 n_samples = SingleFaceSimilar(&*fi,ps, n_samples_per_edge);
00758 } else {
00759 n_samples_per_edge = (int)(sqrt((double)n_samples) +1.0);
00760 n_samples = SingleFaceSimilarDual(&*fi,ps, n_samples_per_edge,randomFlag);
00761 }
00762 }
00763 n_samples_decimal -= (double) n_samples;
00764 }
00765 }
00766
00767
00768
00769
00770
00771
00772
00773
00774
00775
00776
00777 static void SingleFaceRaster(typename MetroMesh::FaceType &f, VertexSampler &ps,
00778 const Point2<typename MetroMesh::ScalarType> & v0,
00779 const Point2<typename MetroMesh::ScalarType> & v1,
00780 const Point2<typename MetroMesh::ScalarType> & v2,
00781 bool correctSafePointsBaryCoords=true)
00782 {
00783 typedef typename MetroMesh::ScalarType S;
00784
00785 Box2i bbox;
00786 Box2<S> bboxf;
00787 bboxf.Add(v0);
00788 bboxf.Add(v1);
00789 bboxf.Add(v2);
00790
00791 bbox.min[0] = floor(bboxf.min[0]);
00792 bbox.min[1] = floor(bboxf.min[1]);
00793 bbox.max[0] = ceil(bboxf.max[0]);
00794 bbox.max[1] = ceil(bboxf.max[1]);
00795
00796
00797 Point2<S> d10 = v1 - v0;
00798 Point2<S> d21 = v2 - v1;
00799 Point2<S> d02 = v0 - v2;
00800
00801
00802 S b0 = (bbox.min[0]-v0[0])*d10[1] - (bbox.min[1]-v0[1])*d10[0];
00803 S b1 = (bbox.min[0]-v1[0])*d21[1] - (bbox.min[1]-v1[1])*d21[0];
00804 S b2 = (bbox.min[0]-v2[0])*d02[1] - (bbox.min[1]-v2[1])*d02[0];
00805
00806 S db0 = d10[1];
00807 S db1 = d21[1];
00808 S db2 = d02[1];
00809
00810 S dn0 = -d10[0];
00811 S dn1 = -d21[0];
00812 S dn2 = -d02[0];
00813
00814
00815 bool flipped = !(d02 * vcg::Point2<S>(-d10[1], d10[0]) >= 0);
00816
00817
00818 Segment2<S> borderEdges[3];
00819 S edgeLength[3];
00820 unsigned char edgeMask = 0;
00821
00822 if (f.IsB(0)) {
00823 borderEdges[0] = Segment2<S>(v0, v1);
00824 edgeLength[0] = borderEdges[0].Length();
00825 edgeMask |= 1;
00826 }
00827 if (f.IsB(1)) {
00828 borderEdges[1] = Segment2<S>(v1, v2);
00829 edgeLength[1] = borderEdges[1].Length();
00830 edgeMask |= 2;
00831 }
00832 if (f.IsB(2)) {
00833 borderEdges[2] = Segment2<S>(v2, v0);
00834 edgeLength[2] = borderEdges[2].Length();
00835 edgeMask |= 4;
00836 }
00837
00838
00839 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];
00840
00841 for(int x=bbox.min[0]-1;x<=bbox.max[0]+1;++x)
00842 {
00843 bool in = false;
00844 S n[3] = { b0-db0-dn0, b1-db1-dn1, b2-db2-dn2};
00845 for(int y=bbox.min[1]-1;y<=bbox.max[1]+1;++y)
00846 {
00847 if((n[0]>=0 && n[1]>=0 && n[2]>=0) || (n[0]<=0 && n[1]<=0 && n[2]<=0))
00848 {
00849 typename MetroMesh::CoordType baryCoord;
00850 baryCoord[0] = double(-y*v1[0]+v2[0]*y+v1[1]*x-v2[0]*v1[1]+v1[0]*v2[1]-x*v2[1])/de;
00851 baryCoord[1] = -double( x*v0[1]-x*v2[1]-v0[0]*y+v0[0]*v2[1]-v2[0]*v0[1]+v2[0]*y)/de;
00852 baryCoord[2] = 1-baryCoord[0]-baryCoord[1];
00853
00854 ps.AddTextureSample(f, baryCoord, Point2i(x,y), 0);
00855 in = true;
00856 } else {
00857
00858 Point2<S> px(x, y);
00859 Point2<S> closePoint;
00860 int closeEdge = -1;
00861 S minDst = FLT_MAX;
00862
00863
00864 for (int i=0; i<3; ++i)
00865 {
00866 if (edgeMask & (1 << i))
00867 {
00868 Point2<S> close;
00869 S dst;
00870 if ( (!flipped && n[i]<0 || flipped && n[i]>0) &&
00871 (dst = ((close = ClosestPoint(borderEdges[i], px)) - px).Norm()) < minDst &&
00872 close.X() > px.X()-1 && close.X() < px.X()+1 &&
00873 close.Y() > px.Y()-1 && close.Y() < px.Y()+1)
00874 {
00875 minDst = dst;
00876 closePoint = close;
00877 closeEdge = i;
00878 }
00879 }
00880 }
00881
00882 if (closeEdge >= 0)
00883 {
00884 typename MetroMesh::CoordType baryCoord;
00885 if (correctSafePointsBaryCoords)
00886 {
00887
00888 baryCoord[closeEdge] = (closePoint - borderEdges[closeEdge].P(1)).Norm()/edgeLength[closeEdge];
00889 baryCoord[(closeEdge+1)%3] = 1 - baryCoord[closeEdge];
00890 baryCoord[(closeEdge+2)%3] = 0;
00891 } else {
00892
00893 baryCoord[0] = double(-y*v1[0]+v2[0]*y+v1[1]*x-v2[0]*v1[1]+v1[0]*v2[1]-x*v2[1])/de;
00894 baryCoord[1] = -double( x*v0[1]-x*v2[1]-v0[0]*y+v0[0]*v2[1]-v2[0]*v0[1]+v2[0]*y)/de;
00895 baryCoord[2] = 1-baryCoord[0]-baryCoord[1];
00896 }
00897 ps.AddTextureSample(f, baryCoord, Point2i(x,y), minDst);
00898 in = true;
00899 }
00900 }
00901 n[0] += dn0;
00902 n[1] += dn1;
00903 n[2] += dn2;
00904 }
00905 b0 += db0;
00906 b1 += db1;
00907 b2 += db2;
00908 }
00909 }
00910
00911
00912 static CoordType RandomBox(vcg::Box3<ScalarType> box)
00913 {
00914 CoordType p = box.min;
00915 p[0] += box.Dim()[0] * RandomDouble01();
00916 p[1] += box.Dim()[1] * RandomDouble01();
00917 p[2] += box.Dim()[2] * RandomDouble01();
00918 return p;
00919 }
00920
00921
00922
00923 static VertexPointer getPrecomputedMontecarloSample(Point3i &cell, MontecarloSHT & samplepool)
00924 {
00925 MontecarloSHTIterator cellBegin;
00926 MontecarloSHTIterator cellEnd;
00927 samplepool.Grid(cell, cellBegin, cellEnd);
00928 return *cellBegin;
00929 }
00930
00931
00932 static bool checkPoissonDisk(MetroMesh & vmesh, SampleSHT & sht, const Point3<ScalarType> & p, ScalarType radius)
00933 {
00934
00935 std::vector<VertexType*> closests;
00936
00937 typedef VertTmark<MetroMesh> MarkerVert;
00938 static MarkerVert mv;
00939
00940 Box3f bb(p-Point3f(radius,radius,radius),p+Point3f(radius,radius,radius));
00941 int nsamples = GridGetInBox(sht, mv, bb, closests);
00942
00943 ScalarType r2 = radius*radius;
00944 for(int i=0; i<closests.size(); ++i)
00945 if(SquaredDistance(p,closests[i]->cP()) < r2)
00946 return false;
00947
00948 return true;
00949 }
00950
00951 struct PoissonDiskParam
00952 {
00953 PoissonDiskParam()
00954 {
00955 adaptiveRadiusFlag = false;
00956 radiusVariance =1;
00957 MAXLEVELS = 5;
00958 invertQuality = false;
00959 preGenFlag = false;
00960 preGenMesh = NULL;
00961 }
00962 bool adaptiveRadiusFlag;
00963 float radiusVariance;
00964 bool invertQuality;
00965 bool preGenFlag;
00966 MetroMesh *preGenMesh;
00967 int MAXLEVELS;
00968 };
00969
00970 static ScalarType ComputePoissonDiskRadius(MetroMesh &origMesh, int sampleNum)
00971 {
00972 ScalarType meshArea = Stat<MetroMesh>::ComputeMeshArea(origMesh);
00973
00974
00975 if(meshArea ==0)
00976 {
00977 meshArea = (origMesh.bbox.DimX()*origMesh.bbox.DimY() +
00978 origMesh.bbox.DimX()*origMesh.bbox.DimZ() +
00979 origMesh.bbox.DimY()*origMesh.bbox.DimZ());
00980 }
00981 ScalarType diskRadius = sqrt(meshArea / (0.7 * M_PI * sampleNum));
00982 return diskRadius;
00983 }
00984
00985 static int ComputePoissonSampleNum(MetroMesh &origMesh, ScalarType diskRadius)
00986 {
00987 ScalarType meshArea = Stat<MetroMesh>::ComputeMeshArea(origMesh);
00988 int sampleNum = meshArea / (diskRadius*diskRadius *M_PI *0.7) ;
00989 return sampleNum;
00990 }
00991
00992 static void ComputePoissonSampleRadii(MetroMesh &sampleMesh, ScalarType diskRadius, ScalarType radiusVariance, bool invert)
00993 {
00994 VertexIterator vi;
00995 std::pair<float,float> minmax = tri::Stat<MetroMesh>::ComputePerVertexQualityMinMax( sampleMesh);
00996 float minRad = diskRadius / radiusVariance;
00997 float maxRad = diskRadius * radiusVariance;
00998 float deltaQ = minmax.second-minmax.first;
00999 float deltaRad = maxRad-minRad;
01000 for (vi = sampleMesh.vert.begin(); vi != sampleMesh.vert.end(); vi++)
01001 {
01002 (*vi).Q() = minRad + deltaRad*((invert ? minmax.second - (*vi).Q() : (*vi).Q() - minmax.first )/deltaQ);
01003 }
01004 }
01005
01006
01007 static void PoissonDiskPruning(MetroMesh &origMesh, VertexSampler &ps, MetroMesh &montecarloMesh, ScalarType diskRadius, const struct PoissonDiskParam pp=PoissonDiskParam())
01008 {
01009
01010 MontecarloSHT montecarloSHT;
01011
01012
01013
01014 ScalarType cellsize = 2.0f* diskRadius / sqrt(3.0);
01015
01016
01017 origMesh.bbox.Offset(cellsize);
01018
01019 int sizeX = vcg::math::Max(1.0f,origMesh.bbox.DimX() / cellsize);
01020 int sizeY = vcg::math::Max(1.0f,origMesh.bbox.DimY() / cellsize);
01021 int sizeZ = vcg::math::Max(1.0f,origMesh.bbox.DimZ() / cellsize);
01022 Point3i gridsize(sizeX, sizeY, sizeZ);
01023 #ifdef QT_VERSION
01024 qDebug("PDS: radius %f Grid:(%i %i %i) ",diskRadius,sizeX,sizeY,sizeZ);
01025 QTime tt; tt.start();
01026 #endif
01027
01028
01029 if(pp.adaptiveRadiusFlag)
01030 ComputePoissonSampleRadii(montecarloMesh, diskRadius, pp.radiusVariance, pp.invertQuality);
01031
01032 montecarloSHT.InitEmpty(origMesh.bbox, gridsize);
01033
01034 for (VertexIterator vi = montecarloMesh.vert.begin(); vi != montecarloMesh.vert.end(); vi++)
01035 montecarloSHT.Add(&(*vi));
01036
01037 montecarloSHT.UpdateAllocatedCells();
01038
01039
01040 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
01041 std::random_shuffle(montecarloSHT.AllocatedCells.begin(),montecarloSHT.AllocatedCells.end(), p_myrandom);
01042
01043 #ifdef QT_VERSION
01044 qDebug("PDS: Completed creation of activeCells, %i cells (%i msec)", (int)montecarloSHT.AllocatedCells.size(), tt.restart());
01045 #endif
01046 int removedCnt=0;
01047 if(pp.preGenFlag)
01048 {
01049
01050 for(VertexIterator vi =pp.preGenMesh->vert.begin(); vi!=pp.preGenMesh->vert.end();++vi)
01051 {
01052 ps.AddVert(*vi);
01053 removedCnt += montecarloSHT.RemoveInSphere(vi->cP(),diskRadius);
01054 }
01055 montecarloSHT.UpdateAllocatedCells();
01056 #ifdef QT_VERSION
01057 qDebug("Removed %i samples in %i",removedCnt,tt.restart());
01058 #endif
01059 }
01060 while(!montecarloSHT.AllocatedCells.empty())
01061 {
01062 removedCnt=0;
01063 for (size_t i = 0; i < montecarloSHT.AllocatedCells.size(); i++)
01064 {
01065 if( montecarloSHT.EmptyCell(montecarloSHT.AllocatedCells[i]) ) continue;
01066 VertexPointer sp = getPrecomputedMontecarloSample(montecarloSHT.AllocatedCells[i], montecarloSHT);
01067 ps.AddVert(*sp);
01068 ScalarType sampleRadius = diskRadius;
01069 if(pp.adaptiveRadiusFlag) sampleRadius = sp->Q();
01070 removedCnt += montecarloSHT.RemoveInSphere(sp->cP(),sampleRadius);
01071 }
01072
01073 #ifdef QT_VERSION
01074 qDebug("Removed %i samples in %i",removedCnt,tt.restart());
01075 #endif
01076 montecarloSHT.UpdateAllocatedCells();
01077 }
01078 }
01079
01090 static void PoissonDisk(MetroMesh &origMesh, VertexSampler &ps, MetroMesh &montecarloMesh, ScalarType diskRadius, const struct PoissonDiskParam pp=PoissonDiskParam())
01091 {
01092
01093
01094 MontecarloSHT montecarloSHTVec[5];
01095
01096
01097
01098
01099
01100
01101 ScalarType cellsize = 2.0f* diskRadius / sqrt(3.0);
01102
01103
01104 origMesh.bbox.Offset(cellsize);
01105
01106 int sizeX = vcg::math::Max(1.0f,origMesh.bbox.DimX() / cellsize);
01107 int sizeY = vcg::math::Max(1.0f,origMesh.bbox.DimY() / cellsize);
01108 int sizeZ = vcg::math::Max(1.0f,origMesh.bbox.DimZ() / cellsize);
01109 Point3i gridsize(sizeX, sizeY, sizeZ);
01110 #ifdef QT_VERSION
01111 qDebug("PDS: radius %f Grid:(%i %i %i) ",diskRadius,sizeX,sizeY,sizeZ);
01112 QTime tt; tt.start();
01113 #endif
01114
01115
01116 SampleSHT checkSHT;
01117 checkSHT.InitEmpty(origMesh.bbox, gridsize);
01118
01119
01120
01121
01122
01123
01124
01125
01126
01127
01128
01129
01130 int level = 0;
01131
01132
01133 montecarloSHTVec[0].InitEmpty(origMesh.bbox, gridsize);
01134
01135 for (VertexIterator vi = montecarloMesh.vert.begin(); vi != montecarloMesh.vert.end(); vi++)
01136 montecarloSHTVec[0].Add(&(*vi));
01137 montecarloSHTVec[0].UpdateAllocatedCells();
01138
01139
01140 if(pp.adaptiveRadiusFlag)
01141 ComputePoissonSampleRadii(montecarloMesh, diskRadius, pp.radiusVariance, pp.invertQuality);
01142
01143 do
01144 {
01145 MontecarloSHT &montecarloSHT = montecarloSHTVec[level];
01146
01147 if(level>0)
01148 {
01149 montecarloSHT.InitEmpty(origMesh.bbox, gridsize);
01150
01151 for (typename MontecarloSHT::HashIterator hi = montecarloSHTVec[level-1].hash_table.begin(); hi != montecarloSHTVec[level-1].hash_table.end(); hi++)
01152 montecarloSHT.Add((*hi).second);
01153 montecarloSHT.UpdateAllocatedCells();
01154 }
01155
01156 unsigned int (*p_myrandom)(unsigned int) = RandomInt;
01157 std::random_shuffle(montecarloSHT.AllocatedCells.begin(),montecarloSHT.AllocatedCells.end(), p_myrandom);
01158 #ifdef QT_VERSION
01159 qDebug("PDS: Init of Hashing grid %i cells and %i samples (%i msec)", montecarloSHT.AllocatedCells.size(), montecarloSHT.hash_table.size(), tt.restart());
01160 #endif
01161
01162
01164 int removedCnt=montecarloSHT.hash_table.size();
01165 int addedCnt=checkSHT.hash_table.size();
01166 for (int i = 0; i < montecarloSHT.AllocatedCells.size(); i++)
01167 {
01168 for(int j=0;j<4;j++)
01169 {
01170 if( montecarloSHT.EmptyCell(montecarloSHT.AllocatedCells[i]) ) continue;
01171
01172
01173 typename MontecarloSHT::HashIterator hi = montecarloSHT.hash_table.find(montecarloSHT.AllocatedCells[i]);
01174
01175 if(hi==montecarloSHT.hash_table.end()) {break;}
01176 VertexPointer sp = (*hi).second;
01177
01178 ScalarType sampleRadius = diskRadius;
01179 if(pp.adaptiveRadiusFlag) sampleRadius = sp->Q();
01180 if (checkPoissonDisk(*ps.m, checkSHT, sp->cP(), sampleRadius))
01181 {
01182 ps.AddVert(*sp);
01183 montecarloSHT.RemoveCell(sp);
01184 checkSHT.Add(sp);
01185 break;
01186 }
01187 else
01188 montecarloSHT.RemovePunctual(sp);
01189 }
01190 }
01191 addedCnt = checkSHT.hash_table.size()-addedCnt;
01192 removedCnt = removedCnt-montecarloSHT.hash_table.size();
01193
01194
01195
01196 gridsize *= 2;
01197
01198
01199 #ifdef QT_VERSION
01200 qDebug("PDS: Pruning %i added %i and removed %i samples (%i msec)",level,addedCnt, removedCnt,tt.restart());
01201 #endif
01202 level++;
01203 } while(level < 5);
01204 }
01205
01206
01207
01208
01209
01210
01211
01212
01213
01214
01215
01216
01217
01218
01219 static void Texture(MetroMesh & m, VertexSampler &ps, int textureWidth, int textureHeight, bool correctSafePointsBaryCoords=true)
01220 {
01221 FaceIterator fi;
01222
01223 printf("Similar Triangles face sampling\n");
01224 for(fi=m.face.begin(); fi != m.face.end(); fi++)
01225 {
01226 Point2f ti[3];
01227 for(int i=0;i<3;++i)
01228 ti[i]=Point2f((*fi).WT(i).U() * textureWidth - 0.5, (*fi).WT(i).V() * textureHeight - 0.5);
01229
01230 SingleFaceRaster(*fi, ps, ti[0],ti[1],ti[2], correctSafePointsBaryCoords);
01231 }
01232 }
01233
01234 typedef GridStaticPtr<FaceType, ScalarType > TriMeshGrid;
01235
01236 class RRParam
01237 {
01238 public:
01239 float offset;
01240 float minDiag;
01241 tri::FaceTmark<MetroMesh> markerFunctor;
01242 TriMeshGrid gM;
01243 };
01244
01245 static void RegularRecursiveOffset(MetroMesh & m, std::vector<Point3f> &pvec, ScalarType offset, float minDiag)
01246 {
01247 Box3<ScalarType> bb=m.bbox;
01248 bb.Offset(offset*2.0);
01249
01250 RRParam rrp;
01251
01252 rrp.markerFunctor.SetMesh(&m);
01253
01254 rrp.gM.Set(m.face.begin(),m.face.end(),bb);
01255
01256
01257 rrp.offset=offset;
01258 rrp.minDiag=minDiag;
01259 SubdivideAndSample(m, pvec, bb, rrp, bb.Diag());
01260 }
01261
01262 static void SubdivideAndSample(MetroMesh & m, std::vector<Point3f> &pvec, const Box3<ScalarType> bb, RRParam &rrp, float curDiag)
01263 {
01264 Point3f startPt = bb.Center();
01265
01266 ScalarType dist;
01267
01268 FaceType *nearestF=0;
01269 float dist_upper_bound = curDiag+rrp.offset;
01270 Point3f closestPt;
01271 vcg::face::PointDistanceBaseFunctor<ScalarType> PDistFunct;
01272 dist=dist_upper_bound;
01273 nearestF = rrp.gM.GetClosest(PDistFunct,rrp.markerFunctor,startPt,dist_upper_bound,dist,closestPt);
01274 curDiag /=2;
01275 if(dist < dist_upper_bound)
01276 {
01277 if(curDiag/3 < rrp.minDiag)
01278 {
01279 if(rrp.offset==0)
01280 pvec.push_back(closestPt);
01281 else
01282 {
01283 if(dist>rrp.offset)
01284 {
01285 Point3f delta = startPt-closestPt;
01286 pvec.push_back(closestPt+delta*(rrp.offset/dist));
01287 }
01288 }
01289 }
01290 if(curDiag < rrp.minDiag) return;
01291 Point3f hs = (bb.max-bb.min)/2;
01292 for(int i=0;i<2;i++)
01293 for(int j=0;j<2;j++)
01294 for(int k=0;k<2;k++)
01295 SubdivideAndSample(m,pvec,
01296 Box3f(Point3f( bb.min[0]+i*hs[0], bb.min[1]+j*hs[1], bb.min[2]+k*hs[2]),
01297 Point3f(startPt[0]+i*hs[0],startPt[1]+j*hs[1],startPt[2]+k*hs[2])),rrp,curDiag);
01298
01299 }
01300 }
01301 };
01302
01303
01304 }
01305 }
01306
01307 #endif
01308