00001 #ifndef QUAD_DIAGONAL_COLLAPSE_H
00002 #define QUAD_DIAGONAL_COLLAPSE_H
00003
00004 #include<vcg/connectors/halfedge_pos.h>
00005 #include<vcg/complex/algorithms/local_optimization.h>
00006 #include<vcg/complex/algorithms/smooth.h>
00007
00008 #include<set>
00009
00010 #include<vcg/space/ray3.h>
00011
00012 #include<vcg/complex/algorithms/halfedge_quad_clean.h>
00013
00014 namespace vcg{
00015 namespace tri{
00016
00017
00022 template<class MeshType, class TriMeshType >
00023 class FeasibilityCheck
00024 {
00025 public:
00026 typedef typename MeshType::HEdgePointer HEdgePointer;
00027 typedef typename TriMeshType::FaceType TriFaceType;
00028 typedef typename vcg::GridStaticPtr<TriFaceType, typename TriFaceType::ScalarType> GRID;
00029 typedef typename TriMeshType::CoordType CoordType;
00030
00031 static bool check_feasible(HEdgePointer hp, CoordType &V1, CoordType &V2, TriMeshType &tm, GRID &grid);
00032 };
00033
00038 template<class MeshType, class TriMeshType >
00039 class OperationWeight
00040 {
00041 public:
00042 typedef typename MeshType::HEdgePointer HEdgePointer;
00043 typedef typename TriMeshType::FaceType TriFaceType;
00044 typedef typename vcg::GridStaticPtr<TriFaceType, typename TriFaceType::ScalarType> GRID;
00045 typedef typename TriMeshType::CoordType CoordType;
00046
00047 static float compute_weight(HEdgePointer hp, CoordType &P, TriMeshType &tm, GRID &grid);
00048 };
00049
00050
00055 template<class MeshType, class TriMeshType >
00056 class FitmapsCollapse : public FeasibilityCheck<MeshType, TriMeshType>, public OperationWeight<MeshType, TriMeshType>
00057 {
00058
00059 protected:
00060
00061 typedef typename MeshType::VertexPointer VertexPointer;
00062 typedef typename MeshType::HEdgePointer HEdgePointer;
00063
00064 typedef typename TriMeshType::FaceType TriFaceType;
00065 typedef typename vcg::GridStaticPtr<TriFaceType, typename TriFaceType::ScalarType> GRID;
00066
00067 typedef typename TriMeshType::CoordType CoordType;
00068 typedef typename TriMeshType::ScalarType ScalarType;
00069 typedef typename TriMeshType::FacePointer FacePointer;
00070
00071 typedef typename TriMeshType::template PerVertexAttributeHandle<float> Fitmap_attr;
00072
00073 public:
00074
00076 static float& Mfit_coeff()
00077 {
00078 static float coeff = 1.5;
00079 return coeff;
00080 }
00081
00092 static bool check_feasible(HEdgePointer hp, CoordType &V1, CoordType &V2, TriMeshType &tm, GRID &grid)
00093 {
00094 float length = Distance( V1, V2 );
00095
00096 Fitmap_attr M_Fit = tri::Allocator<TriMeshType>::template GetPerVertexAttribute<float>(tm,"M-Fitmap");
00097
00098 CoordType P = (V1+V2)/2;
00099 float fitmap = compute_fitmap(hp, P, tm, grid, M_Fit);
00100
00101 return length <= fitmap/Mfit_coeff();
00102 }
00103
00113 static float compute_weight(HEdgePointer hp, CoordType &P, TriMeshType &tm, GRID &grid)
00114 {
00115 Fitmap_attr S_Fit = tri::Allocator<TriMeshType>::template GetPerVertexAttribute<float>(tm,"S-Fitmap");
00116
00117 return compute_fitmap(hp, P, tm, grid, S_Fit);
00118 }
00119
00120 protected:
00121
00133 static float compute_fitmap(HEdgePointer hp, CoordType &P, TriMeshType &tm, GRID &grid, Fitmap_attr &attr)
00134 {
00135 CoordType N(0,0,0);
00136
00137 vector<VertexPointer> vertices = HalfEdgeTopology<MeshType>::getVertices(hp->HFp());
00138
00139 assert(vertices.size() == 4);
00140
00141 N += vcg::Normal<typename MeshType::CoordType>(vertices[0]->cP(), vertices[1]->cP(), vertices[2]->cP());
00142 N += vcg::Normal<typename MeshType::CoordType>(vertices[2]->cP(), vertices[3]->cP(), vertices[0]->cP());
00143
00144 N.Normalize();
00145
00146 CoordType C(0,0,0);
00147 FacePointer T = getClosestFaceRay(tm, grid, P, N, &C, NULL);
00148
00149 float result = 1.0;
00150
00151 if(T)
00152 {
00153 float w0;
00154 float w1;
00155 float w2;
00156 vcg::InterpolationParameters(*T, N, C, w0, w1, w2);
00157
00158 float s0 = attr[T->V(0)];
00159 float s1 = attr[T->V(1)];
00160 float s2 = attr[T->V(2)];
00161
00162 result = (w0*s0 + w1*s1 + w2*s2)/(w0+w1+w2);
00163 }
00164
00165 return result;
00166 }
00167
00168
00169 static FacePointer getClosestFaceRay(TriMeshType &m, GRID &grid, CoordType P, CoordType raydir, CoordType* closest, ScalarType* minDist)
00170 {
00171
00172 ScalarType diag = m.bbox.Diag();
00173
00174 raydir.Normalize();
00175
00176 Ray3<typename GRID::ScalarType> ray;
00177
00178 ray.SetOrigin(P);
00179 ScalarType t;
00180
00181 FacePointer f = 0;
00182 FacePointer fr = 0;
00183
00184 vector<CoordType> closests;
00185 vector<ScalarType> minDists;
00186 vector<FacePointer> faces;
00187
00188 ray.SetDirection(-raydir);
00189
00190 f = vcg::tri::DoRay<TriMeshType,GRID>(m, grid, ray, diag/4.0, t);
00191
00192 if (f)
00193 {
00194 closests.push_back(ray.Origin() + ray.Direction()*t);
00195 minDists.push_back(fabs(t));
00196 faces.push_back(f);
00197 }
00198
00199 ray.SetDirection(raydir);
00200
00201 fr = vcg::tri::DoRay<TriMeshType,GRID>(m, grid, ray, diag/4.0, t);
00202
00203 if (fr)
00204 {
00205 closests.push_back(ray.Origin() + ray.Direction()*t);
00206 minDists.push_back(fabs(t));
00207 faces.push_back(fr);
00208 }
00209
00210 if (fr)
00211 if (fr->N()*raydir<0)
00212 fr=0;
00213
00214 if (minDists.size() == 0)
00215 {
00216 if (closest) *closest=P;
00217 if (minDist) *minDist=0;
00218 f = 0;
00219 }
00220 else
00221 {
00222 int minI = std::min_element(minDists.begin(),minDists.end()) - minDists.begin();
00223 if (closest) *closest= closests[minI];
00224 if (minDist) *minDist= minDists[minI];
00225 f = faces[minI];
00226 }
00227
00228 return f;
00229
00230 }
00231
00232 };
00233
00234
00235
00240 template<class MeshType, class MYTYPE, class TriMeshType, class OptimizationType>
00241 class QuadDiagonalCollapseBase: public LocalOptimization<MeshType>::LocModType
00242 {
00243
00244 protected:
00245
00246 typedef Pos<MeshType> PosType;
00247 typedef typename MeshType::VertexPointer VertexPointer;
00248 typedef typename MeshType::FacePointer FacePointer;
00249 typedef typename MeshType::HEdgePointer HEdgePointer;
00250 typedef typename LocalOptimization<MeshType>::HeapElem HeapElem;
00251 typedef typename LocalOptimization<MeshType>::HeapType HeapType;
00252 typedef typename MeshType::ScalarType ScalarType;
00253 typedef typename MeshType::CoordType CoordType;
00254 typedef typename TriMeshType::FaceType TriFaceType;
00255 typedef typename vcg::GridStaticPtr<TriFaceType, typename TriFaceType::ScalarType> GRID;
00256
00258 VertexPointer ret;
00259
00261 static int& GlobalMark()
00262 {
00263 static int im=0;
00264 return im;
00265 }
00266
00268 int localMark;
00269
00271 ScalarType _priority;
00272
00274 set<FacePointer> faces;
00275
00277 HEdgePointer hp;
00278
00279 public:
00280
00282 static TriMeshType* &refMesh()
00283 {
00284 static TriMeshType* m = NULL;
00285 return m;
00286 }
00287
00289 static GRID* &grid()
00290 {
00291 static GRID* grid = NULL;
00292 return grid;
00293 }
00294
00296 static unsigned int &smoothing_iterations()
00297 {
00298 static unsigned int iterations = 5;
00299 return iterations;
00300 }
00301
00303 QuadDiagonalCollapseBase(){}
00304
00311 QuadDiagonalCollapseBase(HEdgePointer he, int mark)
00312 {
00313 localMark = mark;
00314 hp = he;
00315 _priority = ComputePriority();
00316 }
00317
00318 ~QuadDiagonalCollapseBase()
00319 {
00320 faces.clear();
00321 }
00322
00328 ScalarType ComputePriority()
00329 {
00330 CoordType V1 = hp->HVp()->cP();
00331 CoordType V2 = hp->HNp()->HNp()->HVp()->cP();
00332
00333 _priority = Distance( V1, V2 );
00334 return _priority;
00335 }
00336
00337 virtual const char *Info(MeshType &m)
00338 {
00339 static char buf[60];
00340 sprintf(buf,"(%d - %d) %g\n", hp->HVp()-&m.vert[0], hp->HNp()->HNp()->HVp()-&m.vert[0], -_priority);
00341 return buf;
00342 }
00343
00350 inline void Execute(MeshType &m)
00351 {
00352
00353
00354 ret = HalfEdgeTopology<MeshType>::diagonal_collapse_quad(m,hp->HFp(), hp->HVp());
00355
00356 if(ret->VHp())
00357 {
00358 set<FacePointer> tmp = HalfEdgeTopology<MeshType>::getFaces(ret);
00359
00360 vector<FacePointer> incident_faces = HalfEdgeTopology<MeshType>::get_incident_faces(ret,ret->VHp());
00361
00362 faces.insert(incident_faces.begin(), incident_faces.end());
00363
00364 HalfedgeQuadClean<MeshType>::remove_doublets(m, faces);
00365
00366
00367 if(!ret->IsD())
00368 {
00369 vector<HEdgePointer> hedges = HalfEdgeTopology<MeshType>::get_incident_hedges(ret,ret->VHp());
00370
00371 HalfedgeQuadClean<MeshType>:: template flip_edges<OptimizationType>(m, hedges, faces);
00372 }
00373
00374 faces.insert(tmp.begin(), tmp.end());
00375
00376
00377 set<VertexPointer> vertices;
00378
00379 for(typename set<FacePointer>::iterator fi = faces.begin(); fi != faces.end(); ++fi)
00380 {
00381 if(*fi)
00382 {
00383 if( !((*fi)->IsD()))
00384 {
00385 vector<VertexPointer> aux = HalfEdgeTopology<MeshType>::getVertices(*fi);
00386
00387 vertices.insert(aux.begin(),aux.end());
00388 }
00389 }
00390 }
00391
00392
00393
00394 for(unsigned int i = 0; i < smoothing_iterations(); i++)
00395 {
00396 for(typename set<VertexPointer>::iterator vi = vertices.begin(); vi!= vertices.end(); ++vi)
00397 if(!HalfEdgeTopology<MeshType>::isBorderVertex(*vi))
00398 Smooth<MeshType>::VertexCoordLaplacianReproject(m,*grid(), *refMesh(),*vi);
00399 }
00400
00401
00402
00403 for(typename set<VertexPointer>::iterator vi = vertices.begin(); vi!= vertices.end(); ++vi)
00404 {
00405 vector<FacePointer> tmp_faces = HalfEdgeTopology<MeshType>::get_incident_faces(*vi);
00406
00407 faces.insert(tmp_faces.begin(), tmp_faces.end());
00408 }
00409
00410 }
00411
00412
00413 }
00414
00422 inline void UpdateHeap(HeapType & h_ret)
00423 {
00424
00425 GlobalMark()++;
00426
00427 for(typename set<FacePointer>::iterator fi = faces.begin(); fi != faces.end(); ++fi)
00428 {
00429 if(*fi)
00430 {
00431 if( !((*fi)->IsD()))
00432 {
00433 (*fi)->IMark() = GlobalMark();
00434
00435 HEdgePointer start_he = (*fi)->FHp();
00436
00437 h_ret.push_back( HeapElem( new MYTYPE( start_he, GlobalMark() ) ) );
00438 std::push_heap( h_ret.begin(),h_ret.end() );
00439
00440 h_ret.push_back( HeapElem( new MYTYPE( start_he->HNp(), GlobalMark() ) ) );
00441 std::push_heap( h_ret.begin(),h_ret.end() );
00442 }
00443 }
00444 }
00445 }
00446
00447
00448 ModifierType IsOfType()
00449 {
00450 return QuadDiagCollapseOp;
00451 }
00452
00458 inline bool IsFeasible()
00459 {
00460 FacePointer fp = hp->HFp();
00461
00462 if(!fp)
00463 return false;
00464
00465 if(fp->IsD() || fp->VN() !=4)
00466 return false;
00467
00468 return ( HalfEdgeTopology<MeshType>::check_diagonal_collapse_quad(hp));
00469
00470 }
00471
00477 inline bool IsUpToDate()
00478 {
00479 FacePointer fp = hp->HFp();
00480
00481 if(fp)
00482 return (!hp->IsD() && localMark >= fp->IMark() );
00483
00484 return false;
00485
00486 }
00487
00493 virtual ScalarType Priority() const
00494 {
00495 return _priority;
00496 }
00497
00506 static void Init(MeshType &m,HeapType &h_ret)
00507 {
00508
00509 assert(grid());
00510 assert(refMesh());
00511
00512 assert(!HalfedgeQuadClean<MeshType>::has_doublets(m));
00513 assert(!HalfedgeQuadClean<MeshType>::has_singlets(m));
00514
00515 vcg::tri::InitFaceIMark(m);
00516
00517 h_ret.clear();
00518
00519 typename MeshType::FaceIterator fi;
00520 for(fi = m.face.begin(); fi != m.face.end();++fi)
00521 {
00522 if(!(*fi).IsD())
00523 {
00524
00525 h_ret.push_back( HeapElem(new MYTYPE( (*fi).FHp(), IMark(m))));
00526
00527 h_ret.push_back( HeapElem(new MYTYPE( (*fi).FHp()->HNp(), IMark(m))));
00528
00529 }
00530 }
00531
00532 }
00533
00534
00535 };
00536
00543 template<class MeshType, class MYTYPE, class TriMeshType, class OptimizationType, class WeightType, class CheckType >
00544 class QuadDiagonalCollapse: public QuadDiagonalCollapseBase<MeshType, MYTYPE, TriMeshType, OptimizationType>
00545 {
00546
00547 protected:
00548
00549 typedef Pos<MeshType> PosType;
00550 typedef typename MeshType::VertexPointer VertexPointer;
00551 typedef typename MeshType::FacePointer FacePointer;
00552 typedef typename MeshType::HEdgePointer HEdgePointer;
00553 typedef typename LocalOptimization<MeshType>::HeapElem HeapElem;
00554 typedef typename LocalOptimization<MeshType>::HeapType HeapType;
00555 typedef typename MeshType::ScalarType ScalarType;
00556 typedef typename MeshType::CoordType CoordType;
00557
00558 typedef typename TriMeshType::FaceType TriFaceType;
00559 typedef typename vcg::GridStaticPtr<TriFaceType, typename TriFaceType::ScalarType> GRID;
00560
00561 public:
00562
00564 QuadDiagonalCollapse(){}
00565
00572 QuadDiagonalCollapse(HEdgePointer he, int mark)
00573 {
00574 this->localMark = mark;
00575 this->hp = he;
00576 this->_priority = this->ComputePriority();
00577 }
00578
00584 ScalarType ComputePriority()
00585 {
00586 CoordType V1 = this->hp->HVp()->cP();
00587 CoordType V2 = this->hp->HNp()->HNp()->HVp()->cP();
00588
00589 CoordType P = (V1+V2)/2;
00590 float weight = WeightType::compute_weight(this->hp, P, *(this->refMesh()), *(this->grid()));
00591
00592 this->_priority = Distance( V1, V2 ) * weight;
00593 return this->_priority;
00594 }
00595
00601 bool IsFeasible()
00602 {
00603 FacePointer fp = this->hp->HFp();
00604
00605 if(!fp)
00606 return false;
00607
00608 if(fp->IsD() || fp->VN() !=4)
00609 return false;
00610
00611 if(!HalfEdgeTopology<MeshType>::check_diagonal_collapse_quad(this->hp))
00612 return false;
00613
00614 CoordType V1 = this->hp->HVp()->cP();
00615 CoordType V2 = this->hp->HNp()->HNp()->HVp()->cP();
00616
00617 return CheckType::check_feasible(this->hp, V1, V2, *(this->refMesh()), *(this->grid()));
00618
00619 }
00620
00621 };
00622
00623
00624 }
00625 }
00626
00627 #endif // QUAD_DIAGONAL_COLLAPSE_H