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 #ifndef __VCG_TRIMESHCOLLAPSE_QUADRIC_TEX_
00028 #define __VCG_TRIMESHCOLLAPSE_QUADRIC_TEX_
00029
00030 #include <vcg/complex/algorithms/local_optimization.h>
00031 #include <vcg/complex/algorithms/local_optimization/tri_edge_collapse_quadric.h>
00032 #include <vcg/container/simple_temporary_data.h>
00033 #include <vcg/math/quadric5.h>
00034 namespace vcg
00035 {
00036 namespace tri
00037 {
00038
00039
00040 class TriEdgeCollapseQuadricTexParameter : public BaseParameterClass
00041 {
00042 public:
00043 double BoundaryWeight;
00044 double CosineThr;
00045 float ExtraTCoordWeight;
00046 bool NormalCheck;
00047 double NormalThrRad;
00048 bool OptimalPlacement;
00049 bool PreserveBoundary;
00050 bool PreserveTopology;
00051 double QuadricEpsilon;
00052 double QualityThr;
00053 bool QualityQuadric;
00054 bool SafeHeapUpdate;
00055 double ScaleFactor;
00056 bool ScaleIndependent;
00057 bool UseArea;
00058 bool UseVertexWeight;
00059
00060 TriEdgeCollapseQuadricTexParameter()
00061 {
00062 SetDefaultParams();
00063 }
00064
00065 void SetDefaultParams()
00066 {
00067 this->BoundaryWeight=.5;
00068 this->CosineThr = cos(M_PI/2);
00069 this->ExtraTCoordWeight=0.0;
00070 this->NormalCheck=false;
00071 this->NormalThrRad=M_PI/2;
00072 this->OptimalPlacement=true;
00073 this->PreserveBoundary = false;
00074 this->PreserveTopology = false;
00075 this->QuadricEpsilon =1e-15;
00076 this->QualityThr=.1;
00077 this->QualityQuadric = false;
00078 this->SafeHeapUpdate=false;
00079 this->ScaleFactor=1.0;
00080 this->ScaleIndependent=true;
00081 this->UseArea=true;
00082 this->UseVertexWeight=false;
00083 }
00084 };
00085
00086
00087
00088
00089
00090 template <class MeshType>
00091 class QuadricTexHelper
00092 {
00093 public:
00094 typedef typename MeshType::VertexType VertexType;
00095
00096 typedef SimpleTempData<typename MeshType::VertContainer, std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > > Quadric5Temp;
00097 typedef SimpleTempData<typename MeshType::VertContainer, math::Quadric<double> > QuadricTemp;
00098
00099 QuadricTexHelper(){}
00100
00101
00102 static void Init(){}
00103
00104
00105 static void Alloc(VertexType *v,vcg::TexCoord2f &coord)
00106 {
00107 std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > &qv = Vd(v);
00108 Quadric5<double> newq5;
00109 newq5.Zero();
00110 vcg::TexCoord2f newcoord;
00111 newcoord.u() = coord.u();
00112 newcoord.v() = coord.v();
00113
00114 newq5.Sum3(Qd3(v),coord.u(),coord.v());
00115
00116 qv.push_back(std::pair<vcg::TexCoord2f ,Quadric5<double> >(newcoord,newq5));
00117 }
00118
00119 static void SumAll(VertexType *v,vcg::TexCoord2f &coord, Quadric5<double>& q)
00120 {
00121 std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > &qv = Vd(v);
00122
00123 for(size_t i = 0; i < qv.size(); i++)
00124 {
00125 vcg::TexCoord2f &f = qv[i].first;
00126 if((f.u() == coord.u()) && (f.v() == coord.v()))
00127 qv[i].second += q;
00128 else
00129 qv[i].second.Sum3(Qd3(v),f.u(),f.v());
00130 }
00131 }
00132
00133 static bool Contains(VertexType *v,vcg::TexCoord2f &coord)
00134 {
00135 std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > &qv = Vd(v);
00136
00137 for(size_t i = 0; i < qv.size(); i++)
00138 {
00139 vcg::TexCoord2f &f = qv[i].first;
00140 if((f.u() == coord.u()) && (f.v() == coord.v()))
00141 return true;
00142 }
00143
00144 return false;
00145 }
00146
00147 static Quadric5<double> &Qd(VertexType *v,const vcg::TexCoord2f &coord)
00148 {
00149 std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > &qv = Vd(v);
00150
00151 for(size_t i = 0; i < qv.size(); i++)
00152 {
00153 vcg::TexCoord2f &f = qv[i].first;
00154 if((f.u() == coord.u()) && (f.v() == coord.v()))
00155 return qv[i].second;
00156 }
00157
00158 assert(0);
00159 }
00160 static math::Quadric<double> &Qd3(VertexType *v) {return TD3()[*v];}
00161 static math::Quadric<double> &Qd3(VertexType &v) {return TD3()[v];}
00162
00163 static std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > &Vd(VertexType *v){return (TD()[*v]);}
00164 static typename VertexType::ScalarType W(VertexType * ) {return 1.0;}
00165 static typename VertexType::ScalarType W(VertexType & ) {return 1.0;}
00166 static void Merge(VertexType & , VertexType const & ){}
00167 static Quadric5Temp* &TDp() {static Quadric5Temp *td; return td;}
00168 static Quadric5Temp &TD() {return *TDp();}
00169 static QuadricTemp* &TDp3() {static QuadricTemp *td3; return td3;}
00170 static QuadricTemp &TD3() {return *TDp3();}
00171 };
00172
00173
00174
00175
00176
00177
00178
00179 template<class TriMeshType, class VertexPair, class MYTYPE, class HelperType = tri::QInfoStandard<typename TriMeshType::VertexType> >
00180 class TriEdgeCollapseQuadricTex: public vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE>
00181 {
00182 typedef HelperType QH;
00183 typedef typename tri::TriEdgeCollapse<TriMeshType, VertexPair, MYTYPE>::HeapType HeapType;
00184 typedef typename tri::TriEdgeCollapse<TriMeshType, VertexPair, MYTYPE>::HeapElem HeapElem;
00185 typedef typename TriMeshType::FaceType FaceType;
00186 typedef typename TriMeshType::VertexType VertexType;
00187 typedef typename TriMeshType::CoordType CoordType;
00188 typedef typename TriMeshType::CoordType::ScalarType ScalarType;
00189 typedef typename TriMeshType::VertexPointer VertexPointer;
00190
00191
00192 public:
00193
00194 inline TriEdgeCollapseQuadricTex(const VertexPair &p, int mark, BaseParameterClass *_pp)
00195 {
00196 TriEdgeCollapseQuadricTexParameter *pp = (TriEdgeCollapseQuadricTexParameter *)_pp;
00197 this->localMark = mark;
00198 this->pos=p;
00199 this->_priority = ComputePriority(pp);
00200 }
00201
00202
00203 static std::vector<VertexPointer> & WV(){
00204 static std::vector<VertexPointer> _WV; return _WV;
00205 };
00206
00207
00208
00209 static TriEdgeCollapseQuadricTexParameter & Params(){static TriEdgeCollapseQuadricTexParameter p; return p;}
00210
00211
00212 static void Finalize(TriMeshType &m,HeapType & , BaseParameterClass *_pp)
00213 {
00214 TriEdgeCollapseQuadricTexParameter *pp = (TriEdgeCollapseQuadricTexParameter *)_pp;
00215 vcg::tri::UpdateFlags<TriMeshType>::FaceBorderFromVF(m);
00216
00217
00218 if(pp->PreserveBoundary)
00219 {
00220 typename std::vector<VertexPointer>::iterator wvi;
00221 for(wvi=WV().begin();wvi!=WV().end();++wvi)
00222 if(!(*wvi)->IsD()) (*wvi)->SetW();
00223 }
00224 }
00225
00226
00227
00228
00229 inline static int matchVertexID(FaceType *f,VertexType *v)
00230 {
00231 if(f->V(0)==v) return 0;
00232 if(f->V(1)==v) return 1;
00233 if(f->V(2)==v) return 2;
00234
00235 assert(0); return -1;
00236 }
00237
00238 inline int GetTexCoords(vcg::TexCoord2f &tcoord0_1, vcg::TexCoord2f &tcoord1_1,vcg::TexCoord2f &tcoord0_2,vcg::TexCoord2f &tcoord1_2)
00239 {
00240 int ncoords = 0;
00241 tcoord0_1.P()=Point2f(0.5f,0.5f);
00242 tcoord1_1.P()=Point2f(0.5f,0.5f);
00243 tcoord0_2.P()=Point2f(0.5f,0.5f);
00244 tcoord1_2.P()=Point2f(0.5f,0.5f);
00245
00246 vcg::face::VFIterator<FaceType> vfi(this->pos.V(0));
00247
00248 for(vfi.F() = this->pos.V(0)->VFp(), vfi.I() = this->pos.V(0)->VFi(); vfi.F()!=0; ++vfi )
00249 if(vfi.F()->V(0)==this->pos.V(1) || vfi.F()->V(1)==this->pos.V(1) || vfi.F()->V(2)==this->pos.V(1) )
00250 {
00251 if(ncoords == 0)
00252 {
00253 tcoord0_1 = vfi.F()->WT(matchVertexID(vfi.F(),this->pos.V(0)));
00254 tcoord1_1 = vfi.F()->WT(matchVertexID(vfi.F(),this->pos.V(1)));
00255 }
00256 else
00257 {
00258 tcoord0_2 = vfi.F()->WT(matchVertexID(vfi.F(),this->pos.V(0)));
00259 tcoord1_2 = vfi.F()->WT(matchVertexID(vfi.F(),this->pos.V(1)));
00260
00261 if(
00262 (tcoord0_1.u() == tcoord0_2.u()) &&
00263 (tcoord0_1.v() == tcoord0_2.v()) &&
00264 (tcoord1_1.u() == tcoord1_2.u()) &&
00265 (tcoord1_1.v() == tcoord1_2.v())
00266 )
00267 return 1;
00268 else
00269 return 2;
00270 }
00271 ncoords++;
00272 }
00273
00274 return ncoords;
00275 }
00276
00277
00278 ScalarType ComputePriority(BaseParameterClass *_pp)
00279 {
00280 TriEdgeCollapseQuadricTexParameter *pp = (TriEdgeCollapseQuadricTexParameter *)_pp;
00281 Quadric5<double> qsum1;
00282 Quadric5<double> qsum2;
00283 double min1[5];
00284 double min2[5];
00285 vcg::TexCoord2f tcoord0_1;
00286 vcg::TexCoord2f tcoord1_1;
00287 vcg::TexCoord2f tcoord0_2;
00288 vcg::TexCoord2f tcoord1_2;
00289 int ncoords;
00290
00291 ncoords = GetTexCoords(tcoord0_1,tcoord1_1,tcoord0_2,tcoord1_2);
00292
00293 return (ScalarType)ComputeMinimalsAndPriority(min1,min2,qsum1,qsum2,tcoord0_1,tcoord1_1,tcoord0_2,tcoord1_2,ncoords,pp);
00294 }
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304 ScalarType ComputeTexPriority(const double vv[5],Quadric5<double> &qsum, BaseParameterClass *_pp)
00305 {
00306 TriEdgeCollapseQuadricTexParameter *pp = (TriEdgeCollapseQuadricTexParameter *)_pp;
00307 VertexType * v[2];
00308 v[0] = this->pos.V(0);
00309 v[1] = this->pos.V(1);
00310
00311 assert(!math::IsNAN(vv[0]));
00312 assert(!math::IsNAN(vv[1]));
00313 assert(!math::IsNAN(vv[2]));
00314 assert(!math::IsNAN(vv[3]));
00315 assert(!math::IsNAN(vv[4]));
00316
00318 CoordType OldPos0=v[0]->P();
00319 CoordType OldPos1=v[1]->P();
00320
00321 v[0]->P() = CoordType(vv[0],vv[1],vv[2]);
00322
00323 v[1]->P()=v[0]->P();
00324
00325 double QuadErr = qsum.Apply(vv);
00326
00328 int i;
00329
00330 double qt, MinQual = 1e100;
00331 vcg::face::VFIterator<FaceType> x(this->pos.V(0));
00332
00333 double ndiff,MinCos = 1e100;
00334
00335
00336
00337 for(x.F() = v[0]->VFp(), x.I() = v[0]->VFi(),i=0; x.F()!=0; ++x )
00338 if(x.F()->V(0)!=v[1] && x.F()->V(1)!=v[1] && x.F()->V(2)!=v[1] )
00339 {
00340 qt= QualityFace(*x.F());
00341 if(qt<MinQual) MinQual=qt;
00342 if(pp->NormalCheck){
00343 CoordType nn=TriangleNormal(*x.F()).Normalize();
00344 ndiff=nn.dot(x.F()->N()) / x.F()->N().Norm();
00345 if(ndiff<MinCos) MinCos=ndiff;
00346 assert(!math::IsNAN(ndiff));
00347 }
00348 }
00349 for(x.F() = v[1]->VFp(), x.I() = v[1]->VFi(),i=0; x.F()!=0; ++x )
00350 if(x.F()->V(0)!=v[0] && x.F()->V(1)!=v[0] && x.F()->V(2)!=v[0] )
00351 {
00352 qt= QualityFace(*x.F());
00353 if(qt<MinQual) MinQual=qt;
00354 if(pp->NormalCheck){
00355 CoordType nn=TriangleNormal(*x.F()).Normalize();
00356 ndiff=nn.dot(x.F()->N() / x.F()->N().Norm());
00357 if(ndiff<MinCos) MinCos=ndiff;
00358 assert(!math::IsNAN(ndiff));
00359 }
00360
00361 }
00362
00363
00364
00365 if(MinQual>pp->QualityThr) MinQual=pp->QualityThr;
00366 if(QuadErr<1e-15) QuadErr=1e-15;
00367
00368 this->_priority = (ScalarType)(QuadErr / MinQual);
00369
00370
00371 if(pp->NormalCheck){
00372 if(MinCos<pp->CosineThr) this->_priority *=1000;
00373 }
00374
00375
00376
00377
00378 v[0]->P()=OldPos0;
00379 v[1]->P()=OldPos1;
00380 return this->_priority;
00381 }
00382
00383 inline ScalarType ComputeMinimalsAndPriority(double dest_1[5],
00384 double dest_2[5],
00385 Quadric5<double> &qsum_1,
00386 Quadric5<double> &qsum_2,
00387 const vcg::TexCoord2f &tcoord0_1,
00388 const vcg::TexCoord2f &tcoord1_1,
00389 const vcg::TexCoord2f &tcoord0_2,
00390 const vcg::TexCoord2f &tcoord1_2,
00391 int ncoords,
00392 BaseParameterClass *_pp)
00393 {
00394 TriEdgeCollapseQuadricTexParameter *pp = (TriEdgeCollapseQuadricTexParameter *)_pp;
00395 double tmp1[5];
00396 double tmp2[5];
00397 ScalarType priority1;
00398 ScalarType priority2;
00399
00400 assert(!math::IsNAN(tcoord0_1.u()));
00401 assert(!math::IsNAN(tcoord0_1.v()));
00402 assert(!math::IsNAN(tcoord1_1.u()));
00403 assert(!math::IsNAN(tcoord1_1.v()));
00404 assert(!math::IsNAN(tcoord0_2.u()));
00405 assert(!math::IsNAN(tcoord0_2.v()));
00406 assert(!math::IsNAN(tcoord1_2.u()));
00407 assert(!math::IsNAN(tcoord1_2.v()));
00408
00409
00410 tmp1[0] = this->pos.V(0)->P().X();
00411 tmp1[1] = this->pos.V(0)->P().Y();
00412 tmp1[2] = this->pos.V(0)->P().Z();
00413 tmp1[3] = tcoord0_1.u();
00414 tmp1[4] = tcoord0_1.v();
00415
00416 tmp2[0] = this->pos.V(1)->P().X();
00417 tmp2[1] = this->pos.V(1)->P().Y();
00418 tmp2[2] = this->pos.V(1)->P().Z();
00419 tmp2[3] = tcoord1_1.u();
00420 tmp2[4] = tcoord1_1.v();
00421
00422 assert(QH::Qd(this->pos.V(0),tcoord0_1).IsValid());
00423 assert(QH::Qd(this->pos.V(1),tcoord1_1).IsValid());
00424
00425 qsum_1 = QH::Qd(this->pos.V(0),tcoord0_1);
00426 qsum_1 += QH::Qd(this->pos.V(1),tcoord1_1);
00427
00428 ComputeMinimal(dest_1,tmp1,tmp2,qsum_1,pp);
00429 priority1 = ComputeTexPriority(dest_1,qsum_1,pp);
00430
00431 if(ncoords < 2)
00432 return priority1*(1 + (pp->ExtraTCoordWeight)*(QH::Vd(this->pos.V(0)).size()+ QH::Vd(this->pos.V(1)).size() - 2));
00433
00434
00435 tmp1[3] = tcoord0_2.u();
00436 tmp1[4] = tcoord0_2.v();
00437
00438 tmp2[3] = tcoord1_2.u();
00439 tmp2[4] = tcoord1_2.v();
00440
00441 assert(QH::Qd(this->pos.V(0),tcoord0_2).IsValid());
00442 assert(QH::Qd(this->pos.V(1),tcoord1_2).IsValid());
00443
00444 qsum_2 = QH::Qd(this->pos.V(0),tcoord0_2);
00445 qsum_2 += QH::Qd(this->pos.V(1),tcoord1_2);
00446
00447 ComputeMinimal(dest_2,tmp1,tmp2,qsum_2,pp);
00448 priority2 = ComputeTexPriority(dest_2,qsum_2,pp);
00449
00450 if(priority1 > priority2)
00451 {
00452 ComputeMinimalWithGeoContraints(dest_2,tmp1,tmp2,qsum_2,dest_1,pp);
00453 priority2 = ComputeTexPriority(dest_2,qsum_2,pp);
00454 }
00455 else
00456 {
00457 ComputeMinimalWithGeoContraints(dest_1,tmp1,tmp2,qsum_1,dest_2,pp);
00458 priority1 = ComputeTexPriority(dest_1,qsum_1,pp);
00459 }
00460
00461
00462 this->_priority = std::max(priority1, priority2)*(1 + (pp->ExtraTCoordWeight)*(QH::Vd(this->pos.V(0)).size()+QH::Vd(this->pos.V(1)).size() - 2));
00463
00464 return this->_priority;
00465 }
00466
00467 inline void ComputeMinimal(double vv[5],const double v0[5],const double v1[5], const Quadric5<double> qsum,BaseParameterClass *_pp)
00468 {
00469 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00470 bool rt=qsum.Minimum(vv);
00471
00472
00473 if(!rt || !pp->OptimalPlacement )
00474 {
00475 vv[0] = (v0[0] + v1[0])/2;
00476 vv[1] = (v0[1] + v1[1])/2;
00477 vv[2] = (v0[2] + v1[2])/2;
00478 vv[3] = (v0[3] + v1[3])/2;
00479 vv[4] = (v0[4] + v1[4])/2;
00480
00481
00482 double qvx= std::numeric_limits<float>::max();
00483 if(pp->OptimalPlacement)
00484 qvx = qsum.Apply(vv);
00485
00486
00487 double qv0=qsum.Apply(v0);
00488 double qv1=qsum.Apply(v1);
00489
00490
00491 if(qv0<qvx)
00492 {
00493 vv[0] = v0[0];
00494 vv[1] = v0[1];
00495 vv[2] = v0[2];
00496 vv[3] = v0[3];
00497 vv[4] = v0[4];
00498 }
00499
00500 if(qv1<qvx && qv1<qv0)
00501 {
00502 vv[0] = v1[0];
00503 vv[1] = v1[1];
00504 vv[2] = v1[2];
00505 vv[3] = v1[3];
00506 vv[4] = v1[4];
00507 }
00508 }
00509
00510 assert(!math::IsNAN(vv[0]));
00511 assert(!math::IsNAN(vv[1]));
00512 assert(!math::IsNAN(vv[2]));
00513 assert(!math::IsNAN(vv[3]));
00514 assert(!math::IsNAN(vv[4]));
00515 }
00516
00517 inline void ComputeMinimalWithGeoContraints(double vv[5],const double v0[5],const double v1[5], const Quadric5<double> qsum, const double geo[5],BaseParameterClass *_pp)
00518 {
00519 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00520 bool rt=qsum.MinimumWithGeoContraints(vv,geo);
00521
00522
00523 if(!rt || !pp->OptimalPlacement) {
00524 double qvx = std::numeric_limits<float>::max();
00525 vv[0] = geo[0];
00526 vv[1] = geo[1];
00527 vv[2] = geo[2];
00528 if(pp->OptimalPlacement)
00529 {
00530 vv[3] = (v0[3] + v1[3])/2;
00531 vv[4] = (v0[4] + v1[4])/2;
00532 qvx=qsum.Apply(vv);
00533 }
00534 vv[3] = v0[3];
00535 vv[4] = v0[4];
00536
00537 double qv0=qsum.Apply(vv);
00538
00539 vv[3] = v1[3];
00540 vv[4] = v1[4];
00541
00542 double qv1=qsum.Apply(v1);
00543
00544 vv[3] = (v0[3] + v1[3])/2;
00545 vv[4] = (v0[4] + v1[4])/2;
00546
00547 if(qv0<qvx)
00548 {
00549 vv[3] = v0[3];
00550 vv[4] = v0[4];
00551 }
00552
00553 if(qv1<qvx && qv1<qv0)
00554 {
00555 vv[3] = v1[3];
00556 vv[4] = v1[4];
00557 }
00558 }
00559
00560 }
00561
00562 static void InitQuadric(TriMeshType &m,BaseParameterClass *_pp)
00563 {
00564 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00565 typename TriMeshType::FaceIterator pf;
00566 HelperType::Init();
00567
00568 for(pf=m.face.begin();pf!=m.face.end();++pf)
00569 if( !(*pf).IsD() && (*pf).IsR() )
00570 if((*pf).V(0)->IsR() &&(*pf).V(1)->IsR() &&(*pf).V(2)->IsR())
00571 {
00572 Quadric5<double> q;
00573 q.byFace(*pf, QH::Qd3((*pf).V(0)), QH::Qd3((*pf).V(1)), QH::Qd3((*pf).V(2)),pp->QualityQuadric,pp->BoundaryWeight);
00574
00575 for(int j=0;j<3;++j)
00576 if( (*pf).V(j)->IsW())
00577 {
00578 if(!HelperType::Contains((*pf).V(j),(*pf).WT(j)))
00579 {
00580 HelperType::Alloc((*pf).V(j),(*pf).WT(j));
00581 }
00582 assert(!math::IsNAN((*pf).WT(j).u()));
00583 assert(!math::IsNAN((*pf).WT(j).v()));
00584 HelperType::SumAll((*pf).V(j),(*pf).WT(j),q);
00585 }
00586
00587 }
00588
00589 }
00590
00591 static void Init(TriMeshType &m,HeapType&h_ret,BaseParameterClass *_pp)
00592 {
00593 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00594 typename TriMeshType::VertexIterator vi;
00595 typename TriMeshType::FaceIterator pf;
00596
00597 vcg::tri::UpdateTopology<TriMeshType>::VertexFace(m);
00598 vcg::tri::UpdateFlags<TriMeshType>::FaceBorderFromVF(m);
00599
00600 if(pp->PreserveBoundary )
00601 {
00602 WV().clear();
00603 for(pf=m.face.begin();pf!=m.face.end();++pf)
00604 if( !(*pf).IsD() && (*pf).IsW() )
00605 for(int j=0;j<3;++j)
00606 if((*pf).IsB(j))
00607 {
00608 if((*pf).V(j)->IsW()) {(*pf).V(j)->ClearW(); WV().push_back((*pf).V(j));}
00609 if((*pf).V1(j)->IsW()) {(*pf).V1(j)->ClearW();WV().push_back((*pf).V1(j));}
00610 }
00611 }
00612
00613 InitQuadric(m,pp);
00614
00615
00616 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00617 if((*vi).IsRW())
00618 {
00619 vcg::face::VFIterator<FaceType> x;
00620 for( x.F() = (*vi).VFp(), x.I() = (*vi).VFi(); x.F()!=0; ++ x){
00621 x.V1()->ClearV();
00622 x.V2()->ClearV();
00623 }
00624 for( x.F() = (*vi).VFp(), x.I() = (*vi).VFi(); x.F()!=0; ++x )
00625 {
00626 assert(x.F()->V(x.I())==&(*vi));
00627 if((x.V0()<x.V1()) && x.V1()->IsRW() && !x.V1()->IsV()){
00628 x.V1()->SetV();
00629 h_ret.push_back(HeapElem(new MYTYPE(VertexPair(x.V0(),x.V1()),TriEdgeCollapse< TriMeshType,VertexPair,MYTYPE>::GlobalMark(),pp )));
00630 }
00631 if((x.V0()<x.V2()) && x.V2()->IsRW()&& !x.V2()->IsV()){
00632 x.V2()->SetV();
00633 h_ret.push_back(HeapElem(new MYTYPE(VertexPair(x.V0(),x.V2()),TriEdgeCollapse< TriMeshType,VertexPair,MYTYPE>::GlobalMark(),pp )));
00634 }
00635 }
00636 }
00637 make_heap(h_ret.begin(),h_ret.end());
00638 }
00639
00640 inline void UpdateHeap(HeapType & h_ret,BaseParameterClass *_pp)
00641 {
00642 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00643 this->GlobalMark()++;
00644 VertexType *v[2];
00645 v[0]= this->pos.V(0);
00646 v[1]= this->pos.V(1);
00647 v[1]->IMark() = this->GlobalMark();
00648
00649
00650 vcg::face::VFIterator<FaceType> vfi(v[1]);
00651
00652 while (!vfi.End()){
00653 vfi.V1()->ClearV();
00654 vfi.V2()->ClearV();
00655 ++vfi;
00656 }
00657
00658
00659 vfi = face::VFIterator<FaceType>(v[1]);
00660 while (!vfi.End())
00661 {
00662 assert(!vfi.F()->IsD());
00663 for (int j=0;j<3;j++)
00664 {
00665
00666 if( !(vfi.V1()->IsV()) && vfi.V1()->IsRW())
00667 {
00668 vfi.V1()->SetV();
00669
00670 h_ret.push_back(HeapElem(new MYTYPE(VertexPair(vfi.V0(),vfi.V1()), this->GlobalMark(),pp)));
00671 std::push_heap(h_ret.begin(),h_ret.end());
00672 }
00673
00674 if( !(vfi.V2()->IsV()) && vfi.V2()->IsRW())
00675 {
00676 vfi.V2()->SetV();
00677
00678 h_ret.push_back(HeapElem(new MYTYPE(VertexPair(vfi.V0(),vfi.V2()),this->GlobalMark(),pp)));
00679 std::push_heap(h_ret.begin(),h_ret.end());
00680 }
00681 }
00682 ++vfi;
00683 }
00684 }
00685
00686 void Execute(TriMeshType &m, BaseParameterClass *_pp)
00687 {
00688 tri::TriEdgeCollapseQuadricTexParameter *pp =(tri::TriEdgeCollapseQuadricTexParameter *)_pp;
00689 Quadric5<double> qsum1;
00690 Quadric5<double> qsum2;
00691 double min1[5];
00692 double min2[5];
00693 vcg::TexCoord2f tcoord0_1;
00694 vcg::TexCoord2f tcoord1_1;
00695 vcg::TexCoord2f tcoord0_2;
00696 vcg::TexCoord2f tcoord1_2;
00697 vcg::TexCoord2f newtcoord1;
00698 vcg::TexCoord2f newtcoord2;
00699 std::vector<std::pair<vcg::TexCoord2f ,Quadric5<double> > > qv;
00700 int ncoords;
00701 VertexType * v[2];
00702 v[0] = this->pos.V(0);
00703 v[1] = this->pos.V(1);
00704
00705 math::Quadric<double> qsum3 = QH::Qd3(v[0]);
00706 qsum3 += QH::Qd3(v[1]);
00707
00708 ncoords = GetTexCoords(tcoord0_1,tcoord1_1,tcoord0_2,tcoord1_2);
00709
00710 ComputeMinimalsAndPriority(min1,min2,qsum1,qsum2,tcoord0_1,tcoord1_1,tcoord0_2,tcoord1_2,ncoords,pp);
00711
00712 CoordType newPos(min1[0],min1[1],min1[2]);
00713
00714
00715
00716 EdgeCollapser<TriMeshType,VertexPair>::Do(m, this->pos, newPos);
00717
00718
00719 vcg::TexCoord2f newtcoord;
00720 Quadric5<double> newq;
00721
00722
00723
00724 newtcoord.u() = (float)min1[3];
00725 newtcoord.v() = (float)min1[4];
00726 assert(!math::IsNAN(newtcoord.u()));
00727 assert(!math::IsNAN(newtcoord.v()));
00728 newtcoord1 = newtcoord;
00729 newq = qsum1;
00730
00731 qv.push_back(std::pair<vcg::TexCoord2f ,Quadric5<double> >(newtcoord,newq));
00732
00733 if(ncoords > 1)
00734 {
00735 newtcoord.u() = min2[3];
00736 newtcoord.v() = min2[4];
00737 newtcoord2 = newtcoord;
00738 newq = qsum2;
00739
00740 qv.push_back(std::pair<vcg::TexCoord2f ,Quadric5<double> >(newtcoord2,newq));
00741 }
00742
00743
00744 vcg::face::VFIterator<FaceType> vfi(v[1]);
00745 while (!vfi.End())
00746 {
00747 vcg::TexCoord2f & tcoords = vfi.F()->WT(matchVertexID(vfi.F(),v[1]));
00748
00749 if(
00750 ((tcoords.u() == tcoord0_1.u()) && (tcoords.v() == tcoord0_1.v())) ||
00751 ((tcoords.u() == tcoord1_1.u()) && (tcoords.v() == tcoord1_1.v()))
00752 )
00753 {
00754 tcoords.u() = newtcoord1.u();
00755 tcoords.v() = newtcoord1.v();
00756 }
00757 else if(
00758 (ncoords > 1) &&
00759 (
00760 ((tcoords.u() == tcoord0_2.u()) && (tcoords.v() == tcoord0_2.v())) ||
00761 ((tcoords.u() == tcoord1_2.u()) && (tcoords.v() == tcoord1_2.v()))
00762 )
00763 )
00764 {
00765 tcoords.u()= newtcoord2.u();
00766 tcoords.v()= newtcoord2.v();
00767 }
00768 else
00769 {
00770 newtcoord = tcoords;
00771
00772 if(QH::Contains(v[0],tcoords))
00773 {
00774 newq = QH::Qd(v[0],tcoords);
00775 newq.Sum3(QH::Qd3(v[1]),tcoords.u(),tcoords.v());
00776 }
00777 else if(QH::Contains(v[1],tcoords))
00778 {
00779 newq = QH::Qd(v[1],tcoords);
00780 newq.Sum3(QH::Qd3(v[0]),tcoords.u(),tcoords.v());
00781 }
00782 else
00783 assert(0);
00784
00785 qv.push_back(std::pair<vcg::TexCoord2f ,Quadric5<double> >(newtcoord,newq));
00786 }
00787
00788 ++vfi;
00789 }
00790 QH::Qd3(v[1]) = qsum3;
00791 QH::Vd(v[1]) = qv;
00792
00793 }
00794
00795 };
00796
00797
00798
00799 }
00800 }
00801 #endif