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
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074 #ifndef __VCG_TRIMESHCOLLAPSE_QUADRIC__
00075 #define __VCG_TRIMESHCOLLAPSE_QUADRIC__
00076
00077 #include<vcg/math/quadric.h>
00078 #include<vcg/simplex/face/pos.h>
00079 #include<vcg/complex/trimesh/update/flag.h>
00080 #include<vcg/complex/trimesh/update/topology.h>
00081 #include<vcg/complex/trimesh/update/bounding.h>
00082 #include<vcg/complex/local_optimization/tri_edge_collapse.h>
00083 #include<vcg/complex/local_optimization.h>
00084
00085
00086 namespace vcg{
00087 namespace tri{
00088
00089
00090
00091
00121
00122 template <class VERTEX_TYPE>
00123 class QInfoStandard
00124 {
00125 public:
00126 QInfoStandard(){};
00127 static void Init(){};
00128 static math::Quadric<double> &Qd(VERTEX_TYPE &v) {return v.Qd();}
00129 static math::Quadric<double> &Qd(VERTEX_TYPE *v) {return v->Qd();}
00130 static typename VERTEX_TYPE::ScalarType W(VERTEX_TYPE *v) {return 1.0;};
00131 static typename VERTEX_TYPE::ScalarType W(VERTEX_TYPE &v) {return 1.0;};
00132 static void Merge(VERTEX_TYPE & v_dest, VERTEX_TYPE const & v_del){};
00133 };
00134
00135
00136 class TriEdgeCollapseQuadricParameter
00137 {
00138 public:
00139 double QualityThr;
00140 double BoundaryWeight;
00141 double NormalThrRad;
00142 double CosineThr;
00143 double QuadricEpsilon;
00144 double ScaleFactor;
00145 bool UseArea;
00146 bool UseVertexWeight;
00147 bool NormalCheck;
00148 bool QualityCheck;
00149 bool OptimalPlacement;
00150 bool MemoryLess;
00151 bool QualityWeight;
00152 bool ScaleIndependent;
00153
00154 bool QualityQuadric;
00155 bool PreserveTopology;
00156 bool PreserveBoundary;
00157 bool MarkComplex;
00158 bool FastPreserveBoundary;
00159 bool SafeHeapUpdate;
00160 };
00161
00162
00163 template<class TriMeshType,class MYTYPE, class HelperType = QInfoStandard<typename TriMeshType::VertexType> >
00164 class TriEdgeCollapseQuadric: public TriEdgeCollapse< TriMeshType, MYTYPE>
00165 {
00166 public:
00167 typedef typename vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE > TEC;
00168 typedef typename TEC::EdgeType EdgeType;
00169 typedef typename TriEdgeCollapse<TriMeshType, MYTYPE>::HeapType HeapType;
00170 typedef typename TriEdgeCollapse<TriMeshType, MYTYPE>::HeapElem HeapElem;
00171 typedef typename TriMeshType::CoordType CoordType;
00172 typedef typename TriMeshType::ScalarType ScalarType;
00173 typedef math::Quadric< double > QuadricType;
00174 typedef typename TriMeshType::FaceType FaceType;
00175 typedef typename TriMeshType::VertexType VertexType;
00176 typedef TriEdgeCollapseQuadricParameter QParameter;
00177 typedef HelperType QH;
00178
00179 static QParameter & Params(){
00180 static QParameter p;
00181 return p;
00182 }
00183 enum Hint {
00184 HNHasFFTopology = 0x0001,
00185 HNHasVFTopology = 0x0002,
00186 HNHasBorderFlag = 0x0004
00187 };
00188
00189 static int & Hnt(){static int hnt; return hnt;}
00190
00191 static void SetHint(Hint hn) { Hnt() |= hn; }
00192 static void ClearHint(Hint hn) { Hnt()&=(~hn);}
00193 static bool IsSetHint(Hint hn) { return (Hnt()&hn)!=0; }
00194
00195
00196 static std::vector<typename TriMeshType::VertexPointer> & WV(){
00197 static std::vector<typename TriMeshType::VertexPointer> _WV; return _WV;
00198 };
00199
00200 inline TriEdgeCollapseQuadric(const EdgeType &p, int i)
00201
00202 {
00203 this->localMark = i;
00204 this->pos=p;
00205 this->_priority = ComputePriority();
00206 }
00207
00208
00209 inline bool IsFeasible(){
00210 bool res = ( !Params().PreserveTopology || LinkConditions(this->pos) );
00211 if(!res) ++( TriEdgeCollapse< TriMeshType,MYTYPE>::FailStat::LinkConditionEdge() );
00212 return res;
00213 }
00214
00215 void Execute(TriMeshType &m)
00216 { CoordType newPos;
00217 if(Params().OptimalPlacement) newPos= static_cast<MYTYPE*>(this)->ComputeMinimal();
00218 else newPos=this->pos.V(1)->P();
00219
00220 QH::Qd(this->pos.V(1))+=QH::Qd(this->pos.V(0));
00221
00222 DoCollapse(m, this->pos, newPos);
00223
00224
00225 }
00226
00227
00228
00229
00230 static void Finalize(TriMeshType &m, HeapType& )
00231 {
00232
00233
00234 if(IsSetHint(HNHasBorderFlag) )
00235 vcg::tri::UpdateFlags<TriMeshType>::FaceBorderFromVF(m);
00236
00237
00238 if(Params().FastPreserveBoundary)
00239 {
00240 typename TriMeshType::VertexIterator vi;
00241 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00242 if(!(*vi).IsD()) (*vi).SetW();
00243 }
00244 if(Params().PreserveBoundary)
00245 {
00246 typename std::vector<typename TriMeshType::VertexPointer>::iterator wvi;
00247 for(wvi=WV().begin();wvi!=WV().end();++wvi)
00248 if(!(*wvi)->IsD()) (*wvi)->SetW();
00249 }
00250 }
00251
00252 static void Init(TriMeshType &m,HeapType&h_ret){
00253
00254 typename TriMeshType::VertexIterator vi;
00255 typename TriMeshType::FaceIterator pf;
00256
00257 EdgeType av0,av1,av01;
00258 Params().CosineThr=cos(Params().NormalThrRad);
00259
00260 if(!IsSetHint(HNHasVFTopology) ) vcg::tri::UpdateTopology<TriMeshType>::VertexFace(m);
00261
00262 if(Params().MarkComplex) {
00263 vcg::tri::UpdateTopology<TriMeshType>::FaceFace(m);
00264 vcg::tri::UpdateFlags<TriMeshType>::FaceBorderFromFF(m);
00265 vcg::tri::UpdateTopology<TriMeshType>::VertexFace(m);
00266 }
00267 else
00268 if(!IsSetHint(HNHasBorderFlag) )
00269 vcg::tri::UpdateFlags<TriMeshType>::FaceBorderFromVF(m);
00270
00271 if(Params().FastPreserveBoundary)
00272 {
00273 for(pf=m.face.begin();pf!=m.face.end();++pf)
00274 if( !(*pf).IsD() && (*pf).IsW() )
00275 for(int j=0;j<3;++j)
00276 if((*pf).IsB(j))
00277 {
00278 (*pf).V(j)->ClearW();
00279 (*pf).V1(j)->ClearW();
00280 }
00281 }
00282
00283 if(Params().PreserveBoundary)
00284 {
00285 WV().clear();
00286 for(pf=m.face.begin();pf!=m.face.end();++pf)
00287 if( !(*pf).IsD() && (*pf).IsW() )
00288 for(int j=0;j<3;++j)
00289 if((*pf).IsB(j))
00290 {
00291 if((*pf).V(j)->IsW()) {(*pf).V(j)->ClearW(); WV().push_back((*pf).V(j));}
00292 if((*pf).V1(j)->IsW()) {(*pf).V1(j)->ClearW();WV().push_back((*pf).V1(j));}
00293 }
00294 }
00295
00296 InitQuadric(m);
00297
00298
00299 if(IsSymmetric())
00300 {
00301 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00302 if(!(*vi).IsD() && (*vi).IsRW())
00303 {
00304 vcg::face::VFIterator<FaceType> x;
00305 for( x.F() = (*vi).VFp(), x.I() = (*vi).VFi(); x.F()!=0; ++ x){
00306 x.V1()->ClearV();
00307 x.V2()->ClearV();
00308 }
00309 for( x.F() = (*vi).VFp(), x.I() = (*vi).VFi(); x.F()!=0; ++x )
00310 {
00311 assert(x.F()->V(x.I())==&(*vi));
00312 if((x.V0()<x.V1()) && x.V1()->IsRW() && !x.V1()->IsV()){
00313 x.V1()->SetV();
00314 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(x.V0(),x.V1()),TriEdgeCollapse< TriMeshType,MYTYPE>::GlobalMark() )));
00315 }
00316 if((x.V0()<x.V2()) && x.V2()->IsRW()&& !x.V2()->IsV()){
00317 x.V2()->SetV();
00318 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(x.V0(),x.V2()),TriEdgeCollapse< TriMeshType,MYTYPE>::GlobalMark() )));
00319 }
00320 }
00321 }
00322 }
00323 else
00324 {
00325 for(vi=m.vert.begin();vi!=m.vert.end();++vi)
00326 if(!(*vi).IsD() && (*vi).IsRW())
00327 {
00328 vcg::face::VFIterator<FaceType> x;
00329 UnMarkAll(m);
00330 for( x.F() = (*vi).VFp(), x.I() = (*vi).VFi(); x.F()!=0; ++ x)
00331 {
00332 assert(x.F()->V(x.I())==&(*vi));
00333 if(x.V()->IsRW() && x.V1()->IsRW() && !IsMarked(m,x.F()->V1(x.I()))){
00334 h_ret.push_back( HeapElem( new MYTYPE( EdgeType (x.V(),x.V1()),TriEdgeCollapse< TriMeshType,MYTYPE>::GlobalMark())));
00335 }
00336 if(x.V()->IsRW() && x.V2()->IsRW() && !IsMarked(m,x.F()->V2(x.I()))){
00337 h_ret.push_back( HeapElem( new MYTYPE( EdgeType (x.V(),x.V2()),TriEdgeCollapse< TriMeshType,MYTYPE>::GlobalMark())));
00338 }
00339 }
00340 }
00341 }
00342 }
00343 static float HeapSimplexRatio() {return IsSymmetric()?5.0f:9.0f;}
00344 static bool IsSymmetric() {return Params().OptimalPlacement;}
00345 static bool IsVertexStable() {return !Params().OptimalPlacement;}
00346 static void SetDefaultParams(){
00347 Params().UseArea=true;
00348 Params().UseVertexWeight=false;
00349 Params().NormalCheck=false;
00350 Params().NormalThrRad=M_PI/2;
00351 Params().QualityCheck=true;
00352 Params().QualityThr=.1;
00353 Params().BoundaryWeight=.5;
00354 Params().QualityQuadric=false;
00355 Params().OptimalPlacement=true;
00356 Params().ScaleIndependent=true;
00357 Params().QualityWeight=false;
00358 Params().QuadricEpsilon =1e-15;
00359 Params().ScaleFactor=1.0;
00360
00361 Params().PreserveTopology = false;
00362 }
00363
00365
00366
00367
00368
00369
00370 ScalarType ComputePriority() {
00371 ScalarType error;
00372 typename vcg::face::VFIterator<FaceType> x;
00373 std::vector<CoordType> on;
00374 typename TriMeshType::VertexType * v[2];
00375 v[0] = this->pos.V(0);
00376 v[1] = this->pos.V(1);
00377
00378 if(Params().NormalCheck){
00379
00380 for(x.F() = v[0]->VFp(), x.I() = v[0]->VFi(); x.F()!=0; ++x )
00381 if(x.F()->V(0)!=v[1] && x.F()->V(1)!=v[1] && x.F()->V(2)!=v[1] )
00382 on.push_back(NormalizedNormal(*x.F()));
00383
00384 for(x.F() = v[1]->VFp(), x.I() = v[1]->VFi(); x.F()!=0; ++x )
00385 if(x.F()->V(0)!=v[0] && x.F()->V(1)!=v[0] && x.F()->V(2)!=v[0] )
00386 on.push_back(NormalizedNormal(*x.F()));
00387 }
00388
00390 CoordType OldPos0=v[0]->P();
00391 CoordType OldPos1=v[1]->P();
00392 if(Params().OptimalPlacement) { v[0]->P() = ComputeMinimal(); v[1]->P()=v[0]->P();}
00393 else v[0]->P() = v[1]->P();
00394
00396 int i;
00397 double ndiff,MinCos = 1e100;
00398
00399
00400 double qt, MinQual = 1e100;
00401 CoordType nn;
00402 for(x.F() = v[0]->VFp(), x.I() = v[0]->VFi(),i=0; x.F()!=0; ++x )
00403 if(x.F()->V(0)!=v[1] && x.F()->V(1)!=v[1] && x.F()->V(2)!=v[1] )
00404 {
00405 if(Params().NormalCheck){
00406 nn=NormalizedNormal(*x.F());
00407 ndiff=nn.dot(on[i++]);
00408 if(ndiff<MinCos) MinCos=ndiff;
00409 }
00410 if(Params().QualityCheck){
00411 qt= QualityFace(*x.F());
00412 if(qt<MinQual) MinQual=qt;
00413 }
00414 }
00415 for(x.F() = v[1]->VFp(), x.I() = v[1]->VFi(),i=0; x.F()!=0; ++x )
00416 if(x.F()->V(0)!=v[0] && x.F()->V(1)!=v[0] && x.F()->V(2)!=v[0] )
00417 {
00418 if(Params().NormalCheck){
00419 nn=NormalizedNormal(*x.F());
00420 ndiff=nn.dot(on[i++]);
00421 if(ndiff<MinCos) MinCos=ndiff;
00422 }
00423 if(Params().QualityCheck){
00424 qt= QualityFace(*x.F());
00425 if(qt<MinQual) MinQual=qt;
00426 }
00427 }
00428
00429 QuadricType qq=QH::Qd(v[0]);
00430 qq+=QH::Qd(v[1]);
00431 Point3d tpd=Point3d::Construct(v[1]->P());
00432 double QuadErr = Params().ScaleFactor*qq.Apply(tpd);
00433
00434
00435 if(MinQual>Params().QualityThr) MinQual=Params().QualityThr;
00436
00437 if(Params().NormalCheck){
00438
00439
00440 if(MinCos>Params().CosineThr) MinCos=Params().CosineThr;
00441 MinCos=(MinCos+1)/2.0;
00442 }
00443
00444 if(QuadErr<Params().QuadricEpsilon) QuadErr=Params().QuadricEpsilon;
00445
00446 if( Params().UseVertexWeight ) QuadErr *= (QH::W(v[1])+QH::W(v[0]))/2;
00447
00448 if(!Params().QualityCheck && !Params().NormalCheck) error = (ScalarType)(QuadErr);
00449 if( Params().QualityCheck && !Params().NormalCheck) error = (ScalarType)(QuadErr / MinQual);
00450 if(!Params().QualityCheck && Params().NormalCheck) error = (ScalarType)(QuadErr / MinCos);
00451 if( Params().QualityCheck && Params().NormalCheck) error = (ScalarType)(QuadErr / (MinQual*MinCos));
00452
00453
00454 v[0]->P()=OldPos0;
00455 v[1]->P()=OldPos1;
00456 this->_priority = error;
00457 return this->_priority;
00458 }
00459
00460
00461
00462
00463 inline void UpdateHeap(HeapType & h_ret)
00464 {
00465 this->GlobalMark()++;
00466 VertexType *v[2];
00467 v[0]= this->pos.V(0);
00468 v[1]= this->pos.V(1);
00469 v[1]->IMark() = this->GlobalMark();
00470
00471
00472 vcg::face::VFIterator<FaceType> vfi(v[1]);
00473 while (!vfi.End()){
00474 vfi.V1()->ClearV();
00475 vfi.V2()->ClearV();
00476 ++vfi;
00477 }
00478
00479
00480 vfi = face::VFIterator<FaceType>(v[1]);
00481 while (!vfi.End())
00482 {
00483 assert(!vfi.F()->IsD());
00484 for (int j=0;j<3;j++)
00485 {
00486 if( !(vfi.V1()->IsV()) && vfi.V1()->IsRW())
00487 {
00488 vfi.V1()->SetV();
00489 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V0(),vfi.V1()), this->GlobalMark())));
00490 std::push_heap(h_ret.begin(),h_ret.end());
00491 if(!IsSymmetric()){
00492 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V1(),vfi.V0()), this->GlobalMark())));
00493 std::push_heap(h_ret.begin(),h_ret.end());
00494 }
00495 }
00496 if( !(vfi.V2()->IsV()) && vfi.V2()->IsRW())
00497 {
00498 vfi.V2()->SetV();
00499 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V0(),vfi.V2()),this->GlobalMark())));
00500 std::push_heap(h_ret.begin(),h_ret.end());
00501 if(!IsSymmetric()){
00502 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V2(),vfi.V0()), this->GlobalMark())));
00503 std::push_heap(h_ret.begin(),h_ret.end());
00504 }
00505 }
00506 if(Params().SafeHeapUpdate && vfi.V1()->IsRW() && vfi.V2()->IsRW() )
00507 {
00508 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V1(),vfi.V2()),this->GlobalMark())));
00509 std::push_heap(h_ret.begin(),h_ret.end());
00510 if(!IsSymmetric()){
00511 h_ret.push_back(HeapElem(new MYTYPE(EdgeType(vfi.V2(),vfi.V1()), this->GlobalMark())));
00512 std::push_heap(h_ret.begin(),h_ret.end());
00513 }
00514 }
00515 }
00516 ++vfi;
00517 }
00518
00519 }
00520
00521 static void InitQuadric(TriMeshType &m)
00522 {
00523 typename TriMeshType::FaceIterator pf;
00524 typename TriMeshType::VertexIterator pv;
00525 int j;
00526 QH::Init();
00527
00528 for(pv=m.vert.begin();pv!=m.vert.end();++pv)
00529 if( ! (*pv).IsD() && (*pv).IsW())
00530 QH::Qd(*pv).SetZero();
00531
00532
00533 for(pf=m.face.begin();pf!=m.face.end();++pf)
00534 if( !(*pf).IsD() && (*pf).IsR() )
00535 if((*pf).V(0)->IsR() &&(*pf).V(1)->IsR() &&(*pf).V(2)->IsR())
00536 {
00537 QuadricType q;
00538 Plane3<ScalarType,false> p;
00539
00540 p.SetDirection( ( (*pf).V(1)->cP() - (*pf).V(0)->cP() ) ^ ( (*pf).V(2)->cP() - (*pf).V(0)->cP() ));
00541
00542
00543 if(!Params().UseArea)
00544 p.Normalize();
00545
00546 p.SetOffset( p.Direction().dot((*pf).V(0)->cP()));
00547
00548
00549 q.ByPlane(p);
00550
00551 for(j=0;j<3;++j)
00552 if( (*pf).V(j)->IsW() )
00553 {
00554 if(Params().QualityWeight)
00555 q*=(*pf).V(j)->Q();
00556 QH::Qd((*pf).V(j)) += q;
00557 }
00558
00559 for(j=0;j<3;++j)
00560 if( (*pf).IsB(j) || Params().QualityQuadric )
00561 {
00562 Plane3<ScalarType,false> pb;
00563
00564
00565
00566
00567
00568 pb.SetDirection(p.Direction() ^ ( (*pf).V1(j)->cP() - (*pf).V(j)->cP() ).normalized());
00569 if( (*pf).IsB(j) ) pb.SetDirection(pb.Direction()* (ScalarType)Params().BoundaryWeight);
00570 else pb.SetDirection(pb.Direction()* (ScalarType)(Params().BoundaryWeight/100.0));
00571 pb.SetOffset(pb.Direction().dot((*pf).V(j)->cP()));
00572 q.ByPlane(pb);
00573
00574 if( (*pf).V (j)->IsW() ) QH::Qd((*pf).V (j)) += q;
00575 if( (*pf).V1(j)->IsW() ) QH::Qd((*pf).V1(j)) += q;
00576 }
00577 }
00578
00579 if(Params().ScaleIndependent)
00580 {
00581 vcg::tri::UpdateBounding<TriMeshType>::Box(m);
00582
00583 Params().ScaleFactor = 1e8*pow(1.0/m.bbox.Diag(),6);
00584
00585
00586
00587
00588 }
00589 }
00590
00591
00592
00593
00594
00595
00596
00597
00598
00599
00600
00601
00602
00603
00604
00605
00606 CoordType ComputeMinimal()
00607 {
00608 typename TriMeshType::VertexType * v[2];
00609 v[0] = this->pos.V(0);
00610 v[1] = this->pos.V(1);
00611 QuadricType q=QH::Qd(v[0]);
00612 q+=QH::Qd(v[1]);
00613
00614 Point3<QuadricType::ScalarType> x;
00615
00616 bool rt=q.Minimum(x);
00617 if(!rt) {
00618 Point3<QuadricType::ScalarType> x0=Point3d::Construct(v[0]->P());
00619 Point3<QuadricType::ScalarType> x1=Point3d::Construct(v[1]->P());
00620 x.Import((v[0]->P()+v[1]->P())/2);
00621 double qvx=q.Apply(x);
00622 double qv0=q.Apply(x0);
00623 double qv1=q.Apply(x1);
00624 if(qv0<qvx) x=x0;
00625 if(qv1<qvx && qv1<qv0) x=x1;
00626 }
00627
00628 return CoordType::Construct(x);
00629 }
00630
00631
00632
00633 };
00634 }
00635 }
00636 #endif