00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00030 #ifndef __VCGLIB_REFINE_LOOP
00031 #define __VCGLIB_REFINE_LOOP
00032
00033 #include <cmath>
00034 #include <vcg/space/point3.h>
00035 #include <vcg/complex/complex.h>
00036 #include <vcg/complex/algorithms/refine.h>
00037 #include <vcg/space/color4.h>
00038 #include <vcg/container/simple_temporary_data.h>
00039 #include <vcg/complex/algorithms/update/flag.h>
00040 #include <vcg/complex/algorithms/update/color.h>
00041
00042
00043 namespace vcg{
00044 namespace tri{
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00068 template<class SCALAR_TYPE>
00069 struct LoopWeight {
00070 inline SCALAR_TYPE beta(int k) {
00071 return (k>3)?(5.0/8.0 - std::pow((3.0/8.0 + std::cos(2.0*M_PI/SCALAR_TYPE(k))/4.0),2))/SCALAR_TYPE(k):3.0/16.0;
00072 }
00073
00074 inline SCALAR_TYPE incidentRegular(int) {
00075 return 3.0/8.0;
00076 }
00077 inline SCALAR_TYPE incidentIrregular(int) {
00078 return 3.0/8.0;
00079 }
00080 inline SCALAR_TYPE opposite(int) {
00081 return 1.0/8.0;
00082 }
00083 };
00084
00090 template<class SCALAR_TYPE>
00091 struct RegularLoopWeight {
00092 inline SCALAR_TYPE beta(int k) {
00093 static SCALAR_TYPE bkPolar[] = {
00094 .32517,
00095 .49954,
00096 .59549,
00097 .625,
00098 .63873,
00099 .64643,
00100 .65127,
00101 .67358,
00102 .68678,
00103 .69908
00104 };
00105
00106 return (k<=12)?(1.0-bkPolar[k-3])/k:LoopWeight<SCALAR_TYPE>().beta(k);
00107 }
00108
00109 inline SCALAR_TYPE incidentRegular(int k) {
00110 return 1.0 - incidentIrregular(k) - opposite(k)*2;
00111 }
00112 inline SCALAR_TYPE incidentIrregular(int k) {
00113 static SCALAR_TYPE bkPolar[] = {
00114 .15658,
00115 .25029,
00116 .34547,
00117 .375,
00118 .38877,
00119 .39644,
00120 .40132,
00121 .42198,
00122 .43423,
00123 .44579
00124 };
00125
00126 return (k<=12)?bkPolar[k-3]:LoopWeight<SCALAR_TYPE>().incidentIrregular(k);
00127 }
00128 inline SCALAR_TYPE opposite(int k) {
00129 static SCALAR_TYPE bkPolar[] = {
00130 .14427,
00131 .12524,
00132 .11182,
00133 .125,
00134 .14771,
00135 .1768,
00136 .21092,
00137 .20354,
00138 .20505,
00139 .19828
00140 };
00141
00142 return (k<=12)?bkPolar[k-3]:LoopWeight<SCALAR_TYPE>().opposite(k);
00143 }
00144 };
00145
00146 template<class SCALAR_TYPE>
00147 struct ContinuityLoopWeight {
00148 inline SCALAR_TYPE beta(int k) {
00149 static SCALAR_TYPE bkPolar[] = {
00150 .32517,
00151 .50033,
00152 .59464,
00153 .625,
00154 .63903,
00155 .67821,
00156 .6866,
00157 .69248,
00158 .69678,
00159 .70014
00160 };
00161
00162 return (k<=12)?(1.0-bkPolar[k-3])/k:LoopWeight<SCALAR_TYPE>().beta(k);
00163 }
00164
00165 inline SCALAR_TYPE incidentRegular(int k) {
00166 return 1.0 - incidentIrregular(k) - opposite(k)*2;
00167 }
00168 inline SCALAR_TYPE incidentIrregular(int k) {
00169 static SCALAR_TYPE bkPolar[] = {
00170 .15658,
00171 .26721,
00172 .33539,
00173 .375,
00174 .36909,
00175 .25579,
00176 .2521,
00177 .24926,
00178 .24706,
00179 .2452
00180 };
00181
00182 return (k<=12)?bkPolar[k-3]:LoopWeight<SCALAR_TYPE>().incidentIrregular(k);
00183 }
00184 inline SCALAR_TYPE opposite(int k) {
00185 static SCALAR_TYPE bkPolar[] = {
00186 .14427,
00187 .12495,
00188 .11252,
00189 .125,
00190 .14673,
00191 .16074,
00192 .18939,
00193 .2222,
00194 .25894,
00195 .29934
00196 };
00197
00198 return (k<=12)?bkPolar[k-3]:LoopWeight<SCALAR_TYPE>().opposite(k);
00199 }
00200 };
00201
00202
00203
00207 template<class MESH_TYPE, class LSCALAR_TYPE = typename MESH_TYPE::ScalarType>
00208 struct Centroid {
00209 typedef typename MESH_TYPE::ScalarType Scalar;
00210 typedef typename MESH_TYPE::CoordType CoordType;
00211 typedef LSCALAR_TYPE LScalar;
00212 typedef vcg::Point3<LScalar> LVector;
00213
00214 LVector sumP;
00215 LScalar sumW;
00216
00217 Centroid() { reset(); }
00218 inline void reset() {
00219 sumP.SetZero();
00220 sumW = 0.;
00221 }
00222 inline void addVertex(const typename MESH_TYPE::VertexType &v, LScalar w) {
00223 LVector p(v.cP().X(), v.cP().Y(), v.cP().Z());
00224 sumP += p * w;
00225 sumW += w;
00226 }
00227 inline void project(std::pair<CoordType,CoordType> &nv) const {
00228 LVector position = sumP / sumW;
00229 nv.first = CoordType(position.X(), position.Y(), position.Z());
00230 }
00231 };
00232
00242 template<class MESH_TYPE, class LSCALAR_TYPE = typename MESH_TYPE::ScalarType>
00243 struct LS3Projection {
00244 typedef typename MESH_TYPE::ScalarType Scalar;
00245 typedef typename MESH_TYPE::CoordType CoordType;
00246 typedef LSCALAR_TYPE LScalar;
00247 typedef vcg::Point3<LScalar> LVector;
00248
00249 Scalar beta;
00250
00251 LVector sumP;
00252 LVector sumN;
00253 LScalar sumDotPN;
00254 LScalar sumDotPP;
00255 LScalar sumW;
00256
00257 inline LS3Projection(Scalar beta = 1.0) : beta(beta) { reset(); }
00258 inline void reset() {
00259 sumP.SetZero();
00260 sumN.SetZero();
00261 sumDotPN = 0.;
00262 sumDotPP = 0.;
00263 sumW = 0.;
00264 }
00265 inline void addVertex(const typename MESH_TYPE::VertexType &v, LScalar w) {
00266 LVector p(v.cP().X(), v.cP().Y(), v.cP().Z());
00267 LVector n(v.cN().X(), v.cN().Y(), v.cN().Z());
00268
00269 sumP += p * w;
00270 sumN += n * w;
00271 sumDotPN += w * n.dot(p);
00272 sumDotPP += w * vcg::SquaredNorm(p);
00273 sumW += w;
00274 }
00275 void project(std::pair<CoordType,CoordType> &nv) const {
00276 LScalar invSumW = Scalar(1)/sumW;
00277 LScalar aux4 = beta * LScalar(0.5) *
00278 (sumDotPN - invSumW*sumP.dot(sumN))
00279 /(sumDotPP - invSumW*vcg::SquaredNorm(sumP));
00280 LVector uLinear = (sumN-sumP*(Scalar(2)*aux4))*invSumW;
00281 LScalar uConstant = -invSumW*(uLinear.dot(sumP) + sumDotPP*aux4);
00282 LScalar uQuad = aux4;
00283 LVector orig = sumP*invSumW;
00284
00285
00286 LVector position;
00287 LVector normal;
00288 if (fabs(uQuad)>1e-7)
00289 {
00290 LScalar b = 1./uQuad;
00291 LVector center = uLinear*(-0.5*b);
00292 LScalar radius = sqrt( vcg::SquaredNorm(center) - b*uConstant );
00293
00294 normal = orig - center;
00295 normal.Normalize();
00296 position = center + normal * radius;
00297
00298 normal = uLinear + position * (LScalar(2) * uQuad);
00299 normal.Normalize();
00300 }
00301 else if (uQuad==0.)
00302 {
00303 LScalar s = LScalar(1)/vcg::Norm(uLinear);
00304 assert(!vcg::math::IsNAN(s) && "normal should not have zero len!");
00305 uLinear *= s;
00306 uConstant *= s;
00307
00308 normal = uLinear;
00309 position = orig - uLinear * (orig.dot(uLinear) + uConstant);
00310 }
00311 else
00312 {
00313
00314 LScalar f = 1./sqrt(vcg::SquaredNorm(uLinear) - Scalar(4)*uConstant*uQuad);
00315 uConstant *= f;
00316 uLinear *= f;
00317 uQuad *= f;
00318
00319
00320 LVector grad;
00321 LVector dir = uLinear+orig*(2.*uQuad);
00322 LScalar ilg = 1./vcg::Norm(dir);
00323 dir *= ilg;
00324 LScalar ad = uConstant + uLinear.dot(orig) + uQuad * vcg::SquaredNorm(orig);
00325 LScalar delta = -ad*std::min<Scalar>(ilg,1.);
00326 LVector p = orig + dir*delta;
00327 for (int i=0 ; i<2 ; ++i)
00328 {
00329 grad = uLinear+p*(2.*uQuad);
00330 ilg = 1./vcg::Norm(grad);
00331 delta = -(uConstant + uLinear.dot(p) + uQuad * vcg::SquaredNorm(p))*std::min<Scalar>(ilg,1.);
00332 p += dir*delta;
00333 }
00334 position = p;
00335
00336 normal = uLinear + position * (Scalar(2) * uQuad);
00337 normal.Normalize();
00338 }
00339
00340 nv.first = CoordType(position.X(), position.Y(), position.Z());
00341 nv.second = CoordType(normal.X(), normal.Y(), normal.Z());
00342 }
00343 };
00344
00345 template<class MESH_TYPE, class METHOD_TYPE=Centroid<MESH_TYPE>, class WEIGHT_TYPE=LoopWeight<typename MESH_TYPE::ScalarType> >
00346 struct OddPointLoopGeneric : public std::unary_function<face::Pos<typename MESH_TYPE::FaceType> , typename MESH_TYPE::VertexType>
00347 {
00348 typedef METHOD_TYPE Projection;
00349 typedef WEIGHT_TYPE Weight;
00350 typedef typename MESH_TYPE::template PerVertexAttributeHandle<int> ValenceAttr;
00351 typedef typename MESH_TYPE::CoordType CoordType;
00352
00353 MESH_TYPE &m;
00354 Projection proj;
00355 Weight weight;
00356 ValenceAttr *valence;
00357
00358 inline OddPointLoopGeneric(MESH_TYPE &_m, Projection proj = Projection(), Weight weight = Weight()) :
00359 m(_m), proj(proj), weight(weight), valence(0) {}
00360
00361 void operator()(typename MESH_TYPE::VertexType &nv, face::Pos<typename MESH_TYPE::FaceType> ep) {
00362 proj.reset();
00363
00364 face::Pos<typename MESH_TYPE::FaceType> he(ep.f,ep.z,ep.f->V(ep.z));
00365 typename MESH_TYPE::VertexType *l,*r,*u,*d;
00366 l = he.v;
00367 he.FlipV();
00368 r = he.v;
00369
00370 if( tri::HasPerVertexColor(m))
00371 nv.C().lerp(ep.f->V(ep.z)->C(),ep.f->V1(ep.z)->C(),.5f);
00372
00373 if (he.IsBorder()) {
00374 proj.addVertex(*l, 0.5);
00375 proj.addVertex(*r, 0.5);
00376 std::pair<CoordType,CoordType>pp;
00377 proj.project(pp);
00378 nv.P()=pp.first;
00379 nv.N()=pp.second;
00380 }
00381 else {
00382 he.FlipE(); he.FlipV();
00383 u = he.v;
00384 he.FlipV(); he.FlipE();
00385 assert(he.v == r);
00386 he.FlipF(); he.FlipE(); he.FlipV();
00387 d = he.v;
00388
00389 if(valence && ((*valence)[l]==6 || (*valence)[r]==6)) {
00390 int extra = ((*valence)[l]==6)?(*valence)[r]:(*valence)[l];
00391 proj.addVertex(*l, ((*valence)[l]==6)?weight.incidentRegular(extra):weight.incidentIrregular(extra));
00392 proj.addVertex(*r, ((*valence)[r]==6)?weight.incidentRegular(extra):weight.incidentIrregular(extra));
00393 proj.addVertex(*u, weight.opposite(extra));
00394 proj.addVertex(*d, weight.opposite(extra));
00395 }
00396
00397 else {
00398 proj.addVertex(*l, 3.0/8.0);
00399 proj.addVertex(*r, 3.0/8.0);
00400 proj.addVertex(*u, 1.0/8.0);
00401 proj.addVertex(*d, 1.0/8.0);
00402 }
00403 std::pair<CoordType,CoordType>pp;
00404 proj.project(pp);
00405 nv.P()=pp.first;
00406 nv.N()=pp.second;
00407
00408 }
00409
00410 }
00411
00412 Color4<typename MESH_TYPE::ScalarType> WedgeInterp(Color4<typename MESH_TYPE::ScalarType> &c0, Color4<typename MESH_TYPE::ScalarType> &c1)
00413 {
00414 Color4<typename MESH_TYPE::ScalarType> cc;
00415 return cc.lerp(c0,c1,0.5f);
00416 }
00417
00418 template<class FL_TYPE>
00419 TexCoord2<FL_TYPE,1> WedgeInterp(TexCoord2<FL_TYPE,1> &t0, TexCoord2<FL_TYPE,1> &t1)
00420 {
00421 TexCoord2<FL_TYPE,1> tmp;
00422 tmp.n()=t0.n();
00423 tmp.t()=(t0.t()+t1.t())/2.0;
00424 return tmp;
00425 }
00426
00427 inline void setValenceAttr(ValenceAttr *valence) {
00428 this->valence = valence;
00429 }
00430 };
00431
00432 template<class MESH_TYPE, class METHOD_TYPE=Centroid<MESH_TYPE>, class WEIGHT_TYPE=LoopWeight<typename MESH_TYPE::ScalarType> >
00433 struct EvenPointLoopGeneric : public std::unary_function<face::Pos<typename MESH_TYPE::FaceType> , typename MESH_TYPE::VertexType>
00434 {
00435 typedef METHOD_TYPE Projection;
00436 typedef WEIGHT_TYPE Weight;
00437 typedef typename MESH_TYPE::template PerVertexAttributeHandle<int> ValenceAttr;
00438 typedef typename MESH_TYPE::CoordType CoordType;
00439
00440 Projection proj;
00441 Weight weight;
00442 ValenceAttr *valence;
00443
00444 inline EvenPointLoopGeneric(Projection proj = Projection(), Weight weight = Weight()) :
00445 proj(proj), weight(weight), valence(0) {}
00446
00447 void operator()(std::pair<CoordType,CoordType> &nv, face::Pos<typename MESH_TYPE::FaceType> ep) {
00448 proj.reset();
00449
00450 face::Pos<typename MESH_TYPE::FaceType> he(ep.f,ep.z,ep.f->V(ep.z));
00451 typename MESH_TYPE::VertexType *r, *l, *curr;
00452 curr = he.v;
00453 face::Pos<typename MESH_TYPE::FaceType> heStart = he;
00454
00455
00456 int k = 0;
00457 do {
00458 he.NextE();
00459 k++;
00460 } while(!he.IsBorder() && he != heStart);
00461
00462 if (he.IsBorder()) {
00463
00464 if(valence) {
00465 k = 0;
00466 do {
00467 he.NextE();
00468 k++;
00469 } while(!he.IsBorder());
00470 (*valence)[he.V()] = std::max(2*(k-1), 3);
00471
00472 }
00473
00474 he.FlipV();
00475 r = he.v;
00476 he.FlipV();
00477 he.NextB();
00478 l = he.v;
00479
00480 proj.addVertex(*curr, 3.0/4.0);
00481 proj.addVertex(*l, 1.0/8.0);
00482 proj.addVertex(*r, 1.0/8.0);
00483
00484 proj.project(nv);
00485
00486
00487
00488 }
00489 else {
00490
00491 if(valence)
00492 (*valence)[he.V()] = k;
00493
00494 typename MESH_TYPE::ScalarType beta = weight.beta(k);
00495
00496 proj.addVertex(*curr, 1.0 - (typename MESH_TYPE::ScalarType)(k) * beta);
00497 do {
00498 proj.addVertex(*he.VFlip(), beta);
00499 he.NextE();
00500 } while(he != heStart);
00501
00502 proj.project(nv);
00503 }
00504 }
00505
00506 Color4<typename MESH_TYPE::ScalarType> WedgeInterp(Color4<typename MESH_TYPE::ScalarType> &c0, Color4<typename MESH_TYPE::ScalarType> &c1)
00507 {
00508 Color4<typename MESH_TYPE::ScalarType> cc;
00509 return cc.lerp(c0,c1,0.5f);
00510 }
00511 Color4b WedgeInterp(Color4b &c0, Color4b &c1)
00512 {
00513 Color4b cc;
00514 cc.lerp(c0,c1,0.5f);
00515 return cc;
00516 }
00517
00518 template<class FL_TYPE>
00519 TexCoord2<FL_TYPE,1> WedgeInterp(TexCoord2<FL_TYPE,1> &t0, TexCoord2<FL_TYPE,1> &t1)
00520 {
00521 TexCoord2<FL_TYPE,1> tmp;
00522
00523 tmp.n()=t0.n();
00524 tmp.t()=(t0.t()+t1.t())/2.0;
00525 return tmp;
00526 }
00527
00528 inline void setValenceAttr(ValenceAttr *valence) {
00529 this->valence = valence;
00530 }
00531 };
00532
00533 template<class MESH_TYPE>
00534 struct OddPointLoop : OddPointLoopGeneric<MESH_TYPE, Centroid<MESH_TYPE> >
00535 {
00536 OddPointLoop(MESH_TYPE &_m):OddPointLoopGeneric<MESH_TYPE, Centroid<MESH_TYPE> >(_m){}
00537 };
00538
00539 template<class MESH_TYPE>
00540 struct EvenPointLoop : EvenPointLoopGeneric<MESH_TYPE, Centroid<MESH_TYPE> >
00541 {
00542 };
00543
00544 template<class MESH_TYPE,class ODD_VERT, class EVEN_VERT>
00545 bool RefineOddEven(MESH_TYPE &m, ODD_VERT odd, EVEN_VERT even,float length,
00546 bool RefineSelected=false, CallBackPos *cbOdd = 0, CallBackPos *cbEven = 0)
00547 {
00548 EdgeLen <MESH_TYPE, typename MESH_TYPE::ScalarType> ep(length);
00549 return RefineOddEvenE(m, odd, even, ep, RefineSelected, cbOdd, cbEven);
00550 }
00551
00555 template<class MESH_TYPE, class ODD_VERT, class EVEN_VERT, class PREDICATE>
00556 bool RefineOddEvenE(MESH_TYPE &m, ODD_VERT odd, EVEN_VERT even, PREDICATE edgePred,
00557 bool RefineSelected=false, CallBackPos *cbOdd = 0, CallBackPos *cbEven = 0)
00558 {
00559 typedef typename MESH_TYPE::template PerVertexAttributeHandle<int> ValenceAttr;
00560
00561
00562 cbEven = cbOdd;
00563
00564
00565 int evenFlag = MESH_TYPE::VertexType::NewBitFlag();
00566 for (int i = 0; i < m.vn ; i++ ) {
00567 m.vert[i].ClearUserBit(evenFlag);
00568 }
00569
00570 int j = 0;
00571
00572
00573 ValenceAttr valence = vcg::tri::Allocator<MESH_TYPE>:: template AddPerVertexAttribute<int>(m);
00574 odd.setValenceAttr(&valence);
00575 even.setValenceAttr(&valence);
00576
00577
00578 std::vector<bool> updatedList(m.vn, false);
00579
00580 std::vector<std::pair<typename MESH_TYPE::CoordType, typename MESH_TYPE::CoordType> > newEven(m.vn);
00581
00582 typename MESH_TYPE::VertexIterator vi;
00583 typename MESH_TYPE::FaceIterator fi;
00584 for (fi = m.face.begin(); fi != m.face.end(); fi++) if(!(*fi).IsD() && (!RefineSelected || (*fi).IsS())){
00585 for (int i = 0; i < 3; i++) {
00586 if ( !(*fi).V(i)->IsUserBit(evenFlag) && ! (*fi).V(i)->IsD() ) {
00587 (*fi).V(i)->SetUserBit(evenFlag);
00588
00589
00590
00591 face::Pos<typename MESH_TYPE::FaceType>aux (&(*fi),i);
00592 if( tri::HasPerVertexColor(m) ) {
00593 (*fi).V(i)->C().lerp((*fi).V0(i)->C() , (*fi).V1(i)->C(),0.5f);
00594 }
00595
00596 if (cbEven) {
00597 (*cbEven)(int(100.0f * (float)j / (float)m.fn),"Refining");
00598 j++;
00599 }
00600 int index = tri::Index(m, (*fi).V(i));
00601 updatedList[index] = true;
00602 even(newEven[index], aux);
00603 }
00604 }
00605 }
00606
00607 MESH_TYPE::VertexType::DeleteBitFlag(evenFlag);
00608
00609
00610 RefineE< MESH_TYPE, ODD_VERT > (m, odd, edgePred, RefineSelected, cbOdd);
00611 for(size_t i=0;i<newEven.size();++i) {
00612 if(updatedList[i]) {
00613 m.vert[i].P()=newEven[i].first;
00614 m.vert[i].N()=newEven[i].second;
00615 }
00616 }
00617
00618 odd.setValenceAttr(0);
00619 even.setValenceAttr(0);
00620
00621 vcg::tri::Allocator<MESH_TYPE>::DeletePerVertexAttribute(m, valence);
00622
00623 return true;
00624 }
00625
00626 }
00627 }
00628
00629
00630
00631
00632 #endif
00633
00634
00635