00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include <vcg/math/histogram.h>
00024 #include <vcg/complex/algorithms/update/curvature.h>
00025 #include <vcg/complex/algorithms/update/flag.h>
00026 #include <algorithm>
00027
00028 #ifndef VCG_TANGENT_FIELD_OPERATORS
00029 #define VCG_TANGENT_FIELD_OPERATORS
00030
00031 namespace vcg {
00032 namespace tri{
00033
00034
00035
00036
00037 template < typename ScalarType >
00038 vcg::Point2<ScalarType> InterpolateNRosy2D(const std::vector<vcg::Point2<ScalarType> > &V,
00039 const std::vector<ScalarType> &W,
00040 const int N)
00041 {
00042
00043 assert(V.size() == W.size() && N > 0);
00044
00045
00046 std::vector<ScalarType> angles(V.size(), 0);
00047
00048
00049 for (size_t i = 0; i < V.size(); i++)
00050 angles[i] = std::atan2(V[i].Y(), V[i].X() ) * N;
00051
00052
00053 std::vector<vcg::Point2<ScalarType> > VV(V.size(), vcg::Point2<ScalarType>(0,0));
00054
00055
00056 for (size_t i = 0; i < V.size(); i++) {
00057 VV[i].X() = std::cos(angles[i]);
00058 VV[i].Y() = std::sin(angles[i]);
00059 }
00060
00061
00062 vcg::Point2<ScalarType> Res(0,0);
00063
00064
00065 ScalarType Sum=0;
00066 for (size_t i = 0; i < VV.size(); i++)
00067 {
00068 Res += VV[i] * W[i];
00069 Sum+=W[i];
00070 }
00071 Res /=Sum;
00072
00073
00074
00075
00076 ScalarType a = std::atan2(Res.Y(), Res.X()) / N;
00077 Res.X() = std::cos(a);
00078 Res.Y() = std::sin(a);
00079
00080 return Res;
00081 }
00082
00083 template < typename ScalarType >
00084 vcg::Point3<ScalarType> InterpolateNRosy3D(const std::vector<vcg::Point3<ScalarType> > &V,
00085 const std::vector<vcg::Point3<ScalarType> > &Norm,
00086 const std::vector<ScalarType> &W,
00087 const int N,
00088 const vcg::Point3<ScalarType> &TargetN)
00089 {
00090 typedef typename vcg::Point3<ScalarType> CoordType;
00092 CoordType TargetZ=TargetN;
00093 TargetZ.Normalize();
00094 CoordType U=CoordType(1,0,0);
00095 if (fabs(TargetZ*U)>0.999)
00096 U=CoordType(0,1,0);
00097
00098 CoordType TargetX=TargetZ^U;
00099 CoordType TargetY=TargetX^TargetZ;
00100 TargetX.Normalize();
00101 TargetY.Normalize();
00102 vcg::Matrix33<ScalarType> RotFrame=vcg::TransformationMatrix(TargetX,TargetY,TargetZ);
00103 vcg::Matrix33<ScalarType> RotFrameInv=vcg::Inverse(RotFrame);
00104 std::vector<vcg::Point2<ScalarType> > Cross2D;
00106 for (size_t i=0;i<V.size();i++)
00107 {
00108 CoordType NF=Norm[i];
00109 NF.Normalize();
00110 CoordType Vect=V[i];
00111 Vect.Normalize();
00112
00113
00114
00116 vcg::Matrix33<ScalarType> RotNorm=vcg::RotationMatrix(Norm[i],TargetN);
00117
00118
00119
00120 CoordType rotV=RotNorm*V[i];
00121
00122 rotV.Normalize();
00123
00124
00126 rotV=RotFrame*rotV;
00127
00128 Cross2D.push_back(vcg::Point2<ScalarType>(rotV.X(),rotV.Y()));
00129
00130 }
00131
00132 vcg::Point2<ScalarType> AvDir2D=InterpolateNRosy2D(Cross2D,W,N);
00133 CoordType AvDir3D=CoordType(AvDir2D.X(),AvDir2D.Y(),0);
00134
00135 AvDir3D=RotFrameInv*AvDir3D;
00136 return AvDir3D;
00137 }
00138
00139 template <class MeshType>
00140 class CrossField
00141 {
00142 typedef typename MeshType::FaceType FaceType;
00143 typedef typename MeshType::VertexType VertexType;
00144 typedef typename MeshType::CoordType CoordType;
00145 typedef typename MeshType::ScalarType ScalarType;
00146 typedef typename vcg::face::Pos<FaceType> PosType;
00147 typedef typename vcg::Triangle3<ScalarType> TriangleType;
00148
00149 private:
00150
00151 static void SubDivideDir(const CoordType &Edge0,
00152 const CoordType &Edge1,
00153 std::vector<CoordType> &SubDEdges,
00154 int Nsub)
00155 {
00156 CoordType Dir0=Edge0;
00157 CoordType Dir1=Edge1;
00158 ScalarType a=Edge0.Norm();
00159 Dir0.Normalize();
00160 Dir1.Normalize();
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178 ScalarType BTotal=vcg::Angle(Dir0,Dir1);
00179
00180 ScalarType StepAngle=BTotal/(ScalarType)Nsub;
00181
00182 CoordType Edge2=Edge1-Edge0;
00183
00184
00185 CoordType Dir2=Edge2;
00186 Dir2.Normalize();
00187
00188 ScalarType C=vcg::Angle(Dir2,-Dir0);
00189
00190 assert(BTotal<=(M_PI));
00191 assert(BTotal>=0);
00192 assert(C<=(M_PI));
00193 assert(C>=0);
00194
00195
00196 SubDEdges.push_back(Edge0);
00197 for (size_t i=1;i<Nsub;i++)
00198 {
00199
00200 ScalarType B=StepAngle*(ScalarType)i;
00201 ScalarType A=(M_PI-C-B);
00202 assert(A<=(M_PI));
00203 assert(A>=0);
00204
00205 ScalarType b=a*sin(B)/sin(A);
00206
00207 CoordType intervB=Dir2*b;
00208
00209 intervB+=Edge0;
00210 SubDEdges.push_back(intervB);
00211 }
00212
00213 SubDEdges.push_back(Edge1);
00214 }
00215
00216 static void FindSubDir(vcg::Triangle3<ScalarType> T3,
00217 size_t Nvert,
00218 std::vector<CoordType> &SubDEdges,
00219 int Nsub)
00220 {
00221 CoordType P0=T3.P0(Nvert);
00222 CoordType P1=T3.P1(Nvert);
00223 CoordType P2=T3.P2(Nvert);
00224 P1-=P0;
00225 P2-=P0;
00226 SubDivideDir(P1,P2,SubDEdges,Nsub);
00227 for (size_t j=0;j<SubDEdges.size();j++)
00228 SubDEdges[j]+=P0;
00229 }
00230
00231 static void SubdivideTris(vcg::Triangle3<ScalarType> T3,
00232 size_t Nvert,
00233 std::vector<vcg::Triangle3<ScalarType> > &SubTris,
00234 int Nsub)
00235 {
00236 std::vector<CoordType> SplittedPos;
00237 FindSubDir(T3,Nvert,SplittedPos,Nsub);
00238 CoordType P0=T3.P(Nvert);
00239
00240 for (size_t j=0;j<SplittedPos.size()-1;j++)
00241 {
00242 TriangleType T(P0,SplittedPos[j+1],SplittedPos[j]);
00243 SubTris.push_back(T);
00244 }
00245 }
00246
00247 static ScalarType Sign(ScalarType a){return (ScalarType)((a>0)?+1:-1);}
00248
00249 static void FindSubTriangles(const typename vcg::face::Pos<FaceType> &vPos,
00250 std::vector<TriangleType> &SubFaces,
00251 std::vector<FaceType*> &OriginalFace,
00252 int numSub=3)
00253 {
00254 SubFaces.clear();
00255 OriginalFace.clear();
00256
00257
00258 assert(!vPos.IsBorder());
00259
00260 assert(vPos.F()->V(vPos.E())==vPos.V());
00261
00262
00263 std::vector<PosType> StarPos;
00264 vcg::face::VFOrderedStarFF(vPos, StarPos);
00265
00266
00267
00268 VertexType* v0=vPos.V();
00269 CoordType P0=v0->P();
00270
00271 for (size_t i = 0; i < StarPos.size(); ++i)
00272 {
00273 PosType currPos=StarPos[i];
00274 FaceType *CurrF=currPos.F();
00275 OriginalFace.push_back(CurrF);
00276
00277 VertexType *v1=CurrF->V2(currPos.E());
00278 VertexType *v2=CurrF->V1(currPos.E());
00279 CoordType P1=v1->P();
00280 CoordType P2=v2->P();
00281 assert(v1!=v2);
00282 assert(v0!=v1);
00283 assert(v0!=v2);
00284
00285 SubdivideTris(vcg::Triangle3<ScalarType>(P0,P1,P2),0,SubFaces,numSub);
00286 }
00287 }
00288
00289 static void InterpolateCrossSubTriangles(const std::vector<TriangleType> &SubFaces,
00290 const std::vector<FaceType*> &OriginalFace,
00291 std::vector<CoordType> &Dir,
00292 std::vector<CoordType> &NormSubF)
00293 {
00294 Dir.clear();
00295
00296 assert(SubFaces.size()>OriginalFace.size());
00297
00298 int SubDivisionSize=SubFaces.size()/OriginalFace.size();
00299 assert(SubDivisionSize>=3);
00300 assert(SubDivisionSize%2==1);
00301 int MiddlePos=SubDivisionSize/2+1;
00302
00303
00304 std::vector<std::pair<FaceType*,FaceType*> > InterpFaces;
00305 std::vector<ScalarType> InterpWeights;
00306
00307
00308
00309 for (size_t i=0;i<SubFaces.size();i++)
00310 {
00311
00312 int interval=i/SubDivisionSize;
00313 int sub_int=i%SubDivisionSize;
00314
00315 int IndexF0=-1,IndexF1=-1;
00316 ScalarType alpha;
00317
00318
00319 if (sub_int<MiddlePos)
00320 {
00321 IndexF0=(interval+(OriginalFace.size()-1)) % OriginalFace.size();
00322 IndexF1=interval;
00323 alpha=1-(ScalarType)(sub_int+MiddlePos)/(ScalarType)SubDivisionSize;
00324 }
00325 else
00326 if (sub_int>MiddlePos)
00327 {
00328 IndexF0=interval;
00329 IndexF1=(interval+1) % OriginalFace.size();
00330 alpha=1-(sub_int-MiddlePos)/(ScalarType)SubDivisionSize;
00331 }
00332 else
00333 {
00334 IndexF0=interval;
00335 IndexF1=(interval+1) % OriginalFace.size();
00336 alpha=1;
00337 }
00338 assert((IndexF0>=0)&&(IndexF0<OriginalFace.size()));
00339 assert((IndexF1>=0)&&(IndexF1<OriginalFace.size()));
00340
00341 FaceType* F0=OriginalFace[IndexF0];
00342 FaceType* F1=OriginalFace[IndexF1];
00343
00344 InterpFaces.push_back(std::pair<FaceType*,FaceType*>(F0,F1));
00345 InterpWeights.push_back(alpha);
00346 }
00347 assert(InterpFaces.size()==InterpWeights.size());
00348
00349 for (size_t i=0;i<InterpFaces.size();i++)
00350 {
00351 std::vector<vcg::Point3<ScalarType> > TangVect;
00352 std::vector<vcg::Point3<ScalarType> > Norms;
00353 std::vector<ScalarType> W;
00354 Norms.push_back(InterpFaces[i].first->N());
00355 Norms.push_back(InterpFaces[i].second->N());
00356 CoordType Dir0=InterpFaces[i].first->PD1();
00357 CoordType Dir1=InterpFaces[i].second->PD1();
00358 TangVect.push_back(Dir0);
00359 TangVect.push_back(Dir1);
00360 ScalarType CurrW=InterpWeights[i];
00361 W.push_back(CurrW);
00362 W.push_back(1-CurrW);
00363
00364 CoordType TargetN=InterpFaces[i].first->N();
00365 if (CurrW<0.5)
00366 TargetN=InterpFaces[i].second->N();
00367
00368 NormSubF.push_back(TargetN);
00369
00370 TargetN.Normalize();
00371 CoordType InterpD0=InterpolateNRosy3D(TangVect,Norms,W,4,TargetN);
00372
00373
00374
00375 Dir.push_back(InterpD0);
00376 }
00377 }
00378
00379 static ScalarType turn (const CoordType &norm, const CoordType &d0, const CoordType &d1)
00380 {
00381
00382 return ((d0 ^ d1).normalized() * norm);
00383 }
00384
00385 static void InterpolateDir(const CoordType &Dir0,
00386 const CoordType &Dir1,
00387 const CoordType &Sep0,
00388 const CoordType &Sep1,
00389 const TriangleType &t0,
00390 const TriangleType &t1,
00391 CoordType &Interpolated,
00392 size_t &Face)
00393 {
00394
00395 ScalarType smallestE=std::numeric_limits<ScalarType>::max();
00396 for (int j=0;j<3;j++)
00397 {
00398 ScalarType L0=(t0.P0(j)-t0.P1(j)).Norm();
00399 ScalarType L1=(t1.P0(j)-t1.P1(j)).Norm();
00400 if (L0<smallestE) smallestE=L0;
00401 if (L1<smallestE) smallestE=L1;
00402 }
00403
00404
00405 assert(t0.P(0)==t1.P(0));
00406
00407 CoordType Origin=t0.P(0);
00408 TriangleType T0Rot(CoordType(0,0,0),t0.P(1)-Origin,t0.P(2)-Origin);
00409 TriangleType T1Rot(CoordType(0,0,0),t1.P(1)-Origin,t1.P(2)-Origin);
00410
00411
00412 CoordType N0=vcg::Normal(T0Rot.cP(0),T0Rot.cP(1),T0Rot.P(2));
00413 CoordType N1=vcg::Normal(T1Rot.cP(0),T1Rot.cP(1),T1Rot.cP(2));
00414 N0.Normalize();
00415 N1.Normalize();
00416 vcg::Matrix33<ScalarType> rotation=vcg::RotationMatrix(N0,N1);
00417
00418
00419 T0Rot.P(1)=rotation*T0Rot.P(1);
00420 T0Rot.P(2)=rotation*T0Rot.P(2);
00421
00422
00423 CoordType Dir0Rot=rotation*Dir0;
00424 CoordType Dir1Rot=Dir1;
00425 CoordType Sep0Rot=rotation*Sep0;
00426 CoordType Sep1Rot=Sep1;
00427
00428
00429 ScalarType Angle0=vcg::Angle(Dir0Rot,Sep0Rot);
00430 ScalarType Angle1=vcg::Angle(Dir1Rot,Sep1Rot);
00431 assert(Angle0>=0);
00432 assert(Angle1>=0);
00433 assert(Angle0<=(M_PI/2));
00434 assert(Angle1<=(M_PI/2));
00435 ScalarType alpha=0.5;
00436
00437
00438
00439 Interpolated=Sep0Rot*(1-alpha)+Sep1Rot*alpha;
00440 Interpolated.Normalize();
00441 Interpolated*=smallestE;
00442
00443
00444 CoordType bary0,bary1;
00445 bool Inside0=vcg::InterpolationParameters(T0Rot,Interpolated,bary0);
00446 bool Inside1=vcg::InterpolationParameters(T1Rot,Interpolated,bary1);
00447 assert(Inside0 || Inside1);
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457 if (Inside0)
00458 {
00459 Interpolated=t0.P(0)*bary0.X()+t0.P(1)*bary0.Y()+t0.P(2)*bary0.Z();
00460 Interpolated-=Origin;
00461 Face=0;
00462 }
00463 else
00464 Face=1;
00465
00466
00467 Interpolated.Normalize();
00468 }
00469
00470 static void ReduceOneDirectionField(std::vector<CoordType> &directions,
00471 std::vector<FaceType*> &faces)
00472 {
00473
00474 std::vector<ScalarType> DirProd;
00475 ScalarType MaxProd=-1;
00476 int MaxInd0=-1,MaxInd1=-1;
00477 for (size_t i=0;i<directions.size();i++)
00478 {
00479 ScalarType prod=0;
00480 for (size_t j=1;j<directions.size();j++)
00481 {
00482 int Index0=i;
00483 int Index1=(i+j)%directions.size();
00484 CoordType Dir0=directions[Index0];
00485 CoordType Dir1=directions[Index1];
00486 ScalarType currP=(Dir0*Dir1);
00487 if (currP>MaxProd)
00488 {
00489 MaxProd=currP;
00490 MaxInd0=Index0;
00491 MaxInd1=Index1;
00492 }
00493 prod+=currP;
00494 }
00495 DirProd.push_back(prod);
00496 }
00497 assert(MaxInd0!=MaxInd1);
00498
00499
00500 int IndexDel=MaxInd0;
00501 if (DirProd[MaxInd1]>DirProd[MaxInd0])IndexDel=MaxInd1;
00502
00503 std::vector<CoordType> SwapV(directions.begin(),directions.end());
00504 std::vector<FaceType*> SwapF(faces.begin(),faces.end());
00505
00506 directions.clear();
00507 faces.clear();
00508
00509 for (size_t i=0;i<SwapV.size();i++)
00510 {
00511 if (i==IndexDel)continue;
00512 directions.push_back(SwapV[i]);
00513 faces.push_back(SwapF[i]);
00514 }
00515 }
00516
00517 public:
00518
00519 static size_t FindSeparatrices(const typename vcg::face::Pos<FaceType> &vPos,
00520 std::vector<CoordType> &directions,
00521 std::vector<FaceType*> &faces,
00522 std::vector<TriangleType> &WrongTris,
00523 int expVal=-1,
00524 int numSub=3)
00525 {
00526
00527 directions.clear();
00528
00529
00530 assert(!vPos.IsBorder());
00531
00532 assert(vPos.F()->V(vPos.E())==vPos.V());
00533
00534 std::vector<TriangleType> SubFaces;
00535 std::vector<CoordType> Dir1,Dir2;
00536 std::vector<CoordType> Norms;
00537 std::vector<FaceType*> OriginalFaces;
00538
00539
00540 FindSubTriangles(vPos,SubFaces,OriginalFaces,numSub);
00541
00542
00543 InterpolateCrossSubTriangles(SubFaces,OriginalFaces,Dir1,Norms);
00544
00545
00546 for (size_t i=0;i<Dir1.size();i++)
00547 {
00548 CoordType TargetN=Norms[i];
00549 CoordType CrossDir2=Dir1[i]^TargetN;
00550 CrossDir2.Normalize();
00551 Dir2.push_back(CrossDir2);
00552 }
00553
00554
00555 CoordType CenterStar=vPos.V()->P();
00556 for (size_t i = 0; i < SubFaces.size(); ++i)
00557 {
00558 TriangleType t0=SubFaces[i];
00559 TriangleType t1=SubFaces[(i+1)%SubFaces.size()];
00560 CoordType N0=Norms[i];
00561 CoordType N1=Norms[(i+1)%Norms.size()];
00562 N0.Normalize();
00563 N1.Normalize();
00564
00565 std::vector<CoordType> SubDEdges0;
00566 std::vector<CoordType> SubDEdges1;
00567 FindSubDir(t0,0,SubDEdges0,2);
00568 FindSubDir(t1,0,SubDEdges1,2);
00569 CoordType Bary0=SubDEdges0[1];
00570 CoordType Bary1=SubDEdges1[1];
00571
00572 Bary0-=CenterStar;
00573 Bary1-=CenterStar;
00574 Bary0.Normalize();
00575 Bary1.Normalize();
00576
00577
00578 CoordType Dir1F0=Dir1[i];
00579 CoordType Dir2F0=Dir2[i];
00580
00581 assert(fabs(Dir1F0*N0)<0.001);
00582 assert(fabs(Dir1F0*Dir2F0)<0.001);
00583
00584 if ((Dir1F0*Bary0)<0)Dir1F0=-Dir1F0;
00585 if ((Dir2F0*Bary0)<0)Dir2F0=-Dir2F0;
00586
00587 CoordType Dir1F1=Dir1[(i+1)%Dir1.size()];
00588 CoordType Dir2F1=Dir2[(i+1)%Dir2.size()];
00589
00590 assert(fabs(Dir1F1*N1)<0.001);
00591 assert(fabs(Dir1F1*Dir2F1)<0.01);
00592
00593
00594 vcg::Matrix33<ScalarType> rotation=vcg::RotationMatrix(N0,N1);
00595 CoordType Dir1F0R=rotation*Dir1F0;
00596 CoordType Dir2F0R=rotation*Dir2F0;
00597
00598
00599 Dir1F1=vcg::tri::CrossField<MeshType>::K_PI(Dir1F1,Dir1F0R,N1);
00600 Dir2F1=vcg::tri::CrossField<MeshType>::K_PI(Dir2F1,Dir2F0R,N1);
00601
00602
00603 ScalarType versef0D1 = turn(N0, Bary0, Dir1F0);
00604 ScalarType versef1D1 = turn(N1, Bary1, Dir1F1);
00605 ScalarType versef0D2 = turn(N0, Bary0, Dir2F0);
00606 ScalarType versef1D2 = turn(N1, Bary1, Dir2F1);
00607
00608 if ((Bary0*Bary1)<0)
00609 {
00610
00611 WrongTris.push_back(t0);
00612 WrongTris.push_back(t1);
00613 }
00614
00615
00616 CoordType InterpDir;
00617 size_t tri_Index=-1;
00618 if ((versef0D1 * versef1D1) < ScalarType(0))
00619 {
00620 InterpolateDir(Dir1F0,Dir1F1,Bary0,Bary1,t0,t1,InterpDir,tri_Index);
00621 }
00622 else
00623 {
00624 if ((versef0D2 * versef1D2 )< ScalarType(0))
00625 InterpolateDir(Dir2F0,Dir2F1,Bary0,Bary1,t0,t1,InterpDir,tri_Index);
00626 }
00627
00628 if (tri_Index==-1)continue;
00629
00630
00631 assert((tri_Index==0)||(tri_Index==1));
00632 int OrigFIndex=((i+tri_Index)%SubFaces.size())/numSub;
00633 assert(OrigFIndex>=0);
00634 assert(OrigFIndex<OriginalFaces.size());
00635
00636 FaceType* currF=OriginalFaces[OrigFIndex];
00637
00638 directions.push_back(InterpDir);
00639 faces.push_back(currF);
00640 }
00641 if (expVal==-1)return directions.size();
00642 if (directions.size()<=expVal)return directions.size();
00643
00644 size_t sampledDir=directions.size();
00645 int to_erase=directions.size()-expVal;
00646 do
00647 {
00648 ReduceOneDirectionField(directions,faces);
00649 to_erase--;
00650 }while (to_erase!=0);
00651 return sampledDir;
00652 }
00653
00654 static CoordType FollowDirection(const FaceType &f0,
00655 const FaceType &f1,
00656 const CoordType &dir0)
00657 {
00659 CoordType dirR=vcg::tri::CrossField<MeshType>::Rotate(f0,f1,dir0);
00661 CoordType dir1=f1.cPD1();
00662 CoordType ret=vcg::tri::CrossField<MeshType>::K_PI(dir1,dirR,f1.cN());
00663 return ret;
00664 }
00665
00666 static int FollowDirectionI(const FaceType &f0,
00667 const FaceType &f1,
00668 const CoordType &dir0)
00669 {
00671 CoordType dirTarget=FollowDirection(f0,f1,dir0);
00672 CoordType dir[4];
00673 CrossVector(f1,dir);
00674 ScalarType best=-1;
00675 int ret=-1;
00676 for (int i=0;i<4;i++)
00677 {
00678 ScalarType dot=dir[i]*dirTarget;
00679 if (dot>best)
00680 {
00681 best=dot;
00682 ret=i;
00683 }
00684 }
00685 assert(ret!=-1);
00686
00687 return ret;
00688 }
00689
00690 static int FollowDirection(const FaceType &f0,
00691 const FaceType &f1,
00692 int dir0)
00693 {
00695 CoordType dirS=CrossVector(f0,dir0);
00696 CoordType dirR=vcg::tri::CrossField<MeshType>::Rotate(f0,f1,dirS);
00698 CoordType dir1=f1.cPD1();
00699
00700 CoordType dir[4];
00701 CrossVector(f1,dir);
00702 ScalarType best=-1;
00703 int ret=-1;
00704 for (int i=0;i<4;i++)
00705 {
00706 ScalarType dot=dir[i]*dirR;
00707 if (dot>best)
00708 {
00709 best=dot;
00710 ret=i;
00711 }
00712 }
00713 assert(ret!=-1);
00714
00715 return ret;
00716 }
00717
00718 static int FollowLineDirection(const FaceType &f0,
00719 const FaceType &f1,
00720 int dir)
00721 {
00723 CoordType dir0=CrossVector(f0,dir);
00724 CoordType dir0R=vcg::tri::CrossField<MeshType>::Rotate(f0,f1,dir0);
00726 CoordType dir1_test=CrossVector(f1,dir);
00727 CoordType dir2_test=-dir1_test;
00728 if ((dir1_test*dir0R)>(dir2_test*dir0R))
00729 return dir;
00730 return ((dir+2)%4);
00731
00732 }
00733
00737 static vcg::Matrix33<ScalarType> TransformationMatrix(const FaceType &f)
00738 {
00739 typedef typename FaceType::CoordType CoordType;
00740 typedef typename FaceType::ScalarType ScalarType;
00741
00743 CoordType axis0=f.cPD1();
00744 CoordType axis1=f.cPD2();
00745 CoordType axis2=f.cN();
00746
00747 return (vcg::TransformationMatrix(axis0,axis1,axis2));
00748 }
00749
00750
00753 static CoordType TangentAngleToVect(const FaceType &f,const ScalarType &angle)
00754 {
00756 vcg::Point2<ScalarType> axis2D=vcg::Point2<ScalarType>(cos(angle),sin(angle));
00757 CoordType axis3D=CoordType(axis2D.X(),axis2D.Y(),0);
00758 vcg::Matrix33<ScalarType> Trans=TransformationMatrix(f);
00759 vcg::Matrix33<ScalarType> InvTrans=Inverse(Trans);
00761 return (InvTrans*axis3D);
00762 }
00763
00766 static ScalarType TangentVectToAngle(const CoordType dirX,
00767 const CoordType dirZ,
00768 const CoordType &vect3D)
00769 {
00770 const CoordType dirY=dirX^dirZ;
00771 dirX.Normalize();
00772 dirY.Normalize();
00773 dirZ.Normalize();
00774 vcg::Matrix33<ScalarType> Trans=TransformationMatrix(dirX,dirY,dirZ);
00776 CoordType vect_transf=Trans*vect3D;
00777
00779 vcg::Point2<ScalarType> axis2D=vcg::Point2<ScalarType>(vect_transf.X(),vect_transf.Y());
00780 axis2D.Normalize();
00781
00783 ScalarType alpha=atan2(axis2D.Y(),axis2D.X());
00784 if (alpha<0)
00785 alpha=(2*M_PI+alpha);
00786 if (alpha<0)
00787 alpha=0;
00788 return alpha;
00789 }
00790
00792 static ScalarType VectToAngle(const FaceType &f,const CoordType &vect3D)
00793 {
00794 vcg::Matrix33<ScalarType> Trans=TransformationMatrix(f);
00795
00797 CoordType vect_transf=Trans*vect3D;
00798
00800 vcg::Point2<ScalarType> axis2D=vcg::Point2<ScalarType>(vect_transf.X(),vect_transf.Y());
00801 axis2D.Normalize();
00802
00804 ScalarType alpha=atan2(axis2D.Y(),axis2D.X());
00805 if (alpha<0)
00806 alpha=(2*M_PI+alpha);
00807 if (alpha<0)
00808 alpha=0;
00809 return alpha;
00810 }
00811
00813 static void CrossFieldToAngles(const FaceType &f,
00814 ScalarType &alpha1,
00815 ScalarType &alpha2,
00816 int RefEdge=1)
00817 {
00818 CoordType axis0=f.cP1(RefEdge)-f.cP0(RefEdge);
00819 axis0.Normalize();
00820 CoordType axis2=f.cN();
00821 axis2.Normalize();
00822 CoordType axis1=axis2^axis0;
00823 axis1.Normalize();
00824
00825
00826 vcg::Matrix33<ScalarType> Trans=vcg::TransformationMatrix(axis0,axis1,axis2);
00827
00828
00829 CoordType trasfPD1=Trans*f.cPD1();
00830 CoordType trasfPD2=Trans*f.cPD2();
00831
00832
00833 alpha1=atan2(trasfPD1.Y(),trasfPD1.X());
00834 alpha2=atan2(trasfPD2.Y(),trasfPD2.X());
00835 }
00836
00838 static void AnglesToCrossField(FaceType &f,
00839 const ScalarType &alpha1,
00840 const ScalarType &alpha2,
00841 int RefEdge=1)
00842 {
00843 CoordType axis0=f.cP1(RefEdge)-f.cP0(RefEdge);
00844 axis0.Normalize();
00845 CoordType axis2=f.cN();
00846 axis2.Normalize();
00847 CoordType axis1=axis2^axis0;
00848 axis1.Normalize();
00849
00850 vcg::Matrix33<ScalarType> Trans=vcg::TransformationMatrix(axis0,axis1,axis2);
00851 vcg::Matrix33<ScalarType> InvTrans=Inverse(Trans);
00852
00853 CoordType PD1=CoordType(cos(alpha1),sin(alpha1),0);
00854 CoordType PD2=CoordType(cos(alpha2),sin(alpha2),0);
00855
00856
00857 f.PD1()=(InvTrans*PD1);
00858 f.PD2()=(InvTrans*PD2);
00859 }
00860
00863 static void CrossVector(const CoordType &dir0,
00864 const CoordType &norm,
00865 CoordType axis[4])
00866 {
00867 axis[0]=dir0;
00868 axis[1]=norm^axis[0];
00869 axis[2]=-axis[0];
00870 axis[3]=-axis[1];
00871 }
00872
00875 static void CrossVector(const FaceType &f,
00876 CoordType axis[4])
00877 {
00878 CoordType dir0=f.cPD1();
00879 CoordType dir1=f.cPD2();
00880 axis[0]=dir0;
00881 axis[1]=dir1;
00882 axis[2]=-dir0;
00883 axis[3]=-dir1;
00884 }
00885
00888 static void CrossVector(const VertexType &v,
00889 CoordType axis[4])
00890 {
00891 CoordType dir0=v.cPD1();
00892 CoordType dir1=v.cPD2();
00893 axis[0]=dir0;
00894 axis[1]=dir1;
00895 axis[2]=-dir0;
00896 axis[3]=-dir1;
00897 }
00898
00901 static CoordType CrossVector(const FaceType &f,
00902 const int &index)
00903 {
00904 assert((index>=0)&&(index<4));
00905 CoordType axis[4];
00906 CrossVector(f,axis);
00907 return axis[index];
00908 }
00909
00912 static CoordType CrossVector(const VertexType &v,
00913 const int &index)
00914 {
00915 assert((index>=0)&&(index<4));
00916 CoordType axis[4];
00917 CrossVector(v,axis);
00918 return axis[index];
00919 }
00920
00922 static void SetCrossVector(FaceType &f,
00923 CoordType dir0,
00924 CoordType dir1)
00925 {
00926 f.PD1()=dir0;
00927 f.PD2()=dir1;
00928 }
00929
00931 static void SetFaceCrossVectorFromVert(FaceType &f)
00932 {
00933 const CoordType &t0=f.V(0)->PD1();
00934 const CoordType &t1=f.V(1)->PD1();
00935 const CoordType &t2=f.V(2)->PD1();
00936 const CoordType &N0=f.V(0)->N();
00937 const CoordType &N1=f.V(0)->N();
00938 const CoordType &N2=f.V(0)->N();
00939 const CoordType &NF=f.N();
00940 const CoordType bary=CoordType(0.33333,0.33333,0.33333);
00941 CoordType tF0,tF1;
00942 tF0=InterpolateCrossField(t0,t1,t2,N0,N1,N2,NF,bary);
00943 tF1=NF^tF0;
00944 tF0.Normalize();
00945 tF1.Normalize();
00946 SetCrossVector(f,tF0,tF1);
00947
00948
00949 ScalarType mag1,mag2;
00950 for (int i=0;i<3;i++)
00951 {
00952 vcg::Matrix33<ScalarType> rotN=vcg::RotationMatrix(f.V(i)->N(),f.N());
00953 CoordType rotatedDir=rotN*f.V(i)->PD1();
00954
00955 if (fabs(rotatedDir*tF0)>fabs(rotatedDir*tF1))
00956 {
00957 mag1+=fabs(f.V(i)->K1());
00958 mag2+=fabs(f.V(i)->K2());
00959 }
00960 else
00961 {
00962 mag1+=fabs(f.V(i)->K2());
00963 mag2+=fabs(f.V(i)->K1());
00964 }
00965 }
00966
00967 f.K1()=mag1/(ScalarType)3;
00968 f.K2()=mag2/(ScalarType)3;
00969
00970 }
00971
00972 static void SetFaceCrossVectorFromVert(MeshType &mesh)
00973 {
00974 for (unsigned int i=0;i<mesh.face.size();i++)
00975 {
00976 FaceType *f=&mesh.face[i];
00977 if (f->IsD())continue;
00978 SetFaceCrossVectorFromVert(*f);
00979 }
00980 }
00981
00983 static void SetVertCrossVectorFromFace(VertexType &v)
00984 {
00985 std::vector<FaceType *> faceVec;
00986 std::vector<int> index;
00987 vcg::face::VFStarVF(&v,faceVec,index);
00988 std::vector<CoordType> TangVect;
00989 std::vector<CoordType> Norms;
00990 for (unsigned int i=0;i<faceVec.size();i++)
00991 {
00992 TangVect.push_back(faceVec[i]->PD1());
00993 Norms.push_back(faceVec[i]->N());
00994 }
00995 std::vector<ScalarType> Weights(TangVect.size(),1.0/(ScalarType)TangVect.size());
00996 CoordType NRef=v.N();
00997 CoordType N0=faceVec[0]->N();
00998 CoordType DirRef=faceVec[0]->PD1();
01000 vcg::Matrix33<ScalarType> rotation=vcg::RotationMatrix(N0,NRef);
01001 DirRef=rotation*DirRef;
01002
01003
01004 CoordType tF1=vcg::tri::CrossField<MeshType>::InterpolateCrossField(TangVect,Weights,Norms,NRef);
01005 tF1.Normalize();
01006 CoordType tF2=NRef^tF1;
01007 tF2.Normalize();
01008 v.PD1()=tF1;
01009 v.PD2()=tF2;
01010 }
01011
01012 static void SetVertCrossVectorFromFace(MeshType &mesh)
01013 {
01014 for (unsigned int i=0;i<mesh.vert.size();i++)
01015 {
01016 VertexType *v=&mesh.vert[i];
01017 if (v->IsD())continue;
01018 SetVertCrossVectorFromFace(*v);
01019 }
01020 }
01021
01024 static CoordType Rotate(const FaceType &f0,const FaceType &f1,const CoordType &dir3D)
01025 {
01026 CoordType N0=f0.cN();
01027 CoordType N1=f1.cN();
01028
01030 vcg::Matrix33<ScalarType> rotation=vcg::RotationMatrix(N0,N1);
01031 CoordType rotated=rotation*dir3D;
01032 return rotated;
01033 }
01034
01035
01037 static CoordType K_PI(const CoordType &a, const CoordType &b, const CoordType &n)
01038 {
01039 CoordType c = (a^n).normalized();
01040 ScalarType scorea = a*b;
01041 ScalarType scorec = c*b;
01042 if (fabs(scorea)>=fabs(scorec)) return a*Sign(scorea); else return c*Sign(scorec);
01043 }
01044
01045
01047 static int I_K_PI(const CoordType &a, const CoordType &b, const CoordType &n)
01048 {
01049 CoordType c = (n^a).normalized();
01050 ScalarType scorea = a*b;
01051 ScalarType scorec = c*b;
01052 if (fabs(scorea)>=fabs(scorec))
01053 {
01054 if (scorea>0)return 0;
01055 return 2;
01056 }else
01057 {
01058 if (scorec>0)return 1;
01059 return 3;
01060 }
01061 }
01062
01064 static CoordType InterpolateCrossField(const CoordType &t0,
01065 const CoordType &t1,
01066 const CoordType &t2,
01067 const CoordType &n0,
01068 const CoordType &n1,
01069 const CoordType &n2,
01070 const CoordType &target_n,
01071 const CoordType &bary)
01072 {
01073 std::vector<CoordType > V,Norm;
01074 std::vector<ScalarType > W;
01075 V.push_back(t0);
01076 V.push_back(t1);
01077 V.push_back(t2);
01078 Norm.push_back(n0);
01079 Norm.push_back(n1);
01080 Norm.push_back(n2);
01081 W.push_back(bary.X());
01082 W.push_back(bary.Y());
01083 W.push_back(bary.Z());
01084
01085 CoordType sum=vcg::tri::InterpolateNRosy3D(V,Norm,W,4,target_n);
01086 return sum;
01087 }
01088
01090 static CoordType InterpolateCrossField(const std::vector<CoordType> &TangVect,
01091 const std::vector<ScalarType> &Weight,
01092 const std::vector<CoordType> &Norms,
01093 const CoordType &BaseNorm)
01094 {
01095
01096 CoordType sum=InterpolateNRosy3D(TangVect,Norms,Weight,4,BaseNorm);
01097 return sum;
01098 }
01099
01101 static typename FaceType::CoordType InterpolateCrossFieldLine(const typename FaceType::CoordType &t0,
01102 const typename FaceType::CoordType &t1,
01103 const typename FaceType::CoordType &n0,
01104 const typename FaceType::CoordType &n1,
01105 const typename FaceType::CoordType &target_n,
01106 const typename FaceType::ScalarType &weight)
01107 {
01108 std::vector<CoordType > V,Norm;
01109 std::vector<ScalarType > W;
01110 V.push_back(t0);
01111 V.push_back(t1);
01112 Norm.push_back(n0);
01113 Norm.push_back(n1);
01114 W.push_back(weight);
01115 W.push_back(1-weight);
01116 InterpolateNRosy3D(V,Norm,&W,4,target_n);
01117 }
01118
01119
01121 static typename FaceType::ScalarType DifferenceCrossField(const typename FaceType::CoordType &t0,
01122 const typename FaceType::CoordType &t1,
01123 const typename FaceType::CoordType &n)
01124 {
01125 CoordType trans0=t0;
01126 CoordType trans1=K_PI(t1,t0,n);
01127 ScalarType diff = 1-fabs(trans0*trans1);
01128 return diff;
01129 }
01130
01132 static typename FaceType::ScalarType DifferenceCrossField(const typename vcg::Point2<ScalarType> &t0,
01133 const typename vcg::Point2<ScalarType> &t1)
01134 {
01135 CoordType t03D=CoordType(t0.X(),t0.Y(),0);
01136 CoordType t13D=CoordType(t1.X(),t1.Y(),0);
01137 CoordType trans0=t03D;
01138 CoordType n=CoordType(0,0,1);
01139 CoordType trans1=K_PI(t13D,t03D,n);
01140 ScalarType diff = 1-fabs(trans0*trans1);
01141 return diff;
01142 }
01143
01146 static int MissMatchByCross(const CoordType &dir0,
01147 const CoordType &dir1,
01148 const CoordType &N0,
01149 const CoordType &N1)
01150 {
01151 CoordType dir0Rot=Rotate(dir0,N0,N1);
01152 CoordType dir1Rot=dir1;
01153
01154 dir0Rot.Normalize();
01155 dir1Rot.Normalize();
01156
01157 ScalarType angle_diff=VectToAngle(dir0Rot,N0,dir1Rot);
01158
01159 ScalarType step=M_PI/2.0;
01160 int i=(int)floor((angle_diff/step)+0.5);
01161 int k=0;
01162 if (i>=0)
01163 k=i%4;
01164 else
01165 k=(-(3*i))%4;
01166 return k;
01167 }
01168
01170 static int MissMatchByCross(const FaceType &f0,
01171 const FaceType &f1)
01172 {
01173
01174 CoordType dir1=CrossVector(f1,0);
01175
01176 CoordType dir1Rot=Rotate(f1,f0,dir1);
01177 dir1Rot.Normalize();
01178
01179 ScalarType angle_diff=VectToAngle(f0,dir1Rot);
01180
01181 ScalarType step=M_PI/2.0;
01182 int i=(int)floor((angle_diff/step)+0.5);
01183 int k=0;
01184 if (i>=0)
01185 k=i%4;
01186 else
01187 k=(-(3*i))%4;
01188 return k;
01189 }
01190
01191
01194 static bool IsSingularByCross(const VertexType &v,int &missmatch)
01195 {
01196 typedef typename VertexType::FaceType FaceType;
01198 if (v.IsB())return false;
01199
01200 std::vector<face::Pos<FaceType> > posVec;
01201
01202 face::Pos<FaceType> pos(v.cVFp(), v.cVFi());
01203 vcg::face::VFOrderedStarFF(pos, posVec);
01204
01205 int curr_dir=0;
01206 for (unsigned int i=0;i<posVec.size();i++)
01207 {
01208 FaceType *curr_f=posVec[i].F();
01209 FaceType *next_f=posVec[(i+1)%posVec.size()].F();
01210
01211
01212 curr_dir=FollowDirection(*curr_f,*next_f,curr_dir);
01213 }
01214 missmatch=curr_dir;
01215 return(curr_dir!=0);
01216 }
01217
01219 static void UpdateSingularByCross(MeshType &mesh)
01220 {
01221 bool hasSingular = vcg::tri::HasPerVertexAttribute(mesh,std::string("Singular"));
01222 bool hasSingularIndex = vcg::tri::HasPerVertexAttribute(mesh,std::string("SingularIndex"));
01223
01224 typename MeshType::template PerVertexAttributeHandle<bool> Handle_Singular;
01225 typename MeshType::template PerVertexAttributeHandle<int> Handle_SingularIndex;
01226
01227 if (hasSingular)
01228 Handle_Singular=vcg::tri::Allocator<MeshType>::template GetPerVertexAttribute<bool>(mesh,std::string("Singular"));
01229 else
01230 Handle_Singular=vcg::tri::Allocator<MeshType>::template AddPerVertexAttribute<bool>(mesh,std::string("Singular"));
01231
01232 if (hasSingularIndex)
01233 Handle_SingularIndex=vcg::tri::Allocator<MeshType>::template GetPerVertexAttribute<int>(mesh,std::string("SingularIndex"));
01234 else
01235 Handle_SingularIndex=vcg::tri::Allocator<MeshType>::template AddPerVertexAttribute<int>(mesh,std::string("SingularIndex"));
01236
01237 for (size_t i=0;i<mesh.vert.size();i++)
01238 {
01239 if (mesh.vert[i].IsD())continue;
01240
01241
01242 int missmatch;
01243 if (IsSingularByCross(mesh.vert[i],missmatch))
01244 {
01245 Handle_Singular[i]=true;
01246 Handle_SingularIndex[i]=missmatch;
01247 }
01248 else
01249 {
01250 Handle_Singular[i]=false;
01251 Handle_SingularIndex[i]=0;
01252 }
01253 }
01254 }
01255
01256
01257 static void GradientToCross(const FaceType &f,
01258 const vcg::Point2<ScalarType> &UV0,
01259 const vcg::Point2<ScalarType> &UV1,
01260 const vcg::Point2<ScalarType> &UV2,
01261 CoordType &dirU,
01262 CoordType &dirV)
01263 {
01264 vcg::Point2<ScalarType> Origin2D=(UV0+UV1+UV2)/3;
01265 CoordType Origin3D=(f.cP(0)+f.cP(1)+f.cP(2))/3;
01266
01267 vcg::Point2<ScalarType> UvT0=UV0-Origin2D;
01268 vcg::Point2<ScalarType> UvT1=UV1-Origin2D;
01269 vcg::Point2<ScalarType> UvT2=UV2-Origin2D;
01270
01271 CoordType PosT0=f.cP(0)-Origin3D;
01272 CoordType PosT1=f.cP(1)-Origin3D;
01273 CoordType PosT2=f.cP(2)-Origin3D;
01274
01275 CoordType Bary0,Bary1;
01276 vcg::InterpolationParameters2(UvT0,UvT1,UvT2,vcg::Point2<ScalarType>(1,0),Bary0);
01277 vcg::InterpolationParameters2(UvT0,UvT1,UvT2,vcg::Point2<ScalarType>(0,1),Bary1);
01278
01279
01280 dirU=PosT0*Bary0.X()+PosT1*Bary0.Y()+PosT2*Bary0.Z();
01281 dirV=PosT0*Bary1.X()+PosT1*Bary1.Y()+PosT2*Bary1.Z();
01282
01283
01284
01285 dirU.Normalize();
01286 dirV.Normalize();
01287
01288 CoordType Ntest=dirU^dirV;
01289 CoordType NTarget=vcg::Normal(f.cP(0),f.cP(1),f.cP(2));
01290 if ((Ntest*NTarget)<0)dirV=-dirV;
01291
01292
01293
01294 CoordType dirVTarget=NTarget^dirU;
01295 CoordType dirUTarget=NTarget^dirV;
01296
01297 dirUTarget.Normalize();
01298 dirVTarget.Normalize();
01299 if ((dirUTarget*dirU)<0)dirUTarget=-dirUTarget;
01300 if ((dirVTarget*dirV)<0)dirVTarget=-dirVTarget;
01301
01302 dirU=(dirU+dirUTarget)/2;
01303 dirV=(dirV+dirVTarget)/2;
01304
01305 dirU.Normalize();
01306 dirV.Normalize();
01307
01308
01309
01310
01311
01312
01313
01314
01315
01316
01317
01318
01319
01320
01321
01322 }
01323
01324 static void MakeDirectionFaceCoherent(FaceType *f0,
01325 FaceType *f1)
01326 {
01327 CoordType dir0=f0->PD1();
01328 CoordType dir1=f1->PD1();
01329
01330 CoordType dir0Rot=Rotate(*f0,*f1,dir0);
01331 dir0Rot.Normalize();
01332
01333 CoordType targD=K_PI(dir1,dir0Rot,f1->N());
01334
01335 f1->PD1()=targD;
01336 f1->PD2()=f1->N()^targD;
01337 f1->PD2().Normalize();
01338 }
01339
01340 static void AdjustDirectionsOnTangentspace(MeshType &mesh)
01341 {
01342 for (size_t i=0;i<mesh.face.size();i++)
01343 {
01344 FaceType *f=&mesh.face[i];
01345 if (f->IsD())continue;
01346 CoordType Ntest=mesh.face[i].PD1()^mesh.face[i].PD2();
01347 Ntest.Normalize();
01348 CoordType Ntarget=mesh.face[i].N();
01349 if ((Ntest*Ntarget)>0.999)continue;
01350
01351
01352 vcg::Matrix33<ScalarType> rotation=vcg::RotationMatrix(Ntest,Ntarget);
01353 mesh.face[i].PD1()=rotation*mesh.face[i].PD1();
01354 mesh.face[i].PD2()=rotation*mesh.face[i].PD2();
01355 }
01356 }
01357
01358 static void OrientDirectionFaceCoherently(MeshType &mesh)
01359 {
01360 for (size_t i=0;i<mesh.face.size();i++)
01361 {
01362 FaceType *f=&mesh.face[i];
01363 if (f->IsD())continue;
01364 CoordType Ntest= CoordType::Construct( mesh.face[i].PD1()^mesh.face[i].PD2() );
01365 if ((Ntest*vcg::Normal(f->P(0),f->P(1),f->P(2)))<0)mesh.face[i].PD2()=-mesh.face[i].PD2();
01366 }
01367 }
01368
01369 static void MakeDirectionFaceCoherent(MeshType &mesh,
01370 bool normal_diff=true)
01371 {
01372 vcg::tri::UpdateFlags<MeshType>::FaceClearV(mesh);
01373 vcg::tri::UpdateTopology<MeshType>::FaceFace(mesh);
01374
01375 typedef typename std::pair<FaceType*,FaceType*> FacePair;
01376 std::vector<std::pair<ScalarType,FacePair> > heap;
01377
01378 while (true)
01379 {
01380 bool found=false;
01381 for (int i=0; i<(int)mesh.face.size(); i++)
01382 {
01383 FaceType *f=&(mesh.face[i]);
01384 if (f->IsD())continue;
01385 if (f->IsV())continue;
01386 f->SetV();
01387 found=true;
01388
01389 for (int i=0;i<f->VN();i++)
01390 {
01391 FaceType *Fopp=f->FFp(i);
01392 if (Fopp==f)continue;
01393
01394 FacePair entry(f,Fopp);
01395
01396 ScalarType val=0;
01397 if (normal_diff)val=-(f->N()-Fopp->N()).Norm();
01398
01399 heap.push_back(std::pair<ScalarType,FacePair>(val,entry));
01400 }
01401 break;
01402 }
01403
01404 if (!found)
01405 {
01406
01407 vcg::tri::UpdateFlags<MeshType>::FaceClearV(mesh);
01408 return;
01409 }
01410
01411 std::make_heap (heap.begin(),heap.end());
01412
01413 while (!heap.empty())
01414 {
01415 std::pop_heap(heap.begin(), heap.end());
01416 FaceType *f0=heap.back().second.first;
01417 FaceType *f1=heap.back().second.second;
01418 assert(f0->IsV());
01419 heap.pop_back();
01420
01421 MakeDirectionFaceCoherent(f0,f1);
01422 f1->SetV();
01423 for (int k=0; k<f1->VN(); k++)
01424 {
01425 FaceType* f2 = f1->FFp(k);
01426 if (f2->IsV())continue;
01427 if (f2->IsD())continue;
01428 if (f2==f1)continue;
01429
01430 FacePair entry(f1,f2);
01431
01432 ScalarType val=0;
01433 if (normal_diff)val=-(f1->N()-f2->N()).Norm();
01434
01435 heap.push_back(std::pair<ScalarType,FacePair>(val,entry));
01436 std::push_heap (heap.begin(),heap.end());
01437 }
01438 }
01439 }
01440
01441 }
01442
01444 static vcg::Point2<ScalarType> CrossToUV(FaceType &f,int numD=0)
01445 {
01446 typedef typename FaceType::ScalarType ScalarType;
01447 typedef typename FaceType::CoordType CoordType;
01448
01449 CoordType Curv=CrossVector(f,numD);
01450 Curv.Normalize();
01451
01452 CoordType bary3d=(f.P(0)+f.P(1)+f.P(2))/3.0;
01453 vcg::Point2<ScalarType> Uv0=f.V(0)->T().P();
01454 vcg::Point2<ScalarType> Uv1=f.V(1)->T().P();
01455 vcg::Point2<ScalarType> Uv2=f.V(2)->T().P();
01456 vcg::Point2<ScalarType> baryUV=(Uv0+Uv1+Uv2)/3.0;
01457 CoordType direct3d=bary3d+Curv;
01458 CoordType baryCoordsUV;
01459 vcg::InterpolationParameters<FaceType,ScalarType>(f,direct3d,baryCoordsUV);
01460 vcg::Point2<ScalarType> curvUV=baryCoordsUV.X()*Uv0+
01461 baryCoordsUV.Y()*Uv1+
01462 baryCoordsUV.Z()*Uv2-baryUV;
01463 curvUV.Normalize();
01464 return curvUV;
01465 }
01466
01467 static void InitDirFromWEdgeUV(MeshType &mesh)
01468 {
01469 for (size_t i=0;i<mesh.face.size();i++)
01470 {
01471 vcg::Point2<ScalarType> UV0=mesh.face[i].WT(0).P();
01472 vcg::Point2<ScalarType> UV1=mesh.face[i].WT(1).P();
01473 vcg::Point2<ScalarType> UV2=mesh.face[i].WT(2).P();
01474 GradientToCross(mesh.face[i],UV0,UV1,UV2,
01475 CoordType::Construct(mesh.face[i].PD1()),
01476 CoordType::Construct(mesh.face[i].PD2()) );
01477 }
01478 OrientDirectionFaceCoherently(mesh);
01479 }
01480
01481 };
01482 }
01483 }
01484 #endif