Classes | Typedefs | Functions | Variables
Trimesh

Classes

class  vcg::tri::_SphFace
class  vcg::tri::_SphMesh
struct  vcg::tri::_SphUsedTypes
class  vcg::tri::_SphVertex
class  vcg::tri::Allocator< MeshType >
 Class to safely add and delete elements in a mesh. More...
class  vcg::tri::Append< MeshLeft, ConstMeshRight >
 Class to safely duplicate and append (portion of) meshes. More...
struct  vcg::tri::BaseMeshTypeHolder< TYPESPOOL >
class  vcg::tri::Clean< CleanMeshType >
 Class of static functions to clean//restore meshs. More...
class  vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo
class  vcg::tri::CoM< MeshType >
 A class for managing curves on a 2manifold. More...
struct  vcg::tri::Der< T, CONT >
struct  vcg::tri::DummyContainer
class  vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >
struct  vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet
class  vcg::tri::ExtendedMarchingCubes< TRIMESH_TYPE, WALKER_TYPE >
 This class implements the Extended Marching Cubes algorithm. More...
class  vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat
 static data to gather statistical information about the reasons of collapse failures More...
class  vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo
class  vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo
class  vcg::tri::MarchingCubes< TRIMESH_TYPE, WALKER_TYPE >
 This class implements the Marching Cubes algorithm. More...
struct  vcg::tri::MeshTypeHolder< T, CONT, TRAIT >
struct  vcg::tri::MeshTypeHolder< T, CONT, AllTypes::AEdgeType >
struct  vcg::tri::MeshTypeHolder< T, CONT, AllTypes::AFaceType >
struct  vcg::tri::MeshTypeHolder< T, CONT, AllTypes::AHEdgeType >
struct  vcg::tri::MeshTypeHolder< T, CONT, AllTypes::AVertexType >
class  vcg::tri::Nring< MeshType >
struct  vcg::tri::PointCloudNormal< MeshType >::Param
 parameters for the normal generation More...
class  vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo
class  vcg::tri::Smooth< SmoothMeshType >::PDVertInfo
class  vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >
class  vcg::tri::PlanarEdgeFlipParameter
class  vcg::tri::PointCloudNormal< MeshType >
 Class of static functions to smooth and fair meshes and their attributes. More...
class  vcg::tri::PolygonSupport< TriMeshType, PolyMeshType >
 This class is used convert between polygonal meshes and triangular meshes. More...
class  vcg::tri::Smooth< SmoothMeshType >::QualitySmoothInfo
class  vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >
class  vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo
class  vcg::tri::SelectionStack< ComputeMeshType >
 A stack for saving and restoring selection. More...
class  vcg::tri::Smooth< SmoothMeshType >
 Class of static functions to smooth and fair meshes and their attributes. More...
class  vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >
class  vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >
class  vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >
class  vcg::tri::TriMesh< Container0, Container1, Container2, Container3 >
 The official mesh class. More...
class  vcg::tri::TrivialSampler< MeshType >
 A basic sampler class that show the required interface used by the SurfaceSampling class. More...
class  vcg::tri::UpdateBounding< ComputeMeshType >
 This class is used to compute or update the bounding box of a mesh.. More...
class  vcg::tri::UpdateColor< MeshType >
 Generation and processing of per-vertex and per-face colors according to various strategy. More...
class  vcg::tri::UpdateComponentEP< ComputeMeshType >
 This class is used to compute or update the precomputed data used to efficiently compute point-face distances. More...
class  vcg::tri::UpdateCurvature< MeshType >
 Management, updating and computation of per-vertex and per-face normals. More...
class  vcg::tri::UpdateCurvatureFitting< MeshType >
 Computation of per-vertex directions and values of curvature. More...
class  vcg::tri::UpdateFlags< UpdateMeshType >
 Management, updating and computation of per-vertex and per-face flags (like border flags). More...
class  vcg::tri::UpdateHalfEdges< MeshType >
 This class is used to build edge based data structure from indexed data structure and viceversa. More...
class  vcg::tri::UpdateNormal< ComputeMeshType >
 Management, updating and computation of per-vertex, per-face, and per-wedge normals. More...
class  vcg::tri::UpdatePosition< ComputeMeshType >
 This class is used to update vertex position according to a transformation matrix. More...
class  vcg::tri::UpdateQuality< UpdateMeshType >
 Generation of per-vertex and per-face qualities. More...
class  vcg::tri::UpdateSelection< ComputeMeshType >
 Management, updating and conditional computation of selections (per-vertex, per-edge, and per-face). More...
class  vcg::tri::UpdateTexture< ComputeMeshType >
 This class is used to update/generate texcoord position according to various critera. . More...
class  vcg::tri::UpdateTopology< UpdateMeshType >
 Generation of per-vertex and per-face topological information. More...
class  vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker
class  vcg::tri::PointCloudNormal< MeshType >::WArc
class  vcg::tri::Zonohedron< Scalar >

Typedefs

typedef vcg::Box3< ScalarTypevcg::tri::Smooth< SmoothMeshType >::Box3Type
typedef
MeshType::VertexType::CoordType 
vcg::tri::PointCloudNormal< MeshType >::CoordType
typedef MeshType::CoordType vcg::tri::Nring< MeshType >::CoordType
typedef
MeshType::VertexType::CoordType 
vcg::tri::Smooth< SmoothMeshType >::CoordType
typedef
FaceType::VertexType::CoordType 
vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::CoordType
 The coordinate type.
typedef
FaceType::VertexType::CoordType 
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::CoordType
typedef TRIMESH_TYPE::CoordType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::CoordType
typedef TRIMESH_TYPE::CoordType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::CoordType
typedef TRIMESH_TYPE::CoordType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::CoordType
typedef MeshType::FaceContainer vcg::tri::Smooth< SmoothMeshType >::FaceContainer
typedef TriMeshType::FaceContainer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceContainer
 the container of tetrahedron type
typedef MeshType::FaceIterator vcg::tri::Nring< MeshType >::FaceIterator
typedef MeshType::FaceIterator vcg::tri::Smooth< SmoothMeshType >::FaceIterator
typedef TriMeshType::FaceIterator vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceIterator
 The tetra iterator type.
typedef TRIMESH_TYPE::FaceIterator vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FaceIterator
typedef TRIMESH_TYPE::FaceIterator vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceIterator
typedef MeshType::FacePointer vcg::tri::Smooth< SmoothMeshType >::FacePointer
typedef TRIMESH_TYPE::FacePointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FacePointer
typedef TRIMESH_TYPE::FacePointer vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FacePointer
typedef MeshType::FaceType vcg::tri::Nring< MeshType >::FaceType
typedef MeshType::FaceType vcg::tri::Smooth< SmoothMeshType >::FaceType
typedef TriMeshType::FaceType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceType
 The face type.
typedef TRIMESH_TYPE::FaceType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FaceType
typedef TriMeshType::FaceType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FaceType
typedef TRIMESH_TYPE::FaceType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceType
typedef TRIMESH_TYPE::FaceType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceType
typedef std::pair< bool, float > vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::field_value
typedef vcg::GridStaticPtr
< OldFaceType, OldScalarType > 
vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GridType
typedef LocalOptimization
< TriMeshType >::HeapElem 
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::HeapElem
typedef LocalOptimization
< TRIMESH_TYPE >::HeapElem 
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapElem
typedef LocalOptimization
< TRIMESH_TYPE >::HeapElem 
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::HeapElem
typedef LocalOptimization
< TriMeshType >::HeapType 
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::HeapType
typedef LocalOptimization
< TRIMESH_TYPE >::HeapType 
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapType
typedef LocalOptimization
< TRIMESH_TYPE >::HeapType 
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::HeapType
typedef tri::FaceTmark
< OldMeshType > 
vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MarkerFace
typedef SmoothMeshType vcg::tri::Smooth< SmoothMeshType >::MeshType
typedef
vcg::tri::MarchingCubes
< NewMeshType, MyWalker > 
vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::MyMarchingCubes
typedef Walker vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::MyWalker
typedef NewMeshType::BoxType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewBoxType
typedef NewMeshType::CoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewCoordType
typedef NewMeshType::ScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewScalarType
typedef NewMeshType::VertexIterator vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewVertexIterator
typedef NewMeshType::VertexType * vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewVertexPointer
typedef OldMeshType::CoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldCoordType
typedef OldMeshType::FaceContainer vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldFaceCont
typedef OldMeshType::FaceType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldFaceType
typedef OldMeshType::ScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldScalarType
typedef vcg::face::Pos< FaceType > vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PosType
typedef vcg::face::Pos< FaceType > vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::PosType
typedef vcg::face::Pos< FaceType > vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::PosType
typedef MeshType::ScalarType vcg::tri::PointCloudNormal< MeshType >::ScalarType
typedef MeshType::ScalarType vcg::tri::Nring< MeshType >::ScalarType
typedef MeshType::ScalarType vcg::tri::Smooth< SmoothMeshType >::ScalarType
typedef
TriMeshType::VertexType::ScalarType 
vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::ScalarType
 The scalar type.
typedef TRIMESH_TYPE::ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ScalarType
typedef
TriMeshType::VertexType::ScalarType 
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::ScalarType
typedef TRIMESH_TYPE::ScalarType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::ScalarType
typedef TRIMESH_TYPE::ScalarType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::ScalarType
typedef TRI_MESH_TYPE vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::TriMeshType
 The tetrahedral mesh type.
typedef TriMeshType::VertContainer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertContainer
 the container of vertex type
typedef int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::VertexIndex
typedef MeshType::VertexIterator vcg::tri::PointCloudNormal< MeshType >::VertexIterator
typedef MeshType::VertexIterator vcg::tri::Nring< MeshType >::VertexIterator
typedef MeshType::VertexIterator vcg::tri::Smooth< SmoothMeshType >::VertexIterator
typedef TriMeshType::VertexIterator vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexIterator
 The vertex iterator type.
typedef
TRIMESH_TYPE::VertexIterator 
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::VertexIterator
typedef MeshType::VertexPointer vcg::tri::PointCloudNormal< MeshType >::VertexPointer
typedef MeshType::VertexPointer vcg::tri::Smooth< SmoothMeshType >::VertexPointer
typedef FaceType::VertexPointer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexPointer
typedef TRIMESH_TYPE::VertexPointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::VertexPointer
typedef TRIMESH_TYPE::VertexPointer vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::VertexPointer
typedef MeshType::VertexType vcg::tri::PointCloudNormal< MeshType >::VertexType
typedef MeshType::VertexType vcg::tri::Nring< MeshType >::VertexType
typedef MeshType::VertexType vcg::tri::Smooth< SmoothMeshType >::VertexType
typedef FaceType::VertexType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexType
 The vertex type.
typedef
TriMeshType::FaceType::VertexType 
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::VertexType
typedef TRIMESH_TYPE::VertexType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::VertexType
typedef vcg::face::VFIterator
< FaceType > 
vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VFI
 half edge type
typedef std::vector
< vcg::face::VFIterator
< FaceType > > 
vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VFIVec
 vector of VFIterator
typedef vcg::face::VFIterator
< FaceType > 
vcg::tri::Smooth< SmoothMeshType >::VFLocalIterator

Functions

template<class ScalarType >
static ScalarType vcg::tri::_SQfnC (ScalarType a, ScalarType b)
template<class ScalarType >
static ScalarType vcg::tri::_SQfnS (ScalarType a, ScalarType b)
static void vcg::tri::Smooth< SmoothMeshType >::AccumulateLaplacianInfo (MeshType &m, SimpleTempData< typename MeshType::VertContainer, LaplacianInfo > &TD, bool cotangentFlag=false)
static void vcg::tri::PointCloudNormal< MeshType >::AddNeighboursToHeap (MeshType &m, VertexPointer vp, int nn, KdTree< ScalarType > &tree, std::vector< WArc > &heap)
void vcg::tri::Zonohedron< Scalar >::addVector (Scalar x, Scalar y, Scalar z)
void vcg::tri::Zonohedron< Scalar >::addVectors (const std::vector< Vec3 >)
template<class MeshType >
void vcg::tri::Annulus (MeshType &m, float externalRadius, float internalRadius, int slices)
VFIVec & vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV0 ()
VFIVec & vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV01 ()
VFIVec & vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV1 ()
 vcg::tri::BasicVertexPair< VERTEX_TYPE >::BasicVertexPair ()
 vcg::tri::BasicVertexPair< VERTEX_TYPE >::BasicVertexPair (VERTEX_TYPE *v0, VERTEX_TYPE *v1)
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Begin ()
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Border ()
template<class MeshType >
void vcg::tri::Box (MeshType &in, const typename MeshType::BoxType &bb)
template<class MeshType >
void vcg::tri::BuildCylinderEdgeShell (MeshType &mIn, MeshType &mOut, float radius=0, int slices=16, int stacks=1)
template<class MeshType >
void vcg::tri::BuildCylinderVertexShell (MeshType &mIn, MeshType &mOut, float radius=0, float height=0, int slices=16, int stacks=1)
template<class TriMeshType , class EdgeMeshType >
void vcg::tri::BuildFromNonFaux (TriMeshType &in, EdgeMeshType &out)
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::BuildMesh (OldMeshType &old_mesh, NewMeshType &new_mesh, EXTRACTOR_TYPE &extractor, vcg::CallBackPos *cb)
template<class MeshType , class V >
void vcg::tri::BuildMeshFromCoordVector (MeshType &in, const V &v)
template<class MeshType , class V , class F >
void vcg::tri::BuildMeshFromCoordVectorIndexVector (MeshType &in, const V &v, const F &f)
template<class MeshType >
void vcg::tri::BuildPrismFaceShell (MeshType &mIn, MeshType &mOut, float height=0, float inset=0, bool smoothFlag=true)
template<class MeshType >
void vcg::tri::BuildSphereVertexShell (MeshType &mIn, MeshType &mOut, float radius=0, int recDiv=2)
void vcg::tri::Nring< MeshType >::clear ()
static void vcg::tri::Nring< MeshType >::clearFlags (MeshType *m)
static void vcg::tri::PointCloudNormal< MeshType >::Compute (MeshType &m, Param p, vcg::CallBackPos *cb=0)
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ComputeConsensus (int, field_value *slice_values)
ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::ComputePriority (BaseParameterClass *)
 Compute the priority to be used in the heap.
ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ComputePriority (BaseParameterClass *)
ScalarType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::ComputePriority (BaseParameterClass *)
ScalarType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::ComputePriority (BaseParameterClass *)
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ComputeSliceValues (int slice, field_value *slice_values)
static void vcg::tri::PointCloudNormal< MeshType >::ComputeUndirectedNormal (MeshType &m, int nn, ScalarType maxDist, KdTree< ScalarType > &tree, vcg::CallBackPos *cb=0)
template<class MeshType >
void vcg::tri::Cone (MeshType &in, const typename MeshType::ScalarType r1, const typename MeshType::ScalarType r2, const typename MeshType::ScalarType h, const int SubDiv=36)
 r1 = raggio 1, r2 = raggio2, h = altezza (asse y)
template<class MeshType >
void vcg::tri::Zonohedron< Scalar >::createMesh (MeshType &output)
template<class ScalarType >
static CoordType vcg::tri::Smooth< SmoothMeshType >::CrossProdGradient (CoordType &p, CoordType &p0, CoordType &p1, CoordType &m)
VERTEX_TYPE * vcg::tri::BasicVertexPair< VERTEX_TYPE >::cV (int i) const
template<class MeshType >
void vcg::tri::Cylinder (int slices, int stacks, MeshType &m, bool capped=false)
template<class MeshType >
void vcg::tri::Disk (MeshType &m, int slices)
field_value vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::DistanceFromMesh (OldCoordType &pp)
 return true if the distance form the mesh is less than maxdim and return distance
static int vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::Do (TriMeshType &m, VertexPair &c, const Point3< ScalarType > &p)
template<class DodMeshType >
void vcg::tri::Dodecahedron (DodMeshType &in)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasEEAdjacency (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeColor (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeFlags (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeMark (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeNormal (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeQuality (const std::vector< EdgeType > &)
template<class EdgeType >
bool vcg::tri::EdgeVectorHasVEAdjacency (const std::vector< EdgeType > &)
void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Execute (TriMeshType &m, BaseParameterClass *)
void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Execute (TRIMESH_TYPE &m, BaseParameterClass *)
void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::Execute (TRIMESH_TYPE &m, BaseParameterClass *)
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Exist (const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
void vcg::tri::Nring< MeshType >::expand ()
void vcg::tri::Nring< MeshType >::expand (int k)
static void vcg::tri::Smooth< SmoothMeshType >::FaceColorLaplacian (MeshType &m, int step, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static CoordType vcg::tri::Smooth< SmoothMeshType >::FaceErrorGrad (CoordType &p, CoordType &p0, CoordType &p1, CoordType &m)
template<class MeshType >
void vcg::tri::FaceGrid (MeshType &in, int w, int h)
template<class MeshType >
void vcg::tri::FaceGrid (MeshType &in, const std::vector< int > &grid, int w, int h)
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalAngleThreshold (MeshType &m, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TD, ScalarType sigma)
void vcg::tri::Smooth< SmoothMeshType >::FaceNormalFuzzyVectorSB (MeshType &m, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TD, ScalarType sigma)
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalLaplacianFF (MeshType &m, int step=1, bool SmoothSelected=false)
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalLaplacianVF (MeshType &m)
template<class FaceType >
bool vcg::tri::FaceVectorHasFEAdjacency (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasFFAdjacency (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasFVAdjacency (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceColor (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceCurvatureDir (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceFlags (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceMark (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceNormal (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceQuality (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeColor (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeNormal (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeTexCoord (const std::vector< FaceType > &)
template<class FaceType >
bool vcg::tri::FaceVectorHasVFAdjacency (const std::vector< FaceType > &)
static void vcg::tri::Smooth< SmoothMeshType >::FastFitMesh (MeshType &m, SimpleTempData< typename MeshType::VertContainer, PDVertInfo > &TDV, bool OnlySelected=false)
static void vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FindSets (VertexPair &p, EdgeSet &es)
static void vcg::tri::Smooth< SmoothMeshType >::FitMesh (MeshType &m, SimpleTempData< typename MeshType::VertContainer, PDVertInfo > &TDV, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TDF, float lambda)
template<class MeshType >
void vcg::tri::GenerateCameraMesh (MeshType &in)
int vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GetMark () const
PosType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GetPos () const
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetSliceIndex (int x, int z)
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetXIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
 if there is a vertex in z axis of a cell return the vertex or create it
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetYIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
 if there is a vertex in y axis of a cell return the vertex or create it
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetZIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, NewVertexPointer &v)
 if there is a vertex in z axis of a cell return the vertex or create it
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::GlobalMark ()
 mark for up_dating
static int & vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GlobalMark ()
template<class MeshType >
void vcg::tri::Grid (MeshType &in, int w, int h, float wl, float hl, float *data=0)
template<class TriMeshType >
bool vcg::tri::HasEEAdjacency (const TriMeshType &m)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEFAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEHAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEVAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class TriMeshType >
bool vcg::tri::HasFEAdjacency (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasFFAdjacency (const TriMeshType &m)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasFHAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class TriMeshType >
bool vcg::tri::HasFVAdjacency (const TriMeshType &m)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHEAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHFAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHNextAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHOppAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHPrevAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHVAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeColor (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeFlags (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeMark (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeNormal (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeQuality (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerEdgeVEAdjacency (const TriMeshType &m)
template<class MeshType >
bool vcg::tri::HasPerFaceAttribute (const MeshType &m, std::string name)
template<class TriMeshType >
bool vcg::tri::HasPerFaceColor (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceCurvatureDir (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceFlags (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceMark (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceNormal (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceQuality (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerFaceVFAdjacency (const TriMeshType &m)
template<class MeshType >
bool vcg::tri::HasPerMeshAttribute (const MeshType &m, std::string name)
template<class MeshType >
bool vcg::tri::HasPerVertexAttribute (const MeshType &m, std::string name)
template<class TriMeshType >
bool vcg::tri::HasPerVertexColor (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexCurvature (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexCurvatureDir (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexFlags (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexMark (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexNormal (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexQuality (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexRadius (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexTexCoord (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexVEAdjacency (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerVertexVFAdjacency (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerWedgeColor (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerWedgeNormal (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasPerWedgeTexCoord (const TriMeshType &m)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasPolyInfo (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class TriMeshType >
bool vcg::tri::HasVEAdjacency (const TriMeshType &m)
template<class TriMeshType >
bool vcg::tri::HasVFAdjacency (const TriMeshType &m)
template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasVHAdjacency (const TriMesh< CType0, CType1, CType2, CType3 > &)
template<class MeshType >
void vcg::tri::Hexahedron (MeshType &in)
template<class IcoMeshType >
void vcg::tri::Icosahedron (IcoMeshType &in)
template<class MeshType >
int & vcg::tri::IMark (MeshType &m)
 Access function to the incremental mark. You should not use this member directly. In most of the case just use IsMarked() and Mark()
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::VertexType &v)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::FaceType &f)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::EdgeType &e)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::HEdgeType &h)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::VertexType *vp)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::FaceType *fp)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::EdgeType *e)
template<class MeshType >
size_t vcg::tri::Index (MeshType &m, const typename MeshType::HEdgeType *h)
virtual const char * vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Info (TriMeshType &m)
const char * vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Info (TRIMESH_TYPE &m)
static void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Init ()
static void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Init (TriMeshType &m, HeapType &h_ret, BaseParameterClass *pp)
static void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Init (TRIMESH_TYPE &mesh, HeapType &heap, BaseParameterClass *pp)
static void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::Init (TRIMESH_TYPE &m, HeapType &heap, BaseParameterClass *pp)
template<class MeshType >
void vcg::tri::InitFaceIMark (MeshType &m)
 Initialize the imark-system of the faces.
template<class MeshType >
void vcg::tri::InitVertexIMark (MeshType &m)
 Initialize the imark-system of the vertices.
static void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Insert (HeapType &heap, PosType &p, int mark, BaseParameterClass *pp)
void vcg::tri::Nring< MeshType >::insertAndFlag (FaceType *f)
void vcg::tri::Nring< MeshType >::insertAndFlag (VertexType *v)
void vcg::tri::Nring< MeshType >::insertAndFlag1Ring (VertexType *v)
NewCoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Interpolate (const vcg::Point3i &p1, const vcg::Point3i &p2, int dir)
 interpolate
bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsFeasible (BaseParameterClass *)
 return true if no constraint disallow this operation to be performed (ex: change of topology in edge collapses)
virtual bool vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsFeasible (BaseParameterClass *_pp)
template<class MeshType >
bool vcg::tri::IsMarked (MeshType &m, typename MeshType::ConstVertexPointer v)
 Check if the vertex incremental mark matches the one of the mesh.
template<class MeshType >
bool vcg::tri::IsMarked (MeshType &m, typename MeshType::ConstFacePointer f)
 Check if the face incremental mark matches the one of the mesh.
ModifierType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsOfType ()
ModifierType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsOfType ()
 return the type of operation
static bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsSymmetric (BaseParameterClass *)
bool vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsUpToDate () const
bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsUpToDate () const
 return true if the data have not changed since it was created
template<class MeshType >
bool vcg::tri::IsValidPointer (MeshType &m, const typename MeshType::VertexType *vp)
template<class MeshType >
bool vcg::tri::IsValidPointer (MeshType &m, const typename MeshType::EdgeType *ep)
template<class MeshType >
bool vcg::tri::IsValidPointer (MeshType &m, const typename MeshType::FaceType *fp)
template<class MeshType >
bool vcg::tri::IsValidPointer (MeshType &m, const typename MeshType::HEdgeType *hp)
 vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::LaplacianInfo (const CoordType &_p, const int _n)
 vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::LaplacianInfo ()
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionEdge ()
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionFace ()
static bool vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::LinkConditions (VertexPair &pos)
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionVert ()
template<class MeshType >
void vcg::tri::Mark (MeshType &m, typename MeshType::VertexPointer v)
 Set the vertex incremental mark of the vertex to the one of the mesh.
template<class MeshType >
void vcg::tri::Mark (MeshType &m, typename MeshType::FacePointer f)
 Set the face incremental mark of the vertex to the one of the mesh.
field_value vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MultiDistanceFromMesh (OldCoordType &pp)
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::NextSlice ()
 vcg::tri::Nring< MeshType >::Nring (VertexType *v, MeshType *m)
template<class OctMeshType >
void vcg::tri::Octahedron (OctMeshType &in)
bool vcg::tri::PointCloudNormal< MeshType >::WArc::operator< (const WArc &a) const
template<class MeshType >
void vcg::tri::OrientedAnnulus (MeshType &m, Point3f center, Point3f norm, float externalRadius, float internalRadius, int slices)
template<class MeshType >
void vcg::tri::OrientedCylinder (MeshType &m, const typename MeshType::CoordType origin, const typename MeshType::CoordType end, float radius, bool capped, int slices=32, int stacks=4)
template<class MeshType >
void vcg::tri::OrientedDisk (MeshType &m, int slices, typename MeshType::CoordType center, typename MeshType::CoordType norm, float radius)
template<class MeshType >
void vcg::tri::OrientedEllipticPrism (MeshType &m, const typename MeshType::CoordType origin, const typename MeshType::CoordType end, float radius, float xScale, float yScale, bool capped, int slices=32, int stacks=4)
template<class MeshType >
void vcg::tri::OrientedRect (MeshType &square, float width, float height, Point3f c, Point3f dir=Point3f(0, 0, 0), float angleDeg=0, Point3f preRotTra=Point3f(0, 0, 0))
template<class MeshType >
void vcg::tri::OrientedSquare (MeshType &square, float width, Point3f c, Point3f dir=Point3f(0, 0, 0), float angleDeg=0, Point3f preRotTra=Point3f(0, 0, 0))
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::OutOfDate ()
 vcg::tri::PointCloudNormal< MeshType >::Param::Param ()
 vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::PDFaceInfo ()
 vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::PDFaceInfo (const CoordType &_m)
 vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip ()
 vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip (PosType pos, int mark, BaseParameterClass *pp)
 vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip (const PlanarEdgeFlip &par)
 vcg::tri::PlanarEdgeFlipParameter::PlanarEdgeFlipParameter ()
static void vcg::tri::Smooth< SmoothMeshType >::PointCloudQualityAverage (MeshType &m, int neighbourSize=8, int iter=1)
static void vcg::tri::Smooth< SmoothMeshType >::PointCloudQualityMedian (MeshType &m, int medianSize=8)
virtual ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Priority () const
 Return the priority to be used in the heap (implement static priority)
virtual ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Priority () const
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ProcessSlice (EXTRACTOR_TYPE &extractor)
template<class MeshType , class ATTR_CONT >
void vcg::tri::ReorderAttribute (ATTR_CONT &c, std::vector< size_t > &newVertIndex, MeshType &)
template<class MeshType >
void vcg::tri::RequireCompactness (MeshType &m)
template<class MeshType >
void vcg::tri::RequireEEAdjacency (MeshType &m)
template<class MeshType >
void vcg::tri::RequireFEAdjacency (MeshType &m)
template<class MeshType >
void vcg::tri::RequireFFAdjacency (MeshType &m)
template<class MeshType >
void vcg::tri::RequireFHAdjacency (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerEdgeAttribute (MeshType &m, const char *name)
template<class MeshType >
void vcg::tri::RequirePerEdgeColor (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerEdgeFlags (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerEdgeMark (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerEdgeNormal (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerEdgeQuality (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceAttribute (MeshType &m, const char *name)
template<class MeshType >
void vcg::tri::RequirePerFaceColor (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceCurvatureDir (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceFlags (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceMark (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceNormal (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceQuality (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceWedgeColor (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceWedgeNormal (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerFaceWedgeTexCoord (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerMeshAttribute (MeshType &m, const char *name)
template<class MeshType >
void vcg::tri::RequirePerVertexAttribute (MeshType &m, const char *name)
template<class MeshType >
void vcg::tri::RequirePerVertexColor (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexCurvature (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexCurvatureDir (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexFlags (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexMark (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexNormal (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexQuality (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexRadius (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePerVertexTexCoord (MeshType &m)
template<class MeshType >
void vcg::tri::RequirePolygonalMesh (MeshType &m)
template<class MeshType >
void vcg::tri::RequireTriangularMesh (MeshType &m)
template<class MeshType >
void vcg::tri::RequireVEAdjacency (MeshType &m)
template<class MeshType >
void vcg::tri::RequireVFAdjacency (MeshType &m)
static void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Resample (OldMeshType &old_mesh, NewMeshType &new_mesh, NewBoxType volumeBox, vcg::Point3< int > accuracy, float max_dist, float thr=0, bool DiscretizeFlag=false, bool MultiSampleFlag=false, bool AbsDistFlag=false, vcg::CallBackPos *cb=0)
 resample the mesh using marching cube algorithm ,the accuracy is the dimension of one cell the parameter
template<class MeshType , class ATTR_CONT >
void vcg::tri::ResizeAttribute (ATTR_CONT &c, size_t sz, MeshType &)
void vcg::tri::PlanarEdgeFlipParameter::SetDefaultParams ()
void vcg::tri::BasicVertexPair< VERTEX_TYPE >::Sort ()
template<class MeshType >
void vcg::tri::Sphere (MeshType &in, const int subdiv=3)
template<class MeshType >
void vcg::tri::SphericalCap (MeshType &in, float angleRad, const int subdiv=3)
template<class MeshType >
void vcg::tri::Square (MeshType &in)
template<class MeshType >
void vcg::tri::SuperEllipsoid (MeshType &m, float rFeature, float sFeature, float tFeature, int hRingDiv=24, int vRingDiv=12)
template<class MeshType >
void vcg::tri::SuperToroid (MeshType &m, float hRingRadius, float vRingRadius, float vSquareness, float hSquareness, int hRingDiv=24, int vRingDiv=12)
template<class TetraMeshType >
void vcg::tri::Tetrahedron (TetraMeshType &in)
 vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip ()
 vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip (const PosType pos, int mark, BaseParameterClass *pp)
 vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip (const TopoEdgeFlip &par)
template<class MeshType >
void vcg::tri::Torus (MeshType &m, float hRingRadius, float vRingRadius, int hRingDiv=24, int vRingDiv=12)
static CoordType vcg::tri::Smooth< SmoothMeshType >::TriAreaGradient (CoordType &p, CoordType &p0, CoordType &p1)
 vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::TriEdgeCollapse ()
 Default Constructor.
 vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::TriEdgeCollapse (const VertexPair &p, int mark, BaseParameterClass *pp)
 Constructor with postype.
 vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip ()
 vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip (const PosType pos, int mark, BaseParameterClass *pp)
 vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip (const TriEdgeFlip &par)
template<class MeshType >
void vcg::tri::UnMarkAll (MeshType &m)
 Unmark, in constant time, all the elements (face and vertices) of a mesh.
void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::UpdateHeap (HeapType &h_ret, BaseParameterClass *pp)
 Update the heap as a consequence of this operation.
virtual void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::UpdateHeap (HeapType &heap, BaseParameterClass *pp)
 Update the heap as a consequence of this operation.
void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::UpdateHeap (HeapType &heap, BaseParameterClass *pp)
 Update the heap as a consequence of this operation.
VERTEX_TYPE *& vcg::tri::BasicVertexPair< VERTEX_TYPE >::V (int i)
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::V (const Point3i &p)
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::V (int x, int y, int z)
static void vcg::tri::Smooth< SmoothMeshType >::VertexColorLaplacian (MeshType &m, int step, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacian (MeshType &m, int step, bool SmoothSelected=false, bool cotangentWeight=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianAngleWeighted (MeshType &m, int step, ScalarType delta)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianBlend (MeshType &m, int step, float alpha, bool SmoothSelected=false)
void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianCurvatureFlow (MeshType &, int, ScalarType)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianHC (MeshType &m, int step, bool SmoothSelected=false)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianQuality (MeshType &m, int step, bool SmoothSelected=false)
template<class GRID , class MeshTypeTri >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianReproject (MeshType &m, GRID &grid, MeshTypeTri &gridmesh)
 Laplacian smoothing with a reprojection on a target surface.
template<class GRID , class MeshTypeTri >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianReproject (MeshType &m, GRID &grid, MeshTypeTri &gridmesh, typename MeshType::VertexType *vp)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordPasoDoble (MeshType &m, int NormalSmoothStep, typename MeshType::ScalarType Sigma=0, int FitStep=50, bool SmoothSelected=false)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordPlanarLaplacian (MeshType &m, int step, float AngleThrRad=math::ToRad(1.0), bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordScaleDependentLaplacian_Fujiwara (MeshType &m, int step, ScalarType delta)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordTaubin (MeshType &m, int step, float lambda, float mu, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordViewDepth (MeshType &m, const CoordType &viewpoint, const ScalarType alpha, int step, bool SmoothBorder=false)
static void vcg::tri::Smooth< SmoothMeshType >::VertexNormalLaplacian (MeshType &m, int step, bool SmoothSelected=false)
static void vcg::tri::Smooth< SmoothMeshType >::VertexNormalPointCloud (MeshType &m, int neighborNum, int iterNum, KdTree< ScalarType > *tp=0)
static void vcg::tri::Smooth< SmoothMeshType >::VertexQualityLaplacian (MeshType &m, int step=1, bool SmoothSelected=false)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexColor (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexCurvature (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexCurvatureDir (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexFlags (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexMark (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexNormal (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexQuality (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexRadius (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexTexCoord (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasVEAdjacency (const std::vector< VertexType > &)
template<class VertexType >
bool vcg::tri::VertexVectorHasVFAdjacency (const std::vector< VertexType > &)
static int & vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Volume ()
std::pair< bool, NewScalarType > vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::VV (int x, int y, int z)
 vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Walker (const Box3< NewScalarType > &_bbox, Point3i _siz)
 vcg::tri::PointCloudNormal< MeshType >::WArc::WArc (VertexPointer _s, VertexPointer _t)
 vcg::tri::Nring< MeshType >::~Nring ()
 vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::~PlanarEdgeFlip ()
 vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::~TriEdgeCollapse ()
 vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::~Walker ()

Variables

GridType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_g
int vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_localMark
NewMeshType * vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_newM
OldMeshType * vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_oldM
PosType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_pos
ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_priority
ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::_priority
 priority in the heap
field_value * vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_v_cs
field_value * vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_v_ns
VertexIndexvcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_x_cs
VertexIndexvcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_x_ns
VertexIndexvcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_y_cs
VertexIndexvcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_z_cs
VertexIndexvcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_z_ns
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::a
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::AbsDistFlag
std::vector< FaceType * > vcg::tri::Nring< MeshType >::allF
std::vector< VertexType * > vcg::tri::Nring< MeshType >::allV
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av0
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av01
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av1
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::b
ScalarType vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::cnt
int vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::cnt
int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::cnt
int vcg::tri::Smooth< SmoothMeshType >::QualitySmoothInfo::cnt
int vcg::tri::PointCloudNormal< MeshType >::Param::coherentAdjNum
 number of itaration of a simple normal smoothing (use the same number of ajdacent of fittingAdjNjm)
float vcg::tri::PlanarEdgeFlipParameter::CoplanarAngleThresholdDeg
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::CurrentSlice
CoordType vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::dif
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::DiscretizeFlag
int vcg::tri::PointCloudNormal< MeshType >::Param::fittingAdjNum
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::g
std::vector< FaceType * > vcg::tri::Nring< MeshType >::lastF
std::vector< VertexType * > vcg::tri::Nring< MeshType >::lastV
ScalarType vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo::LenSum
int vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::localMark
 mark for up_dating
MeshType * vcg::tri::Nring< MeshType >::m
CoordType vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::m
MarkerFace vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::markerFunctor
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::max_dim
TriMeshType * vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::mt
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MultiSampleFlag
CoordType vcg::tri::Smooth< SmoothMeshType >::PDVertInfo::np
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::offset
CoordType vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo::PntSum
VertexPair vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::pos
 the pair to collapse
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::r
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::SliceSize
int vcg::tri::PointCloudNormal< MeshType >::Param::smoothingIterNum
 number of adjacent nodes used for computing the fitting plane
VertexPointer vcg::tri::PointCloudNormal< MeshType >::WArc::src
CoordType vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::sum
CoordType vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::sum
ScalarType vcg::tri::Smooth< SmoothMeshType >::QualitySmoothInfo::sum
VertexPointer vcg::tri::PointCloudNormal< MeshType >::WArc::trg
bool vcg::tri::PointCloudNormal< MeshType >::Param::useViewPoint
 position of a viewpoint used to disambiguate direction
VERTEX_TYPE * vcg::tri::BasicVertexPair< VERTEX_TYPE >::v [2]
CoordType vcg::tri::PointCloudNormal< MeshType >::Param::viewPoint
 number of nodes used in the coherency pass
float vcg::tri::PointCloudNormal< MeshType >::WArc::w

Typedef Documentation

template<class SmoothMeshType >
typedef vcg::Box3<ScalarType> vcg::tri::Smooth< SmoothMeshType >::Box3Type

Definition at line 59 of file smooth.h.

template<typename MeshType >
typedef MeshType::VertexType::CoordType vcg::tri::PointCloudNormal< MeshType >::CoordType

Definition at line 22 of file pointcloud_normal.h.

template<class MeshType>
typedef MeshType::CoordType vcg::tri::Nring< MeshType >::CoordType

Definition at line 51 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::VertexType::CoordType vcg::tri::Smooth< SmoothMeshType >::CoordType

Definition at line 51 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef FaceType::VertexType::CoordType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::CoordType

The coordinate type.

Definition at line 69 of file edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
typedef FaceType::VertexType::CoordType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::CoordType [protected]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::CoordType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::CoordType [protected]
template<class TRIMESH_TYPE, class MYTYPE>
typedef TRIMESH_TYPE::CoordType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::CoordType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 350 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::CoordType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::CoordType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 419 of file tri_edge_flip.h.

template<class SmoothMeshType >
typedef MeshType::FaceContainer vcg::tri::Smooth< SmoothMeshType >::FaceContainer

Definition at line 58 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::FaceContainer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceContainer

the container of tetrahedron type

Definition at line 73 of file edge_collapse.h.

template<class MeshType>
typedef MeshType::FaceIterator vcg::tri::Nring< MeshType >::FaceIterator

Definition at line 49 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::FaceIterator vcg::tri::Smooth< SmoothMeshType >::FaceIterator

Definition at line 57 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::FaceIterator vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceIterator

The tetra iterator type.

Definition at line 67 of file edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::FaceIterator vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FaceIterator [protected]

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 70 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::FaceIterator vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceIterator [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 425 of file tri_edge_flip.h.

template<class SmoothMeshType >
typedef MeshType::FacePointer vcg::tri::Smooth< SmoothMeshType >::FacePointer

Definition at line 56 of file smooth.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::FacePointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FacePointer [protected]

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 69 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::FacePointer vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FacePointer [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 417 of file tri_edge_flip.h.

template<class MeshType>
typedef MeshType::FaceType vcg::tri::Nring< MeshType >::FaceType

Definition at line 46 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::FaceType vcg::tri::Smooth< SmoothMeshType >::FaceType

Definition at line 55 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::FaceType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FaceType

The face type.

Definition at line 60 of file edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::FaceType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FaceType [protected]
template<class TriMeshType, class VertexPair, class MYTYPE>
typedef TriMeshType::FaceType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FaceType [protected]
template<class TRIMESH_TYPE, class MYTYPE>
typedef TRIMESH_TYPE::FaceType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 348 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::FaceType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::FaceType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 416 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef std::pair<bool,float> vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::field_value [protected]

Definition at line 86 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef vcg::GridStaticPtr<OldFaceType, OldScalarType> vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GridType [private]

Reimplemented from vcg::BasicGrid< NewMeshType::ScalarType >.

Definition at line 68 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
typedef LocalOptimization<TriMeshType>::HeapElem vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::HeapElem [protected]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef LocalOptimization<TRIMESH_TYPE>::HeapElem vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapElem [protected]

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 76 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef LocalOptimization<TRIMESH_TYPE>::HeapElem vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::HeapElem [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 422 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
typedef LocalOptimization<TriMeshType>::HeapType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::HeapType [protected]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef LocalOptimization<TRIMESH_TYPE>::HeapType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapType [protected]

Reimplemented from vcg::LocalModification< MeshType >.

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 77 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef LocalOptimization<TRIMESH_TYPE>::HeapType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::HeapType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 423 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef tri::FaceTmark<OldMeshType> vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MarkerFace [protected]

Definition at line 74 of file resampler.h.

template<class SmoothMeshType >
typedef SmoothMeshType vcg::tri::Smooth< SmoothMeshType >::MeshType

Definition at line 49 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef vcg::tri::MarchingCubes<NewMeshType, MyWalker> vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::MyMarchingCubes

Definition at line 598 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef Walker vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::MyWalker

Definition at line 596 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef NewMeshType::BoxType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewBoxType [private]

Definition at line 55 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef NewMeshType::CoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewCoordType [private]

Definition at line 56 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef NewMeshType::ScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewScalarType [private]

Definition at line 54 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef NewMeshType::VertexIterator vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewVertexIterator [private]

Definition at line 58 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef NewMeshType::VertexType* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::NewVertexPointer [private]

Definition at line 57 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef OldMeshType::CoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldCoordType [private]

Definition at line 59 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef OldMeshType::FaceContainer vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldFaceCont [private]

Definition at line 60 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef OldMeshType::FaceType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldFaceType [private]

Definition at line 61 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef OldMeshType::ScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::OldScalarType [private]

Definition at line 62 of file resampler.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef vcg::face::Pos<FaceType> vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PosType [protected]
template<class TRIMESH_TYPE, class MYTYPE>
typedef vcg::face::Pos<FaceType> vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::PosType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 351 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef vcg::face::Pos<FaceType> vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::PosType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 420 of file tri_edge_flip.h.

template<typename MeshType >
typedef MeshType::ScalarType vcg::tri::PointCloudNormal< MeshType >::ScalarType

Definition at line 25 of file pointcloud_normal.h.

template<class MeshType>
typedef MeshType::ScalarType vcg::tri::Nring< MeshType >::ScalarType

Definition at line 48 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::ScalarType vcg::tri::Smooth< SmoothMeshType >::ScalarType

Definition at line 54 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::VertexType::ScalarType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::ScalarType

The scalar type.

Definition at line 71 of file edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ScalarType [protected]
template<class TriMeshType, class VertexPair, class MYTYPE>
typedef TriMeshType::VertexType::ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::ScalarType [protected]
template<class TRIMESH_TYPE, class MYTYPE>
typedef TRIMESH_TYPE::ScalarType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::ScalarType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 349 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::ScalarType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::ScalarType [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 418 of file tri_edge_flip.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TRI_MESH_TYPE vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::TriMeshType

The tetrahedral mesh type.

Definition at line 58 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::VertContainer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertContainer

the container of vertex type

Definition at line 75 of file edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
typedef int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::VertexIndex [private]

Definition at line 67 of file resampler.h.

template<typename MeshType >
typedef MeshType::VertexIterator vcg::tri::PointCloudNormal< MeshType >::VertexIterator

Definition at line 24 of file pointcloud_normal.h.

template<class MeshType>
typedef MeshType::VertexIterator vcg::tri::Nring< MeshType >::VertexIterator

Definition at line 50 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::VertexIterator vcg::tri::Smooth< SmoothMeshType >::VertexIterator

Definition at line 53 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef TriMeshType::VertexIterator vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexIterator

The vertex iterator type.

Definition at line 65 of file edge_collapse.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::VertexIterator vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::VertexIterator [protected]

Definition at line 426 of file tri_edge_flip.h.

template<typename MeshType >
typedef MeshType::VertexPointer vcg::tri::PointCloudNormal< MeshType >::VertexPointer

Definition at line 23 of file pointcloud_normal.h.

template<class SmoothMeshType >
typedef MeshType::VertexPointer vcg::tri::Smooth< SmoothMeshType >::VertexPointer

Definition at line 52 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef FaceType::VertexPointer vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexPointer

Definition at line 63 of file edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::VertexPointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::VertexPointer [protected]

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 73 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::VertexPointer vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::VertexPointer [protected]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 414 of file tri_edge_flip.h.

template<typename MeshType >
typedef MeshType::VertexType vcg::tri::PointCloudNormal< MeshType >::VertexType

Definition at line 21 of file pointcloud_normal.h.

template<class MeshType>
typedef MeshType::VertexType vcg::tri::Nring< MeshType >::VertexType

Definition at line 47 of file nring.h.

template<class SmoothMeshType >
typedef MeshType::VertexType vcg::tri::Smooth< SmoothMeshType >::VertexType

Definition at line 50 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef FaceType::VertexType vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VertexType

The vertex type.

Definition at line 62 of file edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
typedef TriMeshType::FaceType::VertexType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::VertexType [protected]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
typedef TRIMESH_TYPE::VertexType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::VertexType [protected]

Definition at line 71 of file tri_edge_flip.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef vcg::face::VFIterator<FaceType> vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VFI

half edge type

vector of pos of VFIterator

Definition at line 81 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
typedef std::vector<vcg::face::VFIterator<FaceType> > vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::VFIVec

vector of VFIterator

Definition at line 83 of file edge_collapse.h.

template<class SmoothMeshType >
typedef vcg::face::VFIterator<FaceType> vcg::tri::Smooth< SmoothMeshType >::VFLocalIterator

Definition at line 60 of file smooth.h.


Function Documentation

template<class ScalarType >
static ScalarType vcg::tri::_SQfnC ( ScalarType  a,
ScalarType  b 
) [static]

Auxilary functions for superquadric surfaces Used by SuperToroid and SuperEllipsoid

Definition at line 606 of file platonic.h.

template<class ScalarType >
static ScalarType vcg::tri::_SQfnS ( ScalarType  a,
ScalarType  b 
) [static]

Definition at line 610 of file platonic.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::AccumulateLaplacianInfo ( MeshType m,
SimpleTempData< typename MeshType::VertContainer, LaplacianInfo > &  TD,
bool  cotangentFlag = false 
) [inline, static]

Definition at line 209 of file smooth.h.

template<typename MeshType >
static void vcg::tri::PointCloudNormal< MeshType >::AddNeighboursToHeap ( MeshType &  m,
VertexPointer  vp,
int  nn,
KdTree< ScalarType > &  tree,
std::vector< WArc > &  heap 
) [inline, static]

Definition at line 66 of file pointcloud_normal.h.

template<class Scalar >
void vcg::tri::Zonohedron< Scalar >::addVector ( Scalar  x,
Scalar  y,
Scalar  z 
)

Definition at line 249 of file zonohedron.h.

template<class Scalar>
void vcg::tri::Zonohedron< Scalar >::addVectors ( const std::vector< Vec3 )

Definition at line 242 of file zonohedron.h.

template<class MeshType >
void vcg::tri::Annulus ( MeshType &  m,
float  externalRadius,
float  internalRadius,
int  slices 
)

Definition at line 907 of file platonic.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec& vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV0 ( ) [inline]

Definition at line 88 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec& vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV01 ( ) [inline]

Definition at line 90 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec& vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::AV1 ( ) [inline]

Definition at line 89 of file edge_collapse.h.

template<class VERTEX_TYPE>
vcg::tri::BasicVertexPair< VERTEX_TYPE >::BasicVertexPair ( ) [inline]

Definition at line 36 of file edge_collapse.h.

template<class VERTEX_TYPE>
vcg::tri::BasicVertexPair< VERTEX_TYPE >::BasicVertexPair ( VERTEX_TYPE *  v0,
VERTEX_TYPE *  v1 
) [inline]

Definition at line 37 of file edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Begin ( ) [inline]

Definition at line 380 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Border ( ) [inline, static]

Definition at line 57 of file tri_edge_collapse.h.

template<class MeshType >
void vcg::tri::Box ( MeshType &  in,
const typename MeshType::BoxType &  bb 
)

Definition at line 529 of file platonic.h.

template<class MeshType >
void vcg::tri::BuildCylinderEdgeShell ( MeshType &  mIn,
MeshType &  mOut,
float  radius = 0,
int  slices = 16,
int  stacks = 1 
)

Definition at line 1166 of file platonic.h.

template<class MeshType >
void vcg::tri::BuildCylinderVertexShell ( MeshType &  mIn,
MeshType &  mOut,
float  radius = 0,
float  height = 0,
int  slices = 16,
int  stacks = 1 
)

Definition at line 1195 of file platonic.h.

template<class TriMeshType , class EdgeMeshType >
void vcg::tri::BuildFromNonFaux ( TriMeshType &  in,
EdgeMeshType &  out 
)

Definition at line 744 of file platonic.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::BuildMesh ( OldMeshType &  old_mesh,
NewMeshType &  new_mesh,
EXTRACTOR_TYPE &  extractor,
vcg::CallBackPos cb 
) [inline]

Definition at line 322 of file resampler.h.

template<class MeshType , class V >
void vcg::tri::BuildMeshFromCoordVector ( MeshType &  in,
const V v 
)

Definition at line 736 of file platonic.h.

template<class MeshType , class V , class F >
void vcg::tri::BuildMeshFromCoordVectorIndexVector ( MeshType &  in,
const V v,
const F &  f 
)

Definition at line 695 of file platonic.h.

template<class MeshType >
void vcg::tri::BuildPrismFaceShell ( MeshType &  mIn,
MeshType &  mOut,
float  height = 0,
float  inset = 0,
bool  smoothFlag = true 
)

Definition at line 1092 of file platonic.h.

template<class MeshType >
void vcg::tri::BuildSphereVertexShell ( MeshType &  mIn,
MeshType &  mOut,
float  radius = 0,
int  recDiv = 2 
)

Definition at line 1181 of file platonic.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::clear ( ) [inline]

Definition at line 123 of file nring.h.

template<class MeshType>
static void vcg::tri::Nring< MeshType >::clearFlags ( MeshType *  m) [inline, static]

Definition at line 117 of file nring.h.

template<typename MeshType >
static void vcg::tri::PointCloudNormal< MeshType >::Compute ( MeshType &  m,
Param  p,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 110 of file pointcloud_normal.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ComputeConsensus ( int  ,
field_value slice_values 
) [inline]

Definition at line 252 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::ComputePriority ( BaseParameterClass pp) [inline, virtual]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ComputePriority ( BaseParameterClass ) [inline, virtual]
template<class TRIMESH_TYPE, class MYTYPE>
ScalarType vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::ComputePriority ( BaseParameterClass ) [inline, virtual]

Compute the priority of this optimization

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 380 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
ScalarType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::ComputePriority ( BaseParameterClass ) [inline, virtual]

Compute the priority of this optimization

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 455 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ComputeSliceValues ( int  slice,
field_value slice_values 
) [inline]

compute the values if an entire slice (per y) distances>dig of a cell are signed with double of the distance of the bb

Definition at line 233 of file resampler.h.

template<typename MeshType >
static void vcg::tri::PointCloudNormal< MeshType >::ComputeUndirectedNormal ( MeshType &  m,
int  nn,
ScalarType  maxDist,
KdTree< ScalarType > &  tree,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 38 of file pointcloud_normal.h.

template<class MeshType >
void vcg::tri::Cone ( MeshType &  in,
const typename MeshType::ScalarType  r1,
const typename MeshType::ScalarType  r2,
const typename MeshType::ScalarType  h,
const int  SubDiv = 36 
)

r1 = raggio 1, r2 = raggio2, h = altezza (asse y)

Definition at line 437 of file platonic.h.

template<class Scalar >
template<class MeshType >
void vcg::tri::Zonohedron< Scalar >::createMesh ( MeshType &  output)

Definition at line 262 of file zonohedron.h.

template<class SmoothMeshType >
template<class ScalarType >
static CoordType vcg::tri::Smooth< SmoothMeshType >::CrossProdGradient ( CoordType p,
CoordType p0,
CoordType p1,
CoordType m 
) [inline, static]

Definition at line 1112 of file smooth.h.

template<class VERTEX_TYPE>
VERTEX_TYPE* vcg::tri::BasicVertexPair< VERTEX_TYPE >::cV ( int  i) const [inline]

Definition at line 40 of file edge_collapse.h.

template<class MeshType >
void vcg::tri::Cylinder ( int  slices,
int  stacks,
MeshType &  m,
bool  capped = false 
)

Definition at line 1027 of file platonic.h.

template<class MeshType >
void vcg::tri::Disk ( MeshType &  m,
int  slices 
)

Definition at line 952 of file platonic.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
field_value vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::DistanceFromMesh ( OldCoordType pp) [inline]

return true if the distance form the mesh is less than maxdim and return distance

Definition at line 154 of file resampler.h.

template<class TRI_MESH_TYPE , class VertexPair >
static int vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::Do ( TriMeshType m,
VertexPair c,
const Point3< ScalarType > &  p 
) [inline, static]

Definition at line 234 of file edge_collapse.h.

template<class DodMeshType >
void vcg::tri::Dodecahedron ( DodMeshType &  in)

builds a Dodecahedron, (each pentagon is composed of 5 triangles)

Definition at line 80 of file platonic.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasEEAdjacency ( const std::vector< EdgeType > &  )

Definition at line 481 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeColor ( const std::vector< EdgeType > &  )

Definition at line 512 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeFlags ( const std::vector< EdgeType > &  )

Definition at line 514 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeMark ( const std::vector< EdgeType > &  )

Definition at line 513 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeNormal ( const std::vector< EdgeType > &  )

Definition at line 511 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasPerEdgeQuality ( const std::vector< EdgeType > &  )

Definition at line 510 of file vcg/complex/base.h.

template<class EdgeType >
bool vcg::tri::EdgeVectorHasVEAdjacency ( const std::vector< EdgeType > &  )

Definition at line 480 of file vcg/complex/base.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Execute ( TriMeshType &  m,
BaseParameterClass  
) [inline]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Execute ( TRIMESH_TYPE &  m,
BaseParameterClass  
) [inline]

Execute the flipping of the edge

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 266 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::Execute ( TRIMESH_TYPE &  m,
BaseParameterClass  
) [inline]

Execute the flipping of the edge

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 496 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Exist ( const vcg::Point3i p1,
const vcg::Point3i p2,
NewVertexPointer v 
) [inline]

Definition at line 398 of file resampler.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::expand ( ) [inline]

Definition at line 134 of file nring.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::expand ( int  k) [inline]

Definition at line 147 of file nring.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FaceColorLaplacian ( MeshType m,
int  step,
bool  SmoothSelected = false,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 584 of file smooth.h.

template<class SmoothMeshType >
static CoordType vcg::tri::Smooth< SmoothMeshType >::FaceErrorGrad ( CoordType p,
CoordType p0,
CoordType p1,
CoordType m 
) [inline, static]

Definition at line 1135 of file smooth.h.

template<class MeshType >
void vcg::tri::FaceGrid ( MeshType &  in,
int  w,
int  h 
)

Definition at line 801 of file platonic.h.

template<class MeshType >
void vcg::tri::FaceGrid ( MeshType &  in,
const std::vector< int > &  grid,
int  w,
int  h 
)

Definition at line 841 of file platonic.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalAngleThreshold ( MeshType m,
SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &  TD,
ScalarType  sigma 
) [inline, static]

Definition at line 1037 of file smooth.h.

template<class SmoothMeshType >
void vcg::tri::Smooth< SmoothMeshType >::FaceNormalFuzzyVectorSB ( MeshType m,
SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &  TD,
ScalarType  sigma 
) [inline]

Definition at line 892 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalLaplacianFF ( MeshType m,
int  step = 1,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 995 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FaceNormalLaplacianVF ( MeshType m) [inline, static]

Definition at line 946 of file smooth.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasFEAdjacency ( const std::vector< FaceType > &  )

Definition at line 540 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasFFAdjacency ( const std::vector< FaceType > &  )

Definition at line 539 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasFVAdjacency ( const std::vector< FaceType > &  )

Definition at line 541 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceColor ( const std::vector< FaceType > &  )

Definition at line 536 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceCurvatureDir ( const std::vector< FaceType > &  )

Definition at line 542 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceFlags ( const std::vector< FaceType > &  )

Definition at line 534 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceMark ( const std::vector< FaceType > &  )

Definition at line 537 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceNormal ( const std::vector< FaceType > &  )

Definition at line 535 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerFaceQuality ( const std::vector< FaceType > &  )

Definition at line 538 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeColor ( const std::vector< FaceType > &  )

Definition at line 523 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeNormal ( const std::vector< FaceType > &  )

Definition at line 524 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasPerWedgeTexCoord ( const std::vector< FaceType > &  )

Definition at line 525 of file vcg/complex/base.h.

template<class FaceType >
bool vcg::tri::FaceVectorHasVFAdjacency ( const std::vector< FaceType > &  )

Definition at line 482 of file vcg/complex/base.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FastFitMesh ( MeshType m,
SimpleTempData< typename MeshType::VertContainer, PDVertInfo > &  TDV,
bool  OnlySelected = false 
) [inline, static]

Definition at line 1174 of file smooth.h.

template<class TRI_MESH_TYPE , class VertexPair >
static void vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::FindSets ( VertexPair p,
EdgeSet es 
) [inline, static, private]

Definition at line 93 of file edge_collapse.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::FitMesh ( MeshType m,
SimpleTempData< typename MeshType::VertContainer, PDVertInfo > &  TDV,
SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &  TDF,
float  lambda 
) [inline, static]

Definition at line 1145 of file smooth.h.

template<class MeshType >
void vcg::tri::GenerateCameraMesh ( MeshType &  in)

Definition at line 1213 of file platonic.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
int vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GetMark ( ) const [inline]

Definition at line 159 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
PosType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GetPos ( ) const [inline]

Parameter

Definition at line 154 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetSliceIndex ( int  x,
int  z 
) [inline]

Definition at line 354 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetXIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
NewVertexPointer v 
) [inline]

if there is a vertex in z axis of a cell return the vertex or create it

Definition at line 491 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetYIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
NewVertexPointer v 
) [inline]

if there is a vertex in y axis of a cell return the vertex or create it

Definition at line 530 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::GetZIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
NewVertexPointer v 
) [inline]

if there is a vertex in z axis of a cell return the vertex or create it

Definition at line 553 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::GlobalMark ( ) [inline, static, protected]

mark for up_dating

Definition at line 82 of file tri_edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
static int& vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GlobalMark ( ) [inline, static, protected]

mark for up_dating

Definition at line 97 of file tri_edge_flip.h.

template<class MeshType >
void vcg::tri::Grid ( MeshType &  in,
int  w,
int  h,
float  wl,
float  hl,
float *  data = 0 
)

Definition at line 777 of file platonic.h.

template<class TriMeshType >
bool vcg::tri::HasEEAdjacency ( const TriMeshType &  m)

Definition at line 551 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEFAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 573 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEHAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 576 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasEVAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 567 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasFEAdjacency ( const TriMeshType &  m)

Definition at line 552 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasFFAdjacency ( const TriMeshType &  m)

Definition at line 550 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasFHAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 579 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasFVAdjacency ( const TriMeshType &  m)

Definition at line 553 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHEAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 585 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHFAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 588 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHNextAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 591 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHOppAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 597 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHPrevAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 594 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasHVAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 582 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeColor ( const TriMeshType &  m)

Definition at line 518 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeFlags ( const TriMeshType &  m)

Definition at line 520 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeMark ( const TriMeshType &  m)

Definition at line 519 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeNormal ( const TriMeshType &  m)

Definition at line 517 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeQuality ( const TriMeshType &  m)

Definition at line 516 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerEdgeVEAdjacency ( const TriMeshType &  m)

Definition at line 486 of file vcg/complex/base.h.

template<class MeshType >
bool vcg::tri::HasPerFaceAttribute ( const MeshType &  m,
std::string  name 
)

Definition at line 623 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceColor ( const TriMeshType &  m)

Definition at line 546 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceCurvatureDir ( const TriMeshType &  m)

Definition at line 549 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceFlags ( const TriMeshType &  m)

Definition at line 544 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceMark ( const TriMeshType &  m)

Definition at line 547 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceNormal ( const TriMeshType &  m)

Definition at line 545 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceQuality ( const TriMeshType &  m)

Definition at line 548 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerFaceVFAdjacency ( const TriMeshType &  m)

Definition at line 487 of file vcg/complex/base.h.

template<class MeshType >
bool vcg::tri::HasPerMeshAttribute ( const MeshType &  m,
std::string  name 
)

Definition at line 632 of file vcg/complex/base.h.

template<class MeshType >
bool vcg::tri::HasPerVertexAttribute ( const MeshType &  m,
std::string  name 
)

Definition at line 615 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexColor ( const TriMeshType &  m)

Definition at line 502 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexCurvature ( const TriMeshType &  m)

Definition at line 506 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexCurvatureDir ( const TriMeshType &  m)

Definition at line 507 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexFlags ( const TriMeshType &  m)

Definition at line 504 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexMark ( const TriMeshType &  m)

Definition at line 503 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexNormal ( const TriMeshType &  m)

Definition at line 501 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexQuality ( const TriMeshType &  m)

Definition at line 500 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexRadius ( const TriMeshType &  m)

Definition at line 505 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexTexCoord ( const TriMeshType &  m)

Definition at line 508 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexVEAdjacency ( const TriMeshType &  m)

Definition at line 485 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerVertexVFAdjacency ( const TriMeshType &  m)

Definition at line 484 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerWedgeColor ( const TriMeshType &  m)

Definition at line 527 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerWedgeNormal ( const TriMeshType &  m)

Definition at line 528 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasPerWedgeTexCoord ( const TriMeshType &  m)

Definition at line 529 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasPolyInfo ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 532 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasVEAdjacency ( const TriMeshType &  m)

Definition at line 556 of file vcg/complex/base.h.

template<class TriMeshType >
bool vcg::tri::HasVFAdjacency ( const TriMeshType &  m)

Definition at line 555 of file vcg/complex/base.h.

template<class CType0 , class CType1 , class CType2 , class CType3 >
bool vcg::tri::HasVHAdjacency ( const TriMesh< CType0, CType1, CType2, CType3 > &  )

Definition at line 564 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::Hexahedron ( MeshType &  in)

Definition at line 278 of file platonic.h.

template<class IcoMeshType >
void vcg::tri::Icosahedron ( IcoMeshType &  in)

Definition at line 221 of file platonic.h.

template<class MeshType >
int& vcg::tri::IMark ( MeshType &  m) [inline]

Access function to the incremental mark. You should not use this member directly. In most of the case just use IsMarked() and Mark()

Definition at line 438 of file vcg/complex/base.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::VertexType &  v 
)

Definition at line 37 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::FaceType &  f 
)

Definition at line 39 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::EdgeType &  e 
)

Definition at line 41 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::HEdgeType &  h 
)

Definition at line 43 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::VertexType *  vp 
)

Definition at line 46 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::FaceType *  fp 
)

Definition at line 48 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::EdgeType *  e 
)

Definition at line 50 of file allocate.h.

template<class MeshType >
size_t vcg::tri::Index ( MeshType &  m,
const typename MeshType::HEdgeType *  h 
)

Definition at line 52 of file allocate.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
virtual const char* vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Info ( TriMeshType &  m) [inline, virtual]

Definition at line 116 of file tri_edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
const char* vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Info ( TRIMESH_TYPE &  m) [inline]

Definition at line 284 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Init ( ) [inline, static]

Definition at line 58 of file tri_edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Init ( TriMeshType &  m,
HeapType h_ret,
BaseParameterClass pp 
) [inline, static]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
static void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Init ( TRIMESH_TYPE &  mesh,
HeapType heap,
BaseParameterClass pp 
) [inline, static]

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 293 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
static void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::Init ( TRIMESH_TYPE &  m,
HeapType heap,
BaseParameterClass pp 
) [inline, static]

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 520 of file tri_edge_flip.h.

template<class MeshType >
void vcg::tri::InitFaceIMark ( MeshType &  m) [inline]

Initialize the imark-system of the faces.

Definition at line 417 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::InitVertexIMark ( MeshType &  m) [inline]

Initialize the imark-system of the vertices.

Definition at line 427 of file vcg/complex/base.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
static void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Insert ( HeapType heap,
PosType p,
int  mark,
BaseParameterClass pp 
) [inline, static, protected]

Definition at line 103 of file tri_edge_flip.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::insertAndFlag ( FaceType f) [inline]

Definition at line 93 of file nring.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::insertAndFlag ( VertexType v) [inline]

Definition at line 106 of file nring.h.

template<class MeshType>
void vcg::tri::Nring< MeshType >::insertAndFlag1Ring ( VertexType v) [inline]

Definition at line 74 of file nring.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewCoordType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Interpolate ( const vcg::Point3i p1,
const vcg::Point3i p2,
int  dir 
) [inline]

interpolate

Definition at line 480 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsFeasible ( BaseParameterClass pp) [inline, virtual]

return true if no constraint disallow this operation to be performed (ex: change of topology in edge collapses)

Implements vcg::LocalModification< MeshType >.

Reimplemented in vcg::tri::TriEdgeCollapseQuadric< TriMeshType, VertexPair, MYTYPE, HelperType >, and vcg::tri::TriEdgeCollapseQuadric< MyMesh, VertexPair, MyTriEdgeCollapse, QInfoStandard< MyVertex > >.

Definition at line 191 of file tri_edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
virtual bool vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsFeasible ( BaseParameterClass _pp) [inline, virtual]

Check if this flipping operation can be performed. It is a topological and geometrical check.

Implements vcg::LocalModification< MeshType >.

Definition at line 191 of file tri_edge_flip.h.

template<class MeshType >
bool vcg::tri::IsMarked ( MeshType &  m,
typename MeshType::ConstVertexPointer  v 
) [inline]

Check if the vertex incremental mark matches the one of the mesh.

Parameters:
mthe mesh containing the element
vVertex pointer

Definition at line 443 of file vcg/complex/base.h.

template<class MeshType >
bool vcg::tri::IsMarked ( MeshType &  m,
typename MeshType::ConstFacePointer  f 
) [inline]

Check if the face incremental mark matches the one of the mesh.

Parameters:
mthe mesh containing the element
fFace pointer

Definition at line 448 of file vcg/complex/base.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
ModifierType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsOfType ( ) [inline, virtual]

Return the LocalOptimization type

Implements vcg::LocalModification< MeshType >.

Definition at line 168 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
ModifierType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsOfType ( ) [inline, virtual]

return the type of operation

Implements vcg::LocalModification< MeshType >.

Definition at line 189 of file tri_edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsSymmetric ( BaseParameterClass ) [inline, static]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
bool vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsUpToDate ( ) const [inline, virtual]

Check if the pos is updated

Implements vcg::LocalModification< MeshType >.

Definition at line 177 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
bool vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::IsUpToDate ( ) const [inline, virtual]

return true if the data have not changed since it was created

Implements vcg::LocalModification< MeshType >.

Definition at line 195 of file tri_edge_collapse.h.

template<class MeshType >
bool vcg::tri::IsValidPointer ( MeshType &  m,
const typename MeshType::VertexType *  vp 
)

Definition at line 55 of file allocate.h.

template<class MeshType >
bool vcg::tri::IsValidPointer ( MeshType &  m,
const typename MeshType::EdgeType *  ep 
)

Definition at line 57 of file allocate.h.

template<class MeshType >
bool vcg::tri::IsValidPointer ( MeshType &  m,
const typename MeshType::FaceType *  fp 
)

Definition at line 59 of file allocate.h.

template<class MeshType >
bool vcg::tri::IsValidPointer ( MeshType &  m,
const typename MeshType::HEdgeType *  hp 
)

Definition at line 61 of file allocate.h.

template<class SmoothMeshType >
vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::LaplacianInfo ( const CoordType _p,
const int  _n 
) [inline]

Definition at line 192 of file smooth.h.

template<class SmoothMeshType >
vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::LaplacianInfo ( ) [inline]

Definition at line 193 of file smooth.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionEdge ( ) [inline, static]

Definition at line 54 of file tri_edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionFace ( ) [inline, static]

Definition at line 53 of file tri_edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
static bool vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::LinkConditions ( VertexPair pos) [inline, static]

Definition at line 154 of file edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::LinkConditionVert ( ) [inline, static]

Definition at line 55 of file tri_edge_collapse.h.

template<class MeshType >
void vcg::tri::Mark ( MeshType &  m,
typename MeshType::VertexPointer  v 
) [inline]

Set the vertex incremental mark of the vertex to the one of the mesh.

Parameters:
mthe mesh containing the element
vVertex pointer

Definition at line 453 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::Mark ( MeshType &  m,
typename MeshType::FacePointer  f 
) [inline]

Set the face incremental mark of the vertex to the one of the mesh.

Parameters:
mthe mesh containing the element
fVertex pointer

Definition at line 458 of file vcg/complex/base.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
field_value vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MultiDistanceFromMesh ( OldCoordType pp) [inline]

Definition at line 206 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::NextSlice ( ) [inline]

Definition at line 361 of file resampler.h.

template<class MeshType>
vcg::tri::Nring< MeshType >::Nring ( VertexType v,
MeshType *  m 
) [inline]

Definition at line 62 of file nring.h.

template<class OctMeshType >
void vcg::tri::Octahedron ( OctMeshType &  in)

Definition at line 187 of file platonic.h.

template<typename MeshType >
bool vcg::tri::PointCloudNormal< MeshType >::WArc::operator< ( const WArc a) const [inline]

Definition at line 35 of file pointcloud_normal.h.

template<class MeshType >
void vcg::tri::OrientedAnnulus ( MeshType &  m,
Point3f  center,
Point3f  norm,
float  externalRadius,
float  internalRadius,
int  slices 
)

Definition at line 938 of file platonic.h.

template<class MeshType >
void vcg::tri::OrientedCylinder ( MeshType &  m,
const typename MeshType::CoordType  origin,
const typename MeshType::CoordType  end,
float  radius,
bool  capped,
int  slices = 32,
int  stacks = 4 
)

Definition at line 1020 of file platonic.h.

template<class MeshType >
void vcg::tri::OrientedDisk ( MeshType &  m,
int  slices,
typename MeshType::CoordType  center,
typename MeshType::CoordType  norm,
float  radius 
)

Definition at line 980 of file platonic.h.

template<class MeshType >
void vcg::tri::OrientedEllipticPrism ( MeshType &  m,
const typename MeshType::CoordType  origin,
const typename MeshType::CoordType  end,
float  radius,
float  xScale,
float  yScale,
bool  capped,
int  slices = 32,
int  stacks = 4 
)

Definition at line 997 of file platonic.h.

template<class MeshType >
void vcg::tri::OrientedRect ( MeshType &  square,
float  width,
float  height,
Point3f  c,
Point3f  dir = Point3f(0,0,0),
float  angleDeg = 0,
Point3f  preRotTra = Point3f(0,0,0) 
)

Definition at line 1258 of file platonic.h.

template<class MeshType >
void vcg::tri::OrientedSquare ( MeshType &  square,
float  width,
Point3f  c,
Point3f  dir = Point3f(0,0,0),
float  angleDeg = 0,
Point3f  preRotTra = Point3f(0,0,0) 
)

Definition at line 1275 of file platonic.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::OutOfDate ( ) [inline, static]

Definition at line 56 of file tri_edge_collapse.h.

template<typename MeshType >
vcg::tri::PointCloudNormal< MeshType >::Param::Param ( ) [inline]

Definition at line 95 of file pointcloud_normal.h.

template<class SmoothMeshType >
vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::PDFaceInfo ( ) [inline]

Definition at line 877 of file smooth.h.

template<class SmoothMeshType >
vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::PDFaceInfo ( const CoordType _m) [inline]

Definition at line 878 of file smooth.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip ( ) [inline]

Default constructor

Definition at line 116 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip ( PosType  pos,
int  mark,
BaseParameterClass pp 
) [inline]

Constructor with pos type

Definition at line 124 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip ( const PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc > &  par) [inline]

Copy Constructor

Definition at line 135 of file tri_edge_flip.h.

Definition at line 41 of file tri_edge_flip.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::PointCloudQualityAverage ( MeshType m,
int  neighbourSize = 8,
int  iter = 1 
) [inline, static]

Definition at line 631 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::PointCloudQualityMedian ( MeshType m,
int  medianSize = 8 
) [inline, static]

Definition at line 654 of file smooth.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
virtual ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::Priority ( ) const [inline, virtual]

Return the priority to be used in the heap (implement static priority)

Implements vcg::LocalModification< MeshType >.

Definition at line 209 of file tri_edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
virtual ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Priority ( ) const [inline, virtual]

Return the priority of this optimization

Implements vcg::LocalModification< MeshType >.

Definition at line 258 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::ProcessSlice ( EXTRACTOR_TYPE &  extractor) [inline]

Definition at line 301 of file resampler.h.

template<class MeshType , class ATTR_CONT >
void vcg::tri::ReorderAttribute ( ATTR_CONT &  c,
std::vector< size_t > &  newVertIndex,
MeshType &   
)

Definition at line 64 of file allocate.h.

template<class MeshType >
void vcg::tri::RequireCompactness ( MeshType &  m)

Definition at line 640 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireEEAdjacency ( MeshType &  m)

Definition at line 652 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireFEAdjacency ( MeshType &  m)

Definition at line 653 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireFFAdjacency ( MeshType &  m)

Definition at line 651 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireFHAdjacency ( MeshType &  m)

Definition at line 654 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeAttribute ( MeshType &  m,
const char *  name 
)

Definition at line 684 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeColor ( MeshType &  m)

Definition at line 668 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeFlags ( MeshType &  m)

Definition at line 670 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeMark ( MeshType &  m)

Definition at line 669 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeNormal ( MeshType &  m)

Definition at line 667 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerEdgeQuality ( MeshType &  m)

Definition at line 666 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceAttribute ( MeshType &  m,
const char *  name 
)

Definition at line 685 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceColor ( MeshType &  m)

Definition at line 674 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceCurvatureDir ( MeshType &  m)

Definition at line 677 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceFlags ( MeshType &  m)

Definition at line 672 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceMark ( MeshType &  m)

Definition at line 675 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceNormal ( MeshType &  m)

Definition at line 673 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceQuality ( MeshType &  m)

Definition at line 676 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceWedgeColor ( MeshType &  m)

Definition at line 679 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceWedgeNormal ( MeshType &  m)

Definition at line 680 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerFaceWedgeTexCoord ( MeshType &  m)

Definition at line 681 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerMeshAttribute ( MeshType &  m,
const char *  name 
)

Definition at line 686 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexAttribute ( MeshType &  m,
const char *  name 
)

Definition at line 683 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexColor ( MeshType &  m)

Definition at line 658 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexCurvature ( MeshType &  m)

Definition at line 662 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexCurvatureDir ( MeshType &  m)

Definition at line 663 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexFlags ( MeshType &  m)

Definition at line 660 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexMark ( MeshType &  m)

Definition at line 659 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexNormal ( MeshType &  m)

Definition at line 657 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexQuality ( MeshType &  m)

Definition at line 656 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexRadius ( MeshType &  m)

Definition at line 661 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePerVertexTexCoord ( MeshType &  m)

Definition at line 664 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequirePolygonalMesh ( MeshType &  m)

Definition at line 647 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireTriangularMesh ( MeshType &  m)

Definition at line 646 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireVEAdjacency ( MeshType &  m)

Definition at line 650 of file vcg/complex/base.h.

template<class MeshType >
void vcg::tri::RequireVFAdjacency ( MeshType &  m)

Definition at line 649 of file vcg/complex/base.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
static void vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Resample ( OldMeshType &  old_mesh,
NewMeshType &  new_mesh,
NewBoxType  volumeBox,
vcg::Point3< int >  accuracy,
float  max_dist,
float  thr = 0,
bool  DiscretizeFlag = false,
bool  MultiSampleFlag = false,
bool  AbsDistFlag = false,
vcg::CallBackPos cb = 0 
) [inline, static]

resample the mesh using marching cube algorithm ,the accuracy is the dimension of one cell the parameter

be sure that the bounding box is updated

Definition at line 601 of file resampler.h.

template<class MeshType , class ATTR_CONT >
void vcg::tri::ResizeAttribute ( ATTR_CONT &  c,
size_t  sz,
MeshType &   
)

Definition at line 71 of file allocate.h.

Definition at line 42 of file tri_edge_flip.h.

template<class VERTEX_TYPE>
void vcg::tri::BasicVertexPair< VERTEX_TYPE >::Sort ( ) [inline]

Definition at line 38 of file edge_collapse.h.

template<class MeshType >
void vcg::tri::Sphere ( MeshType &  in,
const int  subdiv = 3 
)

Definition at line 403 of file platonic.h.

template<class MeshType >
void vcg::tri::SphericalCap ( MeshType &  in,
float  angleRad,
const int  subdiv = 3 
)

Definition at line 358 of file platonic.h.

template<class MeshType >
void vcg::tri::Square ( MeshType &  in)

Definition at line 326 of file platonic.h.

template<class MeshType >
void vcg::tri::SuperEllipsoid ( MeshType &  m,
float  rFeature,
float  sFeature,
float  tFeature,
int  hRingDiv = 24,
int  vRingDiv = 12 
)

Generate a SuperEllipsoid eg a solid whose horizontal sections are super-ellipses (Lamé curves) with the same exponent r, and whose vertical sections through the center are super-ellipses with the same exponent t.

Definition at line 660 of file platonic.h.

template<class MeshType >
void vcg::tri::SuperToroid ( MeshType &  m,
float  hRingRadius,
float  vRingRadius,
float  vSquareness,
float  hSquareness,
int  hRingDiv = 24,
int  vRingDiv = 12 
)

SuperToroid

Generate a a supertoroid, e.g. a member of a family of doughnut-like surfaces (technically, a topological torus) whose shape is defined by mathematical formulas similar to those that define the superquadrics.

Definition at line 623 of file platonic.h.

template<class TetraMeshType >
void vcg::tri::Tetrahedron ( TetraMeshType &  in)

A set of functions that builds meshes that represent surfaces of platonic solids, and other simple shapes.

The 1st parameter is the mesh that will be filled with the solid.

Definition at line 51 of file platonic.h.

template<class TRIMESH_TYPE , class MYTYPE >
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip ( ) [inline]

Default constructor

Definition at line 432 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip ( const PosType  pos,
int  mark,
BaseParameterClass pp 
) [inline]

Constructor with pos type

Definition at line 437 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::TopoEdgeFlip ( const TopoEdgeFlip< TRIMESH_TYPE, MYTYPE > &  par) [inline]

Copy Constructor

Definition at line 447 of file tri_edge_flip.h.

template<class MeshType >
void vcg::tri::Torus ( MeshType &  m,
float  hRingRadius,
float  vRingRadius,
int  hRingDiv = 24,
int  vRingDiv = 12 
)

Definition at line 574 of file platonic.h.

template<class SmoothMeshType >
static CoordType vcg::tri::Smooth< SmoothMeshType >::TriAreaGradient ( CoordType p,
CoordType p0,
CoordType p1 
) [inline, static]

Definition at line 1091 of file smooth.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::TriEdgeCollapse ( ) [inline]

Default Constructor.

Definition at line 92 of file tri_edge_collapse.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::TriEdgeCollapse ( const VertexPair p,
int  mark,
BaseParameterClass pp 
) [inline]

Constructor with postype.

Definition at line 95 of file tri_edge_collapse.h.

template<class TRIMESH_TYPE, class MYTYPE>
vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip ( ) [inline]

Default constructor

Definition at line 357 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE>
vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip ( const PosType  pos,
int  mark,
BaseParameterClass pp 
) [inline]

Constructor with pos type

Definition at line 362 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE>
vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >::TriEdgeFlip ( const TriEdgeFlip< TRIMESH_TYPE, MYTYPE > &  par) [inline]

Copy Constructor

Definition at line 372 of file tri_edge_flip.h.

template<class MeshType >
void vcg::tri::UnMarkAll ( MeshType &  m) [inline]

Unmark, in constant time, all the elements (face and vertices) of a mesh.

Parameters:
mthe mesh containing the element

In practice this function just increment the internal counter that stores the value for which an element is considered marked; therefore all the mesh elements become immediately un-mmarked.

Definition at line 467 of file vcg/complex/base.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
void vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::UpdateHeap ( HeapType ,
BaseParameterClass pp 
) [inline, virtual]
template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
virtual void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::UpdateHeap ( HeapType ,
BaseParameterClass pp 
) [inline, virtual]

Update the heap as a consequence of this operation.

Implements vcg::LocalModification< MeshType >.

Reimplemented in vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 314 of file tri_edge_flip.h.

template<class TRIMESH_TYPE , class MYTYPE >
void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::UpdateHeap ( HeapType ,
BaseParameterClass pp 
) [inline, virtual]

Update the heap as a consequence of this operation.

Reimplemented from vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE >.

Definition at line 539 of file tri_edge_flip.h.

template<class VERTEX_TYPE>
VERTEX_TYPE*& vcg::tri::BasicVertexPair< VERTEX_TYPE >::V ( int  i) [inline]

Definition at line 39 of file edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::V ( const Point3i p) [inline]

Definition at line 128 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::V ( int  x,
int  y,
int  z 
) [inline]

Definition at line 148 of file resampler.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexColorLaplacian ( MeshType m,
int  step,
bool  SmoothSelected = false,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 509 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacian ( MeshType m,
int  step,
bool  SmoothSelected = false,
bool  cotangentWeight = false,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 259 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianAngleWeighted ( MeshType m,
int  step,
ScalarType  delta 
) [inline, static]

Definition at line 80 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianBlend ( MeshType m,
int  step,
float  alpha,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 330 of file smooth.h.

template<class SmoothMeshType >
void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianCurvatureFlow ( MeshType ,
int  ,
ScalarType   
) [inline]

Definition at line 72 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianHC ( MeshType m,
int  step,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 437 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianQuality ( MeshType m,
int  step,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 405 of file smooth.h.

template<class SmoothMeshType >
template<class GRID , class MeshTypeTri >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianReproject ( MeshType m,
GRID grid,
MeshTypeTri &  gridmesh 
) [inline, static]

Laplacian smoothing with a reprojection on a target surface.

Definition at line 1272 of file smooth.h.

template<class SmoothMeshType >
template<class GRID , class MeshTypeTri >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordLaplacianReproject ( MeshType m,
GRID grid,
MeshTypeTri &  gridmesh,
typename MeshType::VertexType *  vp 
) [inline, static]

Definition at line 1283 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordPasoDoble ( MeshType m,
int  NormalSmoothStep,
typename MeshType::ScalarType  Sigma = 0,
int  FitStep = 50,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 1213 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordPlanarLaplacian ( MeshType m,
int  step,
float  AngleThrRad = math::ToRad(1.0),
bool  SmoothSelected = false,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 279 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordScaleDependentLaplacian_Fujiwara ( MeshType m,
int  step,
ScalarType  delta 
) [inline, static]

Definition at line 128 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordTaubin ( MeshType m,
int  step,
float  lambda,
float  mu,
bool  SmoothSelected = false,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 371 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordViewDepth ( MeshType m,
const CoordType viewpoint,
const ScalarType  alpha,
int  step,
bool  SmoothBorder = false 
) [inline, static]

Definition at line 791 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexNormalLaplacian ( MeshType m,
int  step,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 733 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexNormalPointCloud ( MeshType m,
int  neighborNum,
int  iterNum,
KdTree< ScalarType > *  tp = 0 
) [inline, static]

Definition at line 1233 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexQualityLaplacian ( MeshType m,
int  step = 1,
bool  SmoothSelected = false 
) [inline, static]

Definition at line 676 of file smooth.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexColor ( const std::vector< VertexType > &  )

Definition at line 492 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexCurvature ( const std::vector< VertexType > &  )

Definition at line 496 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexCurvatureDir ( const std::vector< VertexType > &  )

Definition at line 497 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexFlags ( const std::vector< VertexType > &  )

Definition at line 494 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexMark ( const std::vector< VertexType > &  )

Definition at line 493 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexNormal ( const std::vector< VertexType > &  )

Definition at line 491 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexQuality ( const std::vector< VertexType > &  )

Definition at line 490 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexRadius ( const std::vector< VertexType > &  )

Definition at line 495 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasPerVertexTexCoord ( const std::vector< VertexType > &  )

Definition at line 498 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasVEAdjacency ( const std::vector< VertexType > &  )

Definition at line 479 of file vcg/complex/base.h.

template<class VertexType >
bool vcg::tri::VertexVectorHasVFAdjacency ( const std::vector< VertexType > &  )

Definition at line 478 of file vcg/complex/base.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
static int& vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::FailStat::Volume ( ) [inline, static]

Definition at line 52 of file tri_edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
std::pair<bool,NewScalarType> vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::VV ( int  x,
int  y,
int  z 
) [inline]

Definition at line 134 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::Walker ( const Box3< NewScalarType > &  _bbox,
Point3i  _siz 
) [inline]

Definition at line 100 of file resampler.h.

template<typename MeshType >
vcg::tri::PointCloudNormal< MeshType >::WArc::WArc ( VertexPointer  _s,
VertexPointer  _t 
) [inline]

Definition at line 30 of file pointcloud_normal.h.

template<class MeshType>
vcg::tri::Nring< MeshType >::~Nring ( ) [inline]

Definition at line 69 of file nring.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::~PlanarEdgeFlip ( ) [inline]

Definition at line 145 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::~TriEdgeCollapse ( ) [inline]

Definition at line 102 of file tri_edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::~Walker ( ) [inline]

Definition at line 124 of file resampler.h.


Variable Documentation

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
GridType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_g [protected]

Definition at line 92 of file resampler.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
int vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_localMark [protected]

Mark for updating

Definition at line 92 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewMeshType* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_newM [protected]

Definition at line 90 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
OldMeshType* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_oldM [protected]

Definition at line 91 of file resampler.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
PosType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_pos [protected]

the pos of the flipping

Definition at line 82 of file tri_edge_flip.h.

template<class TRIMESH_TYPE, class MYTYPE, typename TRIMESH_TYPE::ScalarType(*)(Point3< typename TRIMESH_TYPE::ScalarType > const &p0, Point3< typename TRIMESH_TYPE::ScalarType > const &p1, Point3< typename TRIMESH_TYPE::ScalarType > const &p2) QualityFunc = Quality>
ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::_priority [protected]

priority in the heap

Definition at line 87 of file tri_edge_flip.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::_priority [protected]

priority in the heap

Definition at line 88 of file tri_edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
field_value* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_v_cs [protected]

Definition at line 87 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
field_value* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_v_ns [protected]

Definition at line 88 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
VertexIndex* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_x_cs [protected]

Definition at line 77 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
VertexIndex* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_x_ns [protected]

Definition at line 80 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
VertexIndex* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_y_cs [protected]

Definition at line 78 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
VertexIndex* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_z_cs [protected]

Definition at line 79 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
VertexIndex* vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::_z_ns [protected]

Definition at line 81 of file resampler.h.

template<class SmoothMeshType >
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::a

Definition at line 505 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::AbsDistFlag

Definition at line 99 of file resampler.h.

template<class MeshType>
std::vector<FaceType*> vcg::tri::Nring< MeshType >::allF

Definition at line 55 of file nring.h.

template<class MeshType>
std::vector<VertexType*> vcg::tri::Nring< MeshType >::allV

Definition at line 54 of file nring.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av0

Definition at line 87 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av01

Definition at line 87 of file edge_collapse.h.

template<class TRI_MESH_TYPE , class VertexPair >
VFIVec vcg::tri::EdgeCollapser< TRI_MESH_TYPE, VertexPair >::EdgeSet::av1

Definition at line 87 of file edge_collapse.h.

template<class SmoothMeshType >
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::b

Definition at line 504 of file smooth.h.

template<class SmoothMeshType >
ScalarType vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::cnt

Definition at line 195 of file smooth.h.

template<class SmoothMeshType >
int vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::cnt

Definition at line 434 of file smooth.h.

template<class SmoothMeshType >
int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::cnt

Definition at line 506 of file smooth.h.

template<class SmoothMeshType >
int vcg::tri::Smooth< SmoothMeshType >::QualitySmoothInfo::cnt

Definition at line 628 of file smooth.h.

template<typename MeshType >
int vcg::tri::PointCloudNormal< MeshType >::Param::coherentAdjNum

number of itaration of a simple normal smoothing (use the same number of ajdacent of fittingAdjNjm)

Definition at line 105 of file pointcloud_normal.h.

Definition at line 47 of file tri_edge_flip.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::CurrentSlice [protected]

Definition at line 73 of file resampler.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::dif

Definition at line 432 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::DiscretizeFlag

Definition at line 97 of file resampler.h.

template<typename MeshType >
int vcg::tri::PointCloudNormal< MeshType >::Param::fittingAdjNum

Definition at line 103 of file pointcloud_normal.h.

template<class SmoothMeshType >
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::g

Definition at line 503 of file smooth.h.

template<class MeshType>
std::vector<FaceType*> vcg::tri::Nring< MeshType >::lastF

Definition at line 58 of file nring.h.

template<class MeshType>
std::vector<VertexType*> vcg::tri::Nring< MeshType >::lastV

Definition at line 57 of file nring.h.

template<class SmoothMeshType >
ScalarType vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo::LenSum

Definition at line 66 of file smooth.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
int vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::localMark [protected]

mark for up_dating

Definition at line 85 of file tri_edge_collapse.h.

template<class MeshType>
MeshType* vcg::tri::Nring< MeshType >::m

Definition at line 60 of file nring.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::PDFaceInfo::m

Definition at line 879 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
MarkerFace vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::markerFunctor [protected]

Definition at line 75 of file resampler.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::max_dim

Definition at line 95 of file resampler.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
TriMeshType* vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::mt [protected]

Definition at line 77 of file tri_edge_collapse.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
bool vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::MultiSampleFlag

Definition at line 98 of file resampler.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::PDVertInfo::np

Definition at line 870 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
NewScalarType vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::offset

Definition at line 96 of file resampler.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo::PntSum

Definition at line 65 of file smooth.h.

template<class TriMeshType, class VertexPair, class MYTYPE>
VertexPair vcg::tri::TriEdgeCollapse< TriMeshType, VertexPair, MYTYPE >::pos [protected]

the pair to collapse

Definition at line 79 of file tri_edge_collapse.h.

template<class SmoothMeshType >
unsigned int vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo::r

Definition at line 502 of file smooth.h.

template<class OldMeshType , class NewMeshType , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OldMeshType::ScalarType >>
int vcg::tri::Resampler< OldMeshType, NewMeshType, DISTFUNCTOR >::Walker::SliceSize [protected]

Definition at line 72 of file resampler.h.

template<typename MeshType >
int vcg::tri::PointCloudNormal< MeshType >::Param::smoothingIterNum

number of adjacent nodes used for computing the fitting plane

Definition at line 104 of file pointcloud_normal.h.

template<typename MeshType >
VertexPointer vcg::tri::PointCloudNormal< MeshType >::WArc::src

Definition at line 32 of file pointcloud_normal.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::LaplacianInfo::sum

Definition at line 194 of file smooth.h.

template<class SmoothMeshType >
CoordType vcg::tri::Smooth< SmoothMeshType >::HCSmoothInfo::sum

Definition at line 433 of file smooth.h.

template<class SmoothMeshType >
ScalarType vcg::tri::Smooth< SmoothMeshType >::QualitySmoothInfo::sum

Definition at line 627 of file smooth.h.

template<typename MeshType >
VertexPointer vcg::tri::PointCloudNormal< MeshType >::WArc::trg

Definition at line 33 of file pointcloud_normal.h.

template<typename MeshType >
bool vcg::tri::PointCloudNormal< MeshType >::Param::useViewPoint

position of a viewpoint used to disambiguate direction

Definition at line 107 of file pointcloud_normal.h.

template<class VERTEX_TYPE>
VERTEX_TYPE* vcg::tri::BasicVertexPair< VERTEX_TYPE >::v[2] [private]

Definition at line 42 of file edge_collapse.h.

template<typename MeshType >
CoordType vcg::tri::PointCloudNormal< MeshType >::Param::viewPoint

number of nodes used in the coherency pass

Definition at line 106 of file pointcloud_normal.h.

template<typename MeshType >
float vcg::tri::PointCloudNormal< MeshType >::WArc::w

Definition at line 34 of file pointcloud_normal.h.



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