closest.h
Go to the documentation of this file.
00001 /****************************************************************************
00002 * VCGLib                                                            o o     *
00003 * Visual and Computer Graphics Library                            o     o   *
00004 *                                                                _   O  _   *
00005 * Copyright(C) 2004                                                \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00023 
00024 
00025 #ifndef __VCG_TRIMESH_CLOSEST
00026 #define __VCG_TRIMESH_CLOSEST
00027 #include <math.h>
00028 
00029 #include <vcg/space/point3.h>
00030 #include <vcg/space/box3.h>
00031 #include <vcg/space/point4.h>
00032 #include <vcg/space/index/grid_util.h>
00033 #include <vcg/space/index/grid_closest.h>
00034 #include <vcg/math/base.h>
00035 #include <vcg/simplex/face/distance.h>
00036 #include <vcg/simplex/edge/distance.h>
00037 #include <vcg/simplex/vertex/distance.h>
00038 #include <vcg/space/intersection3.h>
00039 #include <vcg/space/index/space_iterators.h>
00040 #include <vcg/complex/complex.h>
00041 
00042 namespace vcg {
00043     namespace tri {
00044 
00045         //**MARKER CLASSES**//
00046         template <class MESH_TYPE,class OBJ_TYPE>
00047         class Tmark
00048         {
00049             MESH_TYPE *m;
00050         public:
00051             Tmark(){}
00052             Tmark(      MESH_TYPE *m) {SetMesh(m);}
00053             void UnMarkAll(){ vcg::tri::UnMarkAll(*m);}
00054             bool IsMarked(OBJ_TYPE* obj){return (vcg::tri::IsMarked(*m,obj));}
00055             void Mark(OBJ_TYPE* obj){ vcg::tri::Mark(*m,obj);}
00056             void SetMesh(MESH_TYPE *_m)
00057             {
00058               tri::RequirePerFaceMark(*_m);
00059               m=_m;
00060             }
00061         };
00062 
00063         template <class MESH_TYPE>
00064         class FaceTmark:public Tmark<MESH_TYPE,typename MESH_TYPE::FaceType>
00065         {
00066         public:
00067             FaceTmark(){}
00068             FaceTmark(MESH_TYPE *m) {this->SetMesh(m);}
00069         };
00070         
00071         template <class MESH_TYPE>
00072         class EdgeTmark:public Tmark<MESH_TYPE,typename MESH_TYPE::EdgeType>
00073         {
00074         public:
00075             EdgeTmark(){}
00076             EdgeTmark(MESH_TYPE *m) {this->SetMesh(m);}
00077         };
00078         
00079 
00080         template <class MESH_TYPE>
00081         class EmptyTMark
00082         {
00083         public:
00084         typedef typename  MESH_TYPE::VertexType VertexType;
00085           typedef typename  MESH_TYPE::EdgeType EdgeType;
00086             inline EmptyTMark(){}
00087             inline EmptyTMark(MESH_TYPE *){}
00088             inline void UnMarkAll() const {}
00089             inline bool IsMarked(VertexType*) const { return false; }
00090             inline void Mark(VertexType*) const {}
00091             inline bool IsMarked(EdgeType*) const { return false; }
00092             inline void Mark(EdgeType*) const {}
00093             inline void SetMesh(void * /*m=0*/) const {}
00094         };
00095 
00096         //**CLOSEST FUNCTION DEFINITION**//
00097 
00098         /*
00099 
00100         aka MetroCore
00101         data una mesh m e una ug sulle sue facce trova il punto di m piu' vicino ad
00102         un punto dato.
00103         */
00104 
00105         // input: mesh, punto, griglia (gr), distanza limite (mdist)
00106         // output: normale (interpolata) alla faccia e punto piu' vicino su di essa, e coord baricentriche del punto trovato
00107 
00108         // Nota che il parametro template GRID non ci dovrebbe essere, visto che deve essere
00109         // UGrid<MESH::FaceContainer >, ma non sono riuscito a definirlo implicitamente
00110 
00111         template <class MESH, class GRID>
00112             typename MESH::FaceType * GetClosestFaceEP( MESH & mesh, GRID & gr, const typename GRID::CoordType & _p,
00113                                                         const typename GRID::ScalarType & _maxDist, typename GRID::ScalarType & _minDist,
00114                                                         typename GRID::CoordType & _closestPt, typename GRID::CoordType & _normf,
00115                                                         typename GRID::CoordType & _ip)
00116         {
00117             typedef typename GRID::ScalarType ScalarType;
00118 
00119             typedef FaceTmark<MESH> MarkerFace;
00120             MarkerFace mf(&mesh);
00121             vcg::face::PointDistanceEPFunctor<ScalarType> FDistFunct;
00122             _minDist=_maxDist;
00123             typename MESH::FaceType* bestf= gr.GetClosest(FDistFunct, mf, _p, _maxDist, _minDist, _closestPt);
00124 
00125             if(_maxDist> ScalarType(fabs(_minDist)))
00126             {
00127                 // f=bestf;
00128                 //calcolo normale con interpolazione trilineare
00129               InterpolationParameters<typename MESH::FaceType,typename MESH::ScalarType>(*bestf,bestf->N(),_closestPt, _ip);
00130               _normf =  (bestf->V(0)->cN())*_ip[0]+
00131                   (bestf->V(1)->cN())*_ip[1]+
00132                   (bestf->V(2)->cN())*_ip[2] ;
00133 
00134               _minDist = fabs(_minDist);
00135                 return(bestf);
00136             }
00137             return (0);
00138         }
00139 
00140     template <class MESH, class GRID>
00141     typename MESH::FaceType * GetClosestFaceBase( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00142                                                   const typename GRID::ScalarType _maxDist,typename GRID::ScalarType & _minDist,
00143                                                   typename GRID::CoordType &_closestPt)
00144     {
00145       typedef typename GRID::ScalarType ScalarType;
00146       typedef FaceTmark<MESH> MarkerFace;
00147       MarkerFace mf;
00148       mf.SetMesh(&mesh);
00149       vcg::face::PointDistanceBaseFunctor<ScalarType> PDistFunct;
00150       _minDist=_maxDist;
00151       return (gr.GetClosest(PDistFunct,mf,_p,_maxDist,_minDist,_closestPt));
00152     }
00153 
00154     template <class MESH, class GRID>
00155     typename MESH::FaceType * GetClosestFaceBase( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00156                                                   const typename GRID::ScalarType _maxDist,typename GRID::ScalarType & _minDist,
00157                                                   typename GRID::CoordType &_closestPt, typename GRID::CoordType & _normf,
00158                                                   typename GRID::CoordType & _ip)
00159     {
00160       typedef typename GRID::ScalarType ScalarType;
00161       typename MESH::FaceType * f = GetClosestFaceBase(mesh, gr, _p, _maxDist, _minDist, _closestPt);
00162       if(_maxDist> ScalarType(fabs(_minDist)))
00163       {
00164         // normal computed with trilinear interpolation
00165         InterpolationParameters<typename MESH::FaceType,typename MESH::ScalarType>(*f,f->N(),_closestPt, _ip);
00166         _normf =  (f->V(0)->cN())*_ip[0]+
00167                   (f->V(1)->cN())*_ip[1]+
00168                   (f->V(2)->cN())*_ip[2];
00169       }
00170       return f;
00171     }
00172 
00173         template <class MESH, class GRID>
00174             typename MESH::FaceType * GetClosestFaceEP( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00175             const typename GRID::ScalarType _maxDist, typename GRID::ScalarType & _minDist,
00176             typename GRID::CoordType &_closestPt)
00177         {
00178             typedef typename GRID::ScalarType ScalarType;
00179             typedef FaceTmark<MESH> MarkerFace;
00180             MarkerFace mf;
00181             mf.SetMesh(&mesh);
00182             vcg::face::PointDistanceEPFunctor<ScalarType> PDistFunct;
00183             _minDist=_maxDist;
00184             return (gr.GetClosest(PDistFunct,mf,_p,_maxDist,_minDist,_closestPt));
00185         }
00186 
00187         template <class MESH, class GRID>
00188         typename MESH::FaceType * GetClosestFaceNormal(MESH & mesh,GRID & gr,const typename MESH::VertexType & _p,
00189             const typename GRID::ScalarType & _maxDist,typename GRID::ScalarType & _minDist,
00190             typename GRID::CoordType &_closestPt)
00191         {
00192             typedef FaceTmark<MESH> MarkerFace;
00193             MarkerFace mf;
00194             mf.SetMesh(&mesh);
00195             typedef vcg::face::PointNormalDistanceFunctor<typename MESH::VertexType> PDistFunct;
00196             PDistFunct fn;
00197             _minDist=_maxDist;
00198             //return (gr.GetClosest(PDistFunct,mf,_p,_maxDist,_minDist,_closestPt.P()));
00199             return (gr.template GetClosest <PDistFunct,MarkerFace>(fn,mf,_p,_maxDist,_minDist,_closestPt));
00200         }
00201 
00202         template <class MESH, class GRID>
00203             typename MESH::VertexType * GetClosestVertex( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00204             const typename GRID::ScalarType & _maxDist,typename GRID::ScalarType & _minDist )
00205         {
00206             typedef typename GRID::ScalarType ScalarType;
00207             typedef Point3<ScalarType> Point3x;
00208             typedef EmptyTMark<MESH> MarkerVert;
00209             MarkerVert mv;
00210             mv.SetMesh(&mesh);
00211             typedef vcg::vertex::PointDistanceFunctor<typename MESH::ScalarType> VDistFunct;
00212             VDistFunct fn;
00213             _minDist=_maxDist;
00214             Point3x _closestPt;
00215             return (gr.template GetClosest<VDistFunct,MarkerVert>(fn,mv,_p,_maxDist,_minDist,_closestPt));
00216         }
00217 
00218         template <class MESH, class GRID>
00219             typename MESH::VertexType * GetClosestVertexScale( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00220             const typename MESH::CoordType & center, const typename GRID::ScalarType & _maxDist,typename GRID::ScalarType & _minDist )
00221         {
00222             typedef typename GRID::ScalarType ScalarType;
00223             typedef Point3<ScalarType> Point3x;
00224             typedef EmptyTMark<MESH> MarkerVert;
00225             MarkerVert mv;
00226             mv.SetMesh(&mesh);
00227             typedef vcg::vertex::PointScaledDistanceFunctor<typename MESH::VertexType> VDistFunct;
00228             VDistFunct fn;
00229             fn.Cen() = center;
00230             _minDist=_maxDist;
00231             Point3x _closestPt;
00232             return (gr.template GetClosest<VDistFunct,MarkerVert>(fn,mv,_p,_maxDist,_minDist,_closestPt));
00233         }
00234 
00235         template <class MESH, class GRID>
00236             typename MESH::VertexType * GetClosestVertexNormal( MESH & mesh,GRID & gr,const typename MESH::VertexType & _p,
00237             const typename GRID::ScalarType & _maxDist,typename GRID::ScalarType & _minDist )
00238         {
00239             typedef typename GRID::ScalarType ScalarType;
00240             typedef Point3<ScalarType> Point3x;
00241             typedef EmptyTMark<MESH> MarkerVert;
00242             MarkerVert mv;
00243             mv.SetMesh(&mesh);
00244             typedef vcg::vertex::PointNormalDistanceFunctor<typename MESH::VertexType> VDistFunct;
00245             VDistFunct fn;
00246             _minDist=_maxDist;
00247             Point3x _closestPt;
00248             return (gr.template GetClosest <VDistFunct,MarkerVert>(fn,mv,_p,_maxDist,_minDist,_closestPt));
00249         }
00250 
00251     template <class MESH, class GRID, class OBJPTRCONTAINER,class DISTCONTAINER, class POINTCONTAINER>
00252       unsigned int GetKClosestFaceEP(MESH & mesh,GRID & gr, const unsigned int _k,
00253       const typename GRID::CoordType & _p, const typename GRID::ScalarType & _maxDist,
00254       OBJPTRCONTAINER & _objectPtrs,DISTCONTAINER & _distances, POINTCONTAINER & _points)
00255     {
00256       typedef FaceTmark<MESH> MarkerFace;
00257       MarkerFace mf;
00258       mf.SetMesh(&mesh);
00259       vcg::face::PointDistanceEPFunctor<typename MESH::ScalarType> FDistFunct;
00260       return (gr.GetKClosest /*<vcg::face::PointDistanceFunctor, MarkerFace,OBJPTRCONTAINER,DISTCONTAINER,POINTCONTAINER>*/
00261         (FDistFunct,mf,_k,_p,_maxDist,_objectPtrs,_distances,_points));
00262     }
00263 
00264     // This version does not require that the face type has the
00265     // EdgePlane component and use a less optimized (but more memory efficient) point-triangle distance
00266     template <class MESH, class GRID, class OBJPTRCONTAINER,class DISTCONTAINER, class POINTCONTAINER>
00267       unsigned int GetKClosestFaceBase(MESH & mesh,GRID & gr, const unsigned int _k,
00268       const typename GRID::CoordType & _p, const typename GRID::ScalarType & _maxDist,
00269       OBJPTRCONTAINER & _objectPtrs,DISTCONTAINER & _distances, POINTCONTAINER & _points)
00270     {
00271       typedef FaceTmark<MESH> MarkerFace;
00272       MarkerFace mf;
00273       mf.SetMesh(&mesh);
00274       vcg::face::PointDistanceBaseFunctor<typename MESH::ScalarType> FDistFunct;
00275       return (gr.GetKClosest /*<vcg::face::PointDistanceFunctor, MarkerFace,OBJPTRCONTAINER,DISTCONTAINER,POINTCONTAINER>*/
00276         (FDistFunct,mf,_k,_p,_maxDist,_objectPtrs,_distances,_points));
00277     }
00278 
00279         template <class MESH, class GRID, class OBJPTRCONTAINER,class DISTCONTAINER, class POINTCONTAINER>
00280             unsigned int GetKClosestVertex(MESH & mesh,GRID & gr, const unsigned int _k,
00281             const typename GRID::CoordType & _p, const typename GRID::ScalarType & _maxDist,
00282             OBJPTRCONTAINER & _objectPtrs,DISTCONTAINER & _distances, POINTCONTAINER & _points)
00283         {
00284             typedef EmptyTMark<MESH> MarkerVert;
00285             MarkerVert mv;
00286             mv.SetMesh(&mesh);
00287             typedef vcg::vertex::PointDistanceFunctor<typename MESH::ScalarType> VDistFunct;
00288             VDistFunct distFunct;
00289             return (gr.GetKClosest/* <VDistFunct,MarkerVert,OBJPTRCONTAINER,DISTCONTAINER,POINTCONTAINER>*/
00290                 (distFunct,mv,_k,_p,_maxDist,_objectPtrs,_distances,_points));
00291         }
00292 
00293         template <class MESH, class GRID, class OBJPTRCONTAINER, class DISTCONTAINER, class POINTCONTAINER>
00294             unsigned int GetInSphereFaceBase(MESH & mesh,
00295             GRID & gr,
00296             const typename GRID::CoordType & _p,
00297             const typename GRID::ScalarType & _r,
00298             OBJPTRCONTAINER & _objectPtrs,
00299             DISTCONTAINER & _distances,
00300             POINTCONTAINER & _points)
00301         {
00302             typedef FaceTmark<MESH> MarkerFace;
00303             MarkerFace mf;
00304             mf.SetMesh(&mesh);
00305             typedef vcg::face::PointDistanceBaseFunctor<typename MESH::ScalarType> FDistFunct;
00306             return (gr.GetInSphere/*<FDistFunct,MarkerFace,OBJPTRCONTAINER,DISTCONTAINER,POINTCONTAINER>*/
00307                 (FDistFunct(),mf,_p,_r,_objectPtrs,_distances,_points));
00308         }
00309 
00310         template <class MESH, class GRID, class OBJPTRCONTAINER, class DISTCONTAINER, class POINTCONTAINER>
00311             unsigned int GetInSphereVertex(MESH & mesh,
00312             GRID & gr,
00313             const typename GRID::CoordType & _p,
00314             const typename GRID::ScalarType & _r,
00315             OBJPTRCONTAINER & _objectPtrs,
00316             DISTCONTAINER & _distances,
00317             POINTCONTAINER & _points)
00318         {
00319             typedef EmptyTMark<MESH> MarkerVert;
00320             MarkerVert mv;
00321             mv.SetMesh(&mesh);
00322             typedef vcg::vertex::PointDistanceFunctor<typename MESH::ScalarType> VDistFunct;
00323             VDistFunct fn;
00324             return (gr.GetInSphere/*<VDistFunct,MarkerVert,OBJPTRCONTAINER,DISTCONTAINER,POINTCONTAINER>*/
00325                 (fn, mv,_p,_r,_objectPtrs,_distances,_points));
00326         }
00327 
00328         template <class MESH, class GRID, class OBJPTRCONTAINER>
00329             unsigned int GetInBoxFace(MESH & mesh,
00330             GRID & gr,
00331             const vcg::Box3<typename GRID::ScalarType> _bbox,
00332             OBJPTRCONTAINER & _objectPtrs)
00333         {
00334             typedef FaceTmark<MESH> MarkerFace;
00335             MarkerFace mf(&mesh);
00336             return(gr.GetInBox/*<MarkerFace,OBJPTRCONTAINER>*/(mf,_bbox,_objectPtrs));
00337         }
00338 
00339         template <class MESH, class GRID, class OBJPTRCONTAINER>
00340             unsigned int GetInBoxVertex(MESH & mesh,
00341             GRID & gr,
00342             const vcg::Box3<typename GRID::ScalarType> _bbox,
00343             OBJPTRCONTAINER & _objectPtrs)
00344         {
00345             typedef EmptyTMark<MESH> MarkerVert;
00346             MarkerVert mv;
00347             mv.SetMesh(&mesh);
00348             return(gr.GetInBox/*<MarkerVert,OBJPTRCONTAINER>*/(mv,_bbox,_objectPtrs));
00349         }
00350 
00351         template <class MESH, class GRID>
00352             typename GRID::ObjPtr DoRay(MESH & mesh,GRID & gr, const Ray3<typename GRID::ScalarType> & _ray,
00353             const typename GRID::ScalarType & _maxDist, typename GRID::ScalarType & _t)
00354         {
00355             typedef FaceTmark<MESH> MarkerFace;
00356             MarkerFace mf;
00357             mf.SetMesh(&mesh);
00358             Ray3<typename GRID::ScalarType> _ray1=_ray;
00359             _ray1.Normalize();
00360             typedef vcg::RayTriangleIntersectionFunctor<true> FintFunct;
00361       FintFunct ff;
00362       return(gr.DoRay(ff,mf,_ray1,_maxDist,_t));
00363         }
00364 
00365         template <class MESH, class GRID>
00366             typename GRID::ObjPtr DoRay(MESH & mesh,GRID & gr, const Ray3<typename GRID::ScalarType> & _ray,
00367                                         const typename GRID::ScalarType & _maxDist,
00368                                         typename GRID::ScalarType & _t,
00369                                         typename GRID::CoordType & _normf)
00370         {
00371             typedef typename MESH::FaceType FaceType;
00372             typedef typename MESH::ScalarType ScalarType;
00373             typedef FaceTmark<MESH> MarkerFace;
00374             MarkerFace mf;
00375             mf.SetMesh(&mesh);
00376             typedef vcg::RayTriangleIntersectionFunctor<true> FintFunct;
00377             FintFunct fintfunct;
00378             Ray3<typename GRID::ScalarType> _ray1=_ray;
00379             _ray1.Normalize();
00380             FaceType *f=gr.DoRay(fintfunct,mf,_ray1,_maxDist,_t);
00381             typename GRID::CoordType dir=_ray.Direction();
00382             dir.Normalize();
00383             typename GRID::CoordType int_point=_ray.Origin()+_ray1.Direction()*_t;
00384             if (f!=NULL)
00385             {
00386                 Point3<typename GRID::ScalarType> bary;
00387                 InterpolationParameters<FaceType,ScalarType>(*f,f->N(),int_point, bary);
00388 
00389                 _normf =  (f->V(0)->cN())*bary.X()+
00390                                     (f->V(1)->cN())*bary.Y()+
00391                                     (f->V(2)->cN())*bary.Z() ;
00392             }
00393             return f;
00394         }
00395 
00398         template <class MESH, class GRID, class OBJPTRCONTAINER, class COORDCONTAINER>
00399             void RaySpherical(MESH & mesh,GRID & gr, const Ray3<typename GRID::ScalarType> & _ray,
00400                                                const typename GRID::ScalarType & _maxDist,
00401                                                const typename GRID::ScalarType & _theta_interval,
00402                                                const typename GRID::ScalarType & _phi_interval,
00403                                                const int &n_samples,
00404                                                OBJPTRCONTAINER & _objectPtrs,
00405                                                COORDCONTAINER & _pos,
00406                                                  COORDCONTAINER & _norm)
00407         {
00408             typedef typename MESH::FaceType FaceType;
00409             typedef typename MESH::ScalarType ScalarType;
00410             ScalarType delta_theta=_theta_interval/(ScalarType)(n_samples*2);
00411       ScalarType delta_phi  =_phi_interval/(ScalarType)(n_samples*2);
00412       ScalarType theta_init,phi_init,ro;
00413       typename GRID::CoordType dir0=_ray.Direction();
00414       dir0.ToPolarRad(ro,theta_init,phi_init);
00415             for (int x=-n_samples;x<=n_samples;x++)
00416                 for (int y=-n_samples;y<=n_samples;y++)
00417                 {
00418                     ScalarType theta=theta_init+x*delta_theta;
00419           if (theta<0) theta=2.0*M_PI-theta;
00420           ScalarType phi=phi_init+y*delta_phi;
00421 
00422           typename GRID::CoordType dir;
00423           dir.FromxPolar(ro,theta,phi);
00424                     dir.Normalize();
00425                     Ray3<typename GRID::ScalarType> curr_ray(_ray.Origin(),dir);
00426           typename GRID::ScalarType _t;
00427           typename GRID::ObjPtr f=NULL;
00428                     f=DoRay(mesh,gr,curr_ray,_maxDist,_t);
00429                     if (f!=NULL)
00430                     {
00431             typename GRID::CoordType pos=curr_ray.Origin()+curr_ray.Direction()*_t;
00432                         _objectPtrs.push_back(f);
00433                         _pos.push_back(pos);
00434 
00436                         typename GRID::ScalarType alfa,beta,gamma;
00437                         InterpolationParameters<FaceType,ScalarType>(*f,*f.N(),pos, alfa, beta, gamma);
00438                         typename GRID::CoordType norm =  (f->V(0)->cN())*alfa+
00439                                                                                          (f->V(1)->cN())*beta+
00440                                                                                          (f->V(2)->cN())*gamma ;
00441                         _norm.push_back(norm);
00442                     }
00443                 }
00444             }
00445 
00446         //**ITERATORS DEFINITION**//
00447 
00448         template <class GRID,class MESH>
00449         class ClosestFaceEPIterator:public vcg::ClosestIterator<GRID,
00450             vcg::face::PointDistanceEPFunctor<typename MESH::ScalarType>, FaceTmark<MESH> >
00451         {
00452         public:
00453             typedef GRID GridType;
00454             typedef MESH MeshType;
00455             typedef FaceTmark<MESH> MarkerFace;
00456             typedef vcg::face::PointDistanceEPFunctor<typename MESH::ScalarType> PDistFunct;
00457             typedef vcg::ClosestIterator<GRID,PDistFunct, FaceTmark<MESH> > ClosestBaseType;
00458             typedef typename MESH::FaceType FaceType;
00459             typedef typename MESH::ScalarType ScalarType;
00460 
00461             //ClosestFaceIterator(GridType &_Si):ClosestBaseType(_Si,PDistFunct<FaceType,ScalarType>()){}
00462             ClosestFaceEPIterator(GridType &_Si):ClosestBaseType(_Si,PDistFunct()){}
00463 
00464 //    Commented out: it seems unuseful and make gcc complain. p.
00465       void SetMesh(MeshType *m)
00466             {this->tm.SetMesh(m);}
00467         };
00468 
00469         template <class GRID,class MESH>
00470         class ClosestVertexIterator:public vcg::ClosestIterator<GRID, vcg::vertex::PointDistanceFunctor<typename MESH::ScalarType>, EmptyTMark<MESH> >
00471         {
00472         public:
00473             typedef GRID GridType;
00474             typedef MESH MeshType;
00475             typedef EmptyTMark<MESH> MarkerVert;
00476             typedef vcg::vertex::PointDistanceFunctor<typename MESH::ScalarType> VDistFunct;
00477             typedef vcg::ClosestIterator<GRID, VDistFunct, EmptyTMark<MESH> > ClosestBaseType;
00478             VDistFunct fn;
00479             ClosestVertexIterator(GridType &_Si):ClosestBaseType(_Si,fn){}
00480 
00481 //    Commented out: it seems unuseful and make gcc complain. p.
00482             void SetMesh(MeshType *m)
00483             {this->tm.SetMesh(m);}
00484         };
00485 
00486         template <class GRID,class MESH>
00487         class TriRayIterator:public vcg::RayIterator<GRID,vcg::RayTriangleIntersectionFunctor<true>,FaceTmark<MESH> >
00488         {
00489         public:
00490             typedef GRID GridType;
00491             typedef MESH MeshType;
00492             typedef FaceTmark<MESH> MarkerFace;
00493             typedef vcg::RayTriangleIntersectionFunctor<true> FintFunct;
00494             typedef vcg::RayIterator<GRID,FintFunct, FaceTmark<MESH> > RayBaseType;
00495             typedef typename MESH::FaceType FaceType;
00496             typedef typename MESH::ScalarType ScalarType;
00497 
00498             TriRayIterator(GridType &_Si,const ScalarType &max_d):RayBaseType(_Si,FintFunct(),max_d){}
00499 
00500 //    Commented out: it  seems unuseful and make gcc complain. p.
00501             void SetMesh(MeshType *m)
00502             {this->tm.SetMesh(m);}
00503 
00504         };
00505 
00507         template <class MESH, class GRID>
00508             typename MESH::EdgeType * GetClosestEdge2DBase( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00509                                                           const typename GRID::ScalarType _maxDist,typename GRID::ScalarType & _minDist,
00510                                                           typename GRID::CoordType &_closestPt)
00511         {
00512             typedef typename GRID::ScalarType ScalarType;
00513             typedef FaceTmark<MESH> MarkerFace;
00514             MarkerFace mf;
00515             mf.SetMesh(&mesh);
00516             vcg::PointSegment2DEPFunctor<ScalarType> PDistFunct;
00517             _minDist=_maxDist;
00518             return (gr.GetClosest(PDistFunct,mf,_p,_maxDist,_minDist,_closestPt));
00519         }
00520 
00522         template <class MESH, class GRID>
00523             typename MESH::EdgeType * GetClosestEdgeBase( MESH & mesh,GRID & gr,const typename GRID::CoordType & _p,
00524                                                           const typename GRID::ScalarType _maxDist,typename GRID::ScalarType & _minDist,
00525                                                           typename GRID::CoordType &_closestPt)
00526         {
00527             typedef typename GRID::ScalarType ScalarType;
00528             typedef EmptyTMark<MESH> MarkerEdge;
00529             MarkerEdge mf;
00530             mf.SetMesh(&mesh);
00531             vcg::edge::PointDistanceFunctor<ScalarType> PDistFunct;
00532             _minDist=_maxDist;
00533 //            return (gr.GetClosest(PDistFunct,mf,_p,_maxDist,_minDist,_closestPt));
00534             return vcg::GridClosest(gr,PDistFunct,mf, _p,_maxDist,_minDist,_closestPt);
00535         }
00536 
00537     }    // end namespace tri
00538 }        // end namespace vcg
00539 
00540 #endif


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:29:32