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/simplex/face/pos.h>
00024 #include <vcg/simplex/face/topology.h>
00025 #include <vcg/complex/algorithms/update/quality.h>
00026 #include <deque>
00027 #include <functional>
00028 #ifndef __VCGLIB_GEODESIC
00029 #define __VCGLIB_GEODESIC
00030
00031 namespace vcg{
00032 namespace tri{
00033
00034 template <class MeshType>
00035 struct EuclideanDistance{
00036 typedef typename MeshType::VertexType VertexType;
00037 typedef typename MeshType::ScalarType ScalarType;
00038 typedef typename MeshType::FacePointer FacePointer;
00039
00040 EuclideanDistance(){}
00041
00042 ScalarType operator()(const VertexType * v0, const VertexType * v1) const
00043 {return vcg::Distance(v0->cP(),v1->cP());}
00044
00045 ScalarType operator()(const FacePointer f0, const FacePointer f1) const
00046 {return vcg::Distance(Barycenter(*f0),Barycenter(*f1));}
00047 };
00048
00049
00050 template <class MeshType>
00051 class IsotropicDistance{
00052 private:
00053
00054 typename MeshType::template PerVertexAttributeHandle<float> wH;
00055 public:
00056 typedef typename MeshType::VertexType VertexType;
00057 typedef typename MeshType::ScalarType ScalarType;
00058 typedef typename MeshType::FacePointer FacePointer;
00059
00065
00066 IsotropicDistance(MeshType &m, float variance)
00067 {
00068
00069 wH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<float> (m,"distW");
00070 float qmin = 1.0f/variance;
00071 float qmax = variance;
00072 float qrange = qmax-qmin;
00073 std::pair<float,float> minmax = Stat<MeshType>::ComputePerVertexQualityMinMax(m);
00074 float range = minmax.second-minmax.first;
00075 for(size_t i=0;i<m.vert.size();++i)
00076 wH[i]=qmin+((m.vert[i].Q()-minmax.first)/range)*qrange;
00077
00078
00079 }
00080
00081 ScalarType operator()( VertexType * v0, VertexType * v1)
00082 {
00083 float scale = (wH[v0]+wH[v1])/2.0f;
00084 return (1.0f/scale)*vcg::Distance(v0->cP(),v1->cP());
00085 }
00086 };
00087
00088
00089 template <class MeshType>
00090 struct BasicCrossFunctor
00091 {
00092 BasicCrossFunctor(MeshType &m) { tri::RequirePerVertexCurvatureDir(m); }
00093 typedef typename MeshType::VertexType VertexType;
00094
00095 typename MeshType::CoordType D1(VertexType &v) { return v.PD1(); }
00096 typename MeshType::CoordType D2(VertexType &v) { return v.PD2(); }
00097 };
00098
00107 template <class MeshType>
00108 class AnisotropicDistance{
00109 typedef typename MeshType::VertexType VertexType;
00110 typedef typename MeshType::ScalarType ScalarType;
00111 typedef typename MeshType::CoordType CoordType;
00112 typedef typename MeshType::VertexIterator VertexIterator;
00113
00114 typename MeshType::template PerVertexAttributeHandle<CoordType> wxH,wyH;
00115 public:
00116 template <class CrossFunctor > AnisotropicDistance(MeshType &m, CrossFunctor &cf)
00117 {
00118 wxH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<CoordType> (m,"distDirX");
00119 wyH = tri::Allocator<MeshType>:: template GetPerVertexAttribute<CoordType> (m,"distDirY");
00120
00121 for(VertexIterator vi=m.vert.begin();vi!=m.vert.end();++vi)
00122 {
00123 wxH[vi]=cf.D1(*vi);
00124 wyH[vi]=cf.D2(*vi);
00125 }
00126 }
00127
00128 ScalarType operator()( VertexType * v0, VertexType * v1)
00129 {
00130 CoordType dd = v0->cP()-v1->cP();
00131 float x = (fabs(dd * wxH[v0])+fabs(dd *wxH[v1]))/2.0f;
00132 float y = (fabs(dd * wyH[v0])+fabs(dd *wyH[v1]))/2.0f;
00133
00134 return sqrt(x*x+y*y);
00135 }
00136 };
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00153 template <class MeshType>
00154 class Geodesic{
00155
00156 public:
00157
00158 typedef typename MeshType::VertexType VertexType;
00159 typedef typename MeshType::VertexIterator VertexIterator;
00160 typedef typename MeshType::VertexPointer VertexPointer;
00161 typedef typename MeshType::FacePointer FacePointer;
00162 typedef typename MeshType::FaceType FaceType;
00163 typedef typename MeshType::CoordType CoordType;
00164 typedef typename MeshType::ScalarType ScalarType;
00165
00166
00167
00168
00169 struct VertDist{
00170 VertDist(){}
00171 VertDist(VertexPointer _v, ScalarType _d):v(_v),d(_d){}
00172
00173 VertexPointer v;
00174 ScalarType d;
00175 };
00176
00177
00178 struct DIJKDist{
00179 DIJKDist(VertexPointer _v):v(_v){}
00180 VertexPointer v;
00181
00182 bool operator < (const DIJKDist &o) const
00183 {
00184 if( v->Q() != o.v->Q())
00185 return v->Q() > o.v->Q();
00186 return v<o.v;
00187 }
00188 };
00189
00190
00191 struct FaceDist{
00192 FaceDist(FacePointer _f):f(_f){}
00193 FacePointer f;
00194 bool operator < (const FaceDist &o) const
00195 {
00196 if( f->Q() != o.f->Q())
00197 return f->Q() > o.f->Q();
00198 return f<o.f;
00199 }
00200 };
00201
00202
00203 struct TempData{
00204 TempData(){}
00205 TempData(const ScalarType & _d):d(_d),source(0),parent(0){}
00206
00207 ScalarType d;
00208 VertexPointer source;
00209 VertexPointer parent;
00210 };
00211
00212 typedef SimpleTempData<std::vector<VertexType>, TempData > TempDataType;
00213
00214
00215 struct pred: public std::binary_function<VertDist,VertDist,bool>{
00216 pred(){}
00217 bool operator()(const VertDist& v0, const VertDist& v1) const
00218 {return (v0.d > v1.d);}
00219 };
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242 template <class DistanceFunctor>
00243 static ScalarType Distance(DistanceFunctor &distFunc,
00244 const VertexPointer &pw,
00245 const VertexPointer &pw1,
00246 const VertexPointer &curr,
00247 const ScalarType &d_pw1,
00248 const ScalarType &d_curr)
00249 {
00250 ScalarType curr_d=0;
00251
00252 ScalarType ew_c = distFunc(pw,curr);
00253 ScalarType ew_w1 = distFunc(pw,pw1);
00254 ScalarType ec_w1 = distFunc(pw1,curr);
00255 CoordType w_c = (pw->cP()-curr->cP()).Normalize() * ew_c;
00256 CoordType w_w1 = (pw->cP() - pw1->cP()).Normalize() * ew_w1;
00257 CoordType w1_c = (pw1->cP() - curr->cP()).Normalize() * ec_w1;
00258
00259 ScalarType alpha,alpha_, beta,beta_,theta,h,delta,s,a,b;
00260
00261 alpha = acos((w_c.dot(w1_c))/(ew_c*ec_w1));
00262 s = (d_curr + d_pw1+ec_w1)/2;
00263 a = s/ec_w1;
00264 b = a*s;
00265 alpha_ = 2*acos ( std::min<ScalarType>(1.0,sqrt( (b- a* d_pw1)/d_curr)));
00266
00267 if ( alpha+alpha_ > M_PI){
00268 curr_d = d_curr + ew_c;
00269 }else
00270 {
00271 beta_ = 2*acos ( std::min<ScalarType>(1.0,sqrt( (b- a* d_curr)/d_pw1)));
00272 beta = acos((w_w1).dot(-w1_c)/(ew_w1*ec_w1));
00273
00274 if ( beta+beta_ > M_PI)
00275 curr_d = d_pw1 + ew_w1;
00276 else
00277 {
00278 theta = ScalarType(M_PI)-alpha-alpha_;
00279 delta = cos(theta)* ew_c;
00280 h = sin(theta)* ew_c;
00281 curr_d = sqrt( pow(h,2)+ pow(d_curr + delta,2));
00282 }
00283 }
00284 return (curr_d);
00285 }
00286
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298 template <class DistanceFunctor>
00299 static VertexPointer Visit(
00300 MeshType & m,
00301 std::vector<VertDist> & seedVec,
00302 DistanceFunctor &distFunc,
00303 ScalarType distance_threshold = std::numeric_limits<ScalarType>::max(),
00304 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * vertSource = NULL,
00305 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * vertParent = NULL,
00306 std::vector<VertexPointer> *InInterval=NULL)
00307 {
00308 VertexPointer farthest=0;
00309
00310
00311 tri::RequireVFAdjacency(m);
00312 tri::RequirePerVertexQuality(m);
00313
00314 assert(!seedVec.empty());
00315
00316 TempDataType TD(m.vert, std::numeric_limits<ScalarType>::max());
00317
00318
00319 std::vector<VertDist> frontierHeap;
00320 typename std::vector <VertDist >::iterator ifr;
00321 for(ifr = seedVec.begin(); ifr != seedVec.end(); ++ifr){
00322 TD[(*ifr).v].d = (*ifr).d;
00323 TD[(*ifr).v].source = (*ifr).v;
00324 TD[(*ifr).v].parent = (*ifr).v;
00325 frontierHeap.push_back(*ifr);
00326 }
00327 make_heap(frontierHeap.begin(),frontierHeap.end(),pred());
00328
00329 ScalarType curr_d,d_curr = 0.0,d_heap;
00330 ScalarType max_distance=0.0;
00331
00332 while(!frontierHeap.empty() && max_distance < distance_threshold)
00333 {
00334 pop_heap(frontierHeap.begin(),frontierHeap.end(),pred());
00335 VertexPointer curr = (frontierHeap.back()).v;
00336 if (InInterval!=NULL) InInterval->push_back(curr);
00337
00338 if(vertSource!=NULL) (*vertSource)[curr] = TD[curr].source;
00339 if(vertParent!=NULL) (*vertParent)[curr] = TD[curr].parent;
00340
00341 d_heap = (frontierHeap.back()).d;
00342 frontierHeap.pop_back();
00343
00344 assert(TD[curr].d <= d_heap);
00345 if(TD[curr].d < d_heap )
00346 continue;
00347 assert(TD[curr].d == d_heap);
00348
00349 d_curr = TD[curr].d;
00350
00351 for(face::VFIterator<FaceType> vfi(curr) ; vfi.f!=0; ++vfi )
00352 {
00353 for(int k=0;k<2;++k)
00354 {
00355 VertexPointer pw,pw1;
00356 if(k==0) {
00357 pw = vfi.f->V1(vfi.z);
00358 pw1= vfi.f->V2(vfi.z);
00359 }
00360 else {
00361 pw = vfi.f->V2(vfi.z);
00362 pw1= vfi.f->V1(vfi.z);
00363 }
00364
00365 const ScalarType & d_pw1 = TD[pw1].d;
00366 {
00367 const ScalarType inter = distFunc(curr,pw1);
00368 const ScalarType tol = (inter + d_curr + d_pw1)*.0001f;
00369
00370 if ( (TD[pw1].source != TD[curr].source)||
00371 (inter + d_curr < d_pw1 +tol ) ||
00372 (inter + d_pw1 < d_curr +tol ) ||
00373 (d_curr + d_pw1 < inter +tol )
00374 )
00375 curr_d = d_curr + distFunc(pw,curr);
00376 else
00377 curr_d = Distance(distFunc,pw,pw1,curr,d_pw1,d_curr);
00378 }
00379
00380 if(TD[pw].d > curr_d){
00381 TD[pw].d = curr_d;
00382 TD[pw].source = TD[curr].source;
00383 TD[pw].parent = curr;
00384 frontierHeap.push_back(VertDist(pw,curr_d));
00385 push_heap(frontierHeap.begin(),frontierHeap.end(),pred());
00386 }
00387
00388 if(d_curr > max_distance){
00389 max_distance = d_curr;
00390 farthest = curr;
00391 }
00392
00393 }
00394 }
00395 }
00396
00397
00398
00399 if (InInterval==NULL)
00400 {
00401 for(VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi) if(!(*vi).IsD())
00402 (*vi).Q() = TD[&(*vi)].d;
00403 }
00404 else
00405 {
00406 assert(InInterval->size()>0);
00407 for(size_t i=0;i<InInterval->size();i++)
00408 (*InInterval)[i]->Q() = TD[(*InInterval)[i]].d;
00409 }
00410
00411
00412 return farthest;
00413 }
00414
00415 public:
00447 static bool Compute( MeshType & m,
00448 const std::vector<VertexPointer> & seedVec)
00449 {
00450 EuclideanDistance<MeshType> dd;
00451 return Compute(m,seedVec,dd);
00452 }
00453
00454 template <class DistanceFunctor>
00455 static bool Compute( MeshType & m,
00456 const std::vector<VertexPointer> & seedVec,
00457 DistanceFunctor &distFunc,
00458 ScalarType maxDistanceThr = std::numeric_limits<ScalarType>::max(),
00459 std::vector<VertexPointer> *withinDistanceVec=NULL,
00460 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * sourceSeed = NULL,
00461 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * parentSeed = NULL
00462 )
00463 {
00464 if(seedVec.empty()) return false;
00465 std::vector<VertDist> vdSeedVec;
00466 typename std::vector<VertexPointer>::const_iterator fi;
00467 for( fi = seedVec.begin(); fi != seedVec.end() ; ++fi)
00468 vdSeedVec.push_back(VertDist(*fi,0.0));
00469 Visit(m, vdSeedVec, distFunc, maxDistanceThr, sourceSeed, parentSeed, withinDistanceVec);
00470 return true;
00471 }
00472
00473
00474
00475
00476
00477
00478
00479
00480 static bool DistanceFromBorder( MeshType & m, typename MeshType::template PerVertexAttributeHandle<VertexPointer> * sources = NULL)
00481 {
00482 std::vector<VertexPointer> fro;
00483 for(VertexIterator vi = m.vert.begin(); vi != m.vert.end(); ++vi)
00484 if( (*vi).IsB())
00485 fro.push_back(&(*vi));
00486 if(fro.empty()) return false;
00487 EuclideanDistance<MeshType> dd;
00488 tri::UpdateQuality<MeshType>::VertexConstant(m,0);
00489 return Compute(m,fro,dd,std::numeric_limits<ScalarType>::max(),0,sources);
00490 }
00491
00492
00493 static bool ConvertPerVertexSeedToPerFaceSeed(MeshType &m, const std::vector<VertexPointer> &vertexSeedVec,
00494 std::vector<FacePointer> &faceSeedVec)
00495 {
00496 tri::RequireVFAdjacency(m);
00497 tri::RequirePerFaceMark(m);
00498
00499 faceSeedVec.clear();
00500 tri::UnMarkAll(m);
00501 for(size_t i=0;i<vertexSeedVec.size();++i)
00502 {
00503 for(face::VFIterator<FaceType> vfi(vertexSeedVec[i]);!vfi.End();++vfi)
00504 {
00505 if(tri::IsMarked(m,vfi.F())) return false;
00506 faceSeedVec.push_back(vfi.F());
00507 tri::Mark(m,vfi.F());
00508 }
00509 }
00510 return true;
00511 }
00512
00513 static inline std::string sourcesAttributeName(void) { return "sources"; }
00514 static inline std::string parentsAttributeName(void) { return "parent"; }
00515
00516 template <class DistanceFunctor>
00517 static void PerFaceDijsktraCompute(MeshType &m, const std::vector<FacePointer> &seedVec,
00518 DistanceFunctor &distFunc,
00519 ScalarType maxDistanceThr = std::numeric_limits<ScalarType>::max(),
00520 std::vector<FacePointer> *InInterval=NULL,
00521 FacePointer FaceTarget=NULL,
00522 bool avoid_selected=false)
00523 {
00524 tri::RequireFFAdjacency(m);
00525 tri::RequirePerFaceMark(m);
00526 tri::RequirePerFaceQuality(m);
00527
00528 typename MeshType::template PerFaceAttributeHandle<FacePointer> sourceHandle
00529 = tri::Allocator<MeshType>::template GetPerFaceAttribute<FacePointer>(m, sourcesAttributeName());
00530
00531 typename MeshType::template PerFaceAttributeHandle<FacePointer> parentHandle
00532 = tri::Allocator<MeshType>::template GetPerFaceAttribute<FacePointer>(m, parentsAttributeName());
00533
00534 std::vector<FaceDist> Heap;
00535 tri::UnMarkAll(m);
00536 for(size_t i=0;i<seedVec.size();++i)
00537 {
00538 tri::Mark(m,seedVec[i]);
00539 seedVec[i]->Q()=0;
00540 sourceHandle[seedVec[i]]=seedVec[i];
00541 parentHandle[seedVec[i]]=seedVec[i];
00542 Heap.push_back(FaceDist(seedVec[i]));
00543 if (InInterval!=NULL) InInterval->push_back(seedVec[i]);
00544 }
00545
00546 std::make_heap(Heap.begin(),Heap.end());
00547 while(!Heap.empty())
00548 {
00549 pop_heap(Heap.begin(),Heap.end());
00550 FacePointer curr = (Heap.back()).f;
00551 if ((FaceTarget!=NULL)&&(curr==FaceTarget))return;
00552 Heap.pop_back();
00553
00554 for(int i=0;i<3;++i)
00555 {
00556 if(!face::IsBorder(*curr,i) )
00557 {
00558 FacePointer nextF = curr->FFp(i);
00559 ScalarType nextDist = curr->Q() + distFunc(curr,nextF);
00560 if( (nextDist < maxDistanceThr) &&
00561 (!tri::IsMarked(m,nextF) || nextDist < nextF->Q()) )
00562 {
00563 nextF->Q() = nextDist;
00564 if ((avoid_selected)&&(nextF->IsS()))continue;
00565 tri::Mark(m,nextF);
00566 Heap.push_back(FaceDist(nextF));
00567 push_heap(Heap.begin(),Heap.end());
00568 if (InInterval!=NULL) InInterval->push_back(nextF);
00569 sourceHandle[nextF] = sourceHandle[curr];
00570 parentHandle[nextF] = curr;
00571
00572 }
00573 }
00574 }
00575 }
00576 }
00577
00578
00579
00580
00581 template <class DistanceFunctor>
00582 static void PerVertexDijsktraCompute(MeshType &m, const std::vector<VertexPointer> &seedVec,
00583 DistanceFunctor &distFunc,
00584 ScalarType maxDistanceThr = std::numeric_limits<ScalarType>::max(),
00585 std::vector<VertexPointer> *InInterval=NULL,
00586 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * sourceHandle= NULL,
00587 typename MeshType::template PerVertexAttributeHandle<VertexPointer> * parentHandle=NULL,
00588 bool avoid_selected=false,
00589 VertexPointer target=NULL)
00590 {
00591 tri::RequireVFAdjacency(m);
00592 tri::RequirePerVertexMark(m);
00593 tri::RequirePerVertexQuality(m);
00594
00595
00596
00597
00598
00599
00600
00601 std::vector<DIJKDist> Heap;
00602 tri::UnMarkAll(m);
00603
00604 for(size_t i=0;i<seedVec.size();++i)
00605 {
00606 assert(!tri::IsMarked(m,seedVec[i]));
00607 tri::Mark(m,seedVec[i]);
00608 seedVec[i]->Q()=0;
00609 if (sourceHandle!=NULL)
00610 (*sourceHandle)[seedVec[i]]=seedVec[i];
00611 if (parentHandle!=NULL)
00612 (*parentHandle)[seedVec[i]]=seedVec[i];
00613 Heap.push_back(DIJKDist(seedVec[i]));
00614 if (InInterval!=NULL) InInterval->push_back(seedVec[i]);
00615 }
00616
00617 std::make_heap(Heap.begin(),Heap.end());
00618 while(!Heap.empty())
00619 {
00620 pop_heap(Heap.begin(),Heap.end());
00621 VertexPointer curr = (Heap.back()).v;
00622 if ((target!=NULL)&&(target==curr))return;
00623 Heap.pop_back();
00624 std::vector<VertexPointer> vertVec;
00625 face::VVStarVF<FaceType>(curr,vertVec);
00626 for(size_t i=0;i<vertVec.size();++i)
00627 {
00628 VertexPointer nextV = vertVec[i];
00629 if ((avoid_selected)&&(nextV->IsS()))continue;
00630 ScalarType nextDist = curr->Q() + distFunc(curr,nextV);
00631 if( (nextDist < maxDistanceThr) &&
00632 (!tri::IsMarked(m,nextV) || nextDist < nextV->Q()) )
00633 {
00634 nextV->Q() = nextDist;
00635 tri::Mark(m,nextV);
00636 Heap.push_back(DIJKDist(nextV));
00637 push_heap(Heap.begin(),Heap.end());
00638 if (InInterval!=NULL) InInterval->push_back(nextV);
00639 if (sourceHandle!=NULL)
00640 (*sourceHandle)[nextV] = (*sourceHandle)[curr];
00641 if (parentHandle!=NULL)
00642 (*parentHandle)[nextV] = curr;
00643
00644 }
00645 }
00646 }
00647 }
00648
00649
00650 };
00651 }
00652 }
00653 #endif