Trimesh

Classes

struct  vcg::tri::BaseMeshTypeHolder< TYPESPOOL >
class  vcg::tri::Clean< CleanMeshType >
 Class of static functions to clean/correct/restore meshs. More...
class  vcg::tri::Smooth< SmoothMeshType >::ColorSmoothInfo
struct  vcg::tri::Der< T, CONT >
struct  vcg::tri::DummyContainer
class  vcg::tri::EdgeCollapse< TRI_MESH_TYPE >
class  vcg::tri::ExtendedMarchingCubes< TRIMESH_TYPE, WALKER_TYPE >
 This class implements the Extended Marching Cubes algorithm. 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::Smooth< SmoothMeshType >::PDFaceInfo
class  vcg::tri::Smooth< SmoothMeshType >::PDVertInfo
class  vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >
struct  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< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >
class  vcg::tri::Smooth< SmoothMeshType >::ScaleLaplacianInfo
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, MYTYPE >
class  vcg::tri::TriEdgeFlip< TRIMESH_TYPE, MYTYPE >
class  vcg::tri::TriMesh< Container0, Container1, Container2, Container3 >
class  vcg::tri::UpdateBounding< ComputeMeshType >
 Management, updating and computation of per-vertex and per-face normals. More...
class  vcg::tri::UpdateColor< UpdateMeshType >
 Generation of per-vertex and per-face colors according to various strategy. 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::UpdateEdges< ComputeMeshType >
 This class is used to compute or update the precomputed data used to efficiently compute point-face distances. 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::UpdateNormals< ComputeMeshType >
 Management, updating and computation of per-vertex and per-face 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 computation of per-vertex and per-face normals. More...
class  vcg::tri::UpdateTexture< ComputeMeshType >
 This class is used to update vertex position according to a transformation matrix. More...
class  vcg::tri::UpdateTopology< UpdateMeshType >
 Generation of per-vertex and per-face topological information. More...
class  vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker

Typedefs

typedef vcg::Box3< ScalarTypevcg::tri::Smooth::Box3Type
typedef
MeshType::VertexType::CoordType 
vcg::tri::Smooth::CoordType
typedef
FaceType::VertexType::CoordType 
vcg::tri::EdgeCollapse::CoordType
 The coordinate type.
typedef TRIMESH_TYPE::CoordType vcg::tri::TopoEdgeFlip::CoordType
typedef TRIMESH_TYPE::CoordType vcg::tri::TriEdgeFlip::CoordType
typedef TRIMESH_TYPE::CoordType vcg::tri::PlanarEdgeFlip::CoordType
typedef
FaceType::VertexType::CoordType 
vcg::tri::TriEdgeCollapse::CoordType
 The coordinate type.
typedef
TriMeshType::FaceType::EdgeType 
vcg::tri::EdgeCollapse::EdgeType
 half edge type
typedef VertexType::EdgeType vcg::tri::TriEdgeCollapse::EdgeType
 half edge type
typedef std::vector< EdgeType > vcg::tri::EdgeCollapse::EdgeVec
 vector of pos
typedef Old_Mesh::FaceContainer vcg::tri::Resampler::Walker::FaceCont
typedef MeshType::FaceContainer vcg::tri::Smooth::FaceContainer
typedef TriMeshType::FaceContainer vcg::tri::EdgeCollapse::FaceContainer
 the container of tetrahedron type
typedef MeshType::FaceIterator vcg::tri::Smooth::FaceIterator
typedef TriMeshType::FaceIterator vcg::tri::EdgeCollapse::FaceIterator
 The tetra iterator type.
typedef TRIMESH_TYPE::FaceIterator vcg::tri::TopoEdgeFlip::FaceIterator
typedef TRIMESH_TYPE::FaceIterator vcg::tri::PlanarEdgeFlip::FaceIterator
typedef MeshType::FacePointer vcg::tri::Smooth::FacePointer
typedef TRIMESH_TYPE::FacePointer vcg::tri::TopoEdgeFlip::FacePointer
typedef TRIMESH_TYPE::FacePointer vcg::tri::PlanarEdgeFlip::FacePointer
typedef MeshType::FaceType vcg::tri::Smooth::FaceType
typedef TriMeshType::FaceType vcg::tri::EdgeCollapse::FaceType
 The tetrahedron type.
typedef TRIMESH_TYPE::FaceType vcg::tri::TopoEdgeFlip::FaceType
typedef TriMeshType::FaceType vcg::tri::TriEdgeCollapse::FaceType
 The tetrahedron type.
typedef std::pair< bool, float > vcg::tri::Resampler::Walker::field_value
typedef vcg::GridStaticPtr
< typename Old_Mesh::FaceType > 
vcg::tri::Resampler::Walker::GridType
typedef LocalOptimization
< TRIMESH_TYPE >::HeapElem 
vcg::tri::TopoEdgeFlip::HeapElem
typedef LocalOptimization
< TRIMESH_TYPE >::HeapElem 
vcg::tri::PlanarEdgeFlip::HeapElem
typedef LocalOptimization
< TriMeshType >::HeapElem 
vcg::tri::TriEdgeCollapse::HeapElem
typedef LocalOptimization
< TRIMESH_TYPE >::HeapType 
vcg::tri::TopoEdgeFlip::HeapType
typedef LocalOptimization
< TRIMESH_TYPE >::HeapType 
vcg::tri::PlanarEdgeFlip::HeapType
typedef LocalOptimization
< TriMeshType >::HeapType 
vcg::tri::TriEdgeCollapse::HeapType
typedef tri::FaceTmark< Old_Mesh > vcg::tri::Resampler::Walker::MarkerFace
typedef
vcg::tri::MarchingCubes
< New_Mesh, MyWalker > 
vcg::tri::Resampler::MyMarchingCubes
typedef Walker vcg::tri::Resampler::MyWalker
typedef NEW_MESH_TYPE vcg::tri::Resampler::Walker::New_Mesh
typedef NEW_MESH_TYPE vcg::tri::Resampler::New_Mesh
typedef New_Mesh::CoordType vcg::tri::Resampler::Walker::NewCoordType
typedef OLD_MESH_TYPE vcg::tri::Resampler::Walker::Old_Mesh
typedef vcg::face::Pos< FaceType > vcg::tri::TopoEdgeFlip::PosType
typedef vcg::face::Pos< FaceType > vcg::tri::TriEdgeFlip::PosType
typedef vcg::face::Pos< FaceType > vcg::tri::PlanarEdgeFlip::PosType
typedef MeshType::ScalarType vcg::tri::Smooth::ScalarType
typedef
TriMeshType::VertexType::ScalarType 
vcg::tri::EdgeCollapse::ScalarType
 The scalar type.
typedef TRIMESH_TYPE::ScalarType vcg::tri::TopoEdgeFlip::ScalarType
typedef TRIMESH_TYPE::ScalarType vcg::tri::TriEdgeFlip::ScalarType
typedef TRIMESH_TYPE::ScalarType vcg::tri::PlanarEdgeFlip::ScalarType
typedef
TriMeshType::VertexType::ScalarType 
vcg::tri::TriEdgeCollapse::ScalarType
typedef TriMeshType::VertContainer vcg::tri::EdgeCollapse::VertContainer
 the container of vertex type
typedef MeshType::VertexIterator vcg::tri::Smooth::VertexIterator
typedef TriMeshType::VertexIterator vcg::tri::EdgeCollapse::VertexIterator
 The vertex iterator type.
typedef
TRIMESH_TYPE::VertexIterator 
vcg::tri::TopoEdgeFlip::VertexIterator
typedef MeshType::VertexPointer vcg::tri::Smooth::VertexPointer
typedef FaceType::VertexPointer vcg::tri::EdgeCollapse::VertexPointer
typedef New_Mesh::VertexType * vcg::tri::Resampler::Walker::VertexPointer
typedef TRIMESH_TYPE::VertexPointer vcg::tri::PlanarEdgeFlip::VertexPointer
typedef MeshType::VertexType vcg::tri::Smooth::VertexType
typedef FaceType::VertexType vcg::tri::EdgeCollapse::VertexType
 The vertex type.
typedef TRIMESH_TYPE::VertexType vcg::tri::PlanarEdgeFlip::VertexType
typedef
TriMeshType::FaceType::VertexType 
vcg::tri::TriEdgeCollapse::VertexType
 The vertex type.
typedef vcg::face::VFIterator
< FaceType > 
vcg::tri::EdgeCollapse::VFI
 of VFIterator
typedef std::vector
< vcg::face::VFIterator
< FaceType > > 
vcg::tri::EdgeCollapse::VFIVec
 vector of VFIterator
typedef vcg::face::VFIterator
< FaceType > 
vcg::tri::Smooth::VFLocalIterator

Functions

static void vcg::tri::Smooth::AccumulateLaplacianInfo (MeshType &m, SimpleTempData< typename MeshType::VertContainer, LaplacianInfo > &TD)
static VFIVec & vcg::tri::EdgeCollapse::AV0 ()
static VFIVec & vcg::tri::EdgeCollapse::AV01 ()
static VFIVec & vcg::tri::EdgeCollapse::AV1 ()
void vcg::tri::Resampler::Walker::Begin ()
static int & vcg::tri::TriEdgeCollapse::FailStat::Border ()
template<class MeshType >
void vcg::tri::Box (MeshType &in, const typename MeshType::BoxType &bb)
template<class MeshType , class V , class F >
void vcg::tri::Build (MeshType &in, const V &v, const F &f)
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler::Walker::BuildMesh (Old_Mesh &old_mesh, New_Mesh &new_mesh, EXTRACTOR_TYPE &extractor, vcg::CallBackPos *cb)
void vcg::tri::Resampler::Walker::ComputeConsensus (int slice, field_value *slice_values)
ScalarType vcg::tri::TopoEdgeFlip::ComputePriority ()
ScalarType vcg::tri::TriEdgeFlip::ComputePriority ()
virtual ScalarType vcg::tri::PlanarEdgeFlip::ComputePriority ()
ScalarType vcg::tri::TriEdgeCollapse::ComputePriority ()
 Compute the priority to be used in the heap.
void vcg::tri::Resampler::Walker::ComputeSliceValues (int slice, field_value *slice_values)
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)
static ScalarTypevcg::tri::PlanarEdgeFlip::CoplanarAngleThresholdDeg ()
template<class ScalarType >
CoordType vcg::tri::Smooth::CrossProdGradient (CoordType &p, CoordType &p0, CoordType &p1, CoordType &m)
template<class MeshType >
void vcg::tri::Cylinder (int slices, int stacks, MeshType &m)
field_value vcg::tri::Resampler::Walker::DistanceFromMesh (Point3f &pp, Old_Mesh *)
 return true if the distance form the mesh is less than maxdim and return distance
int vcg::tri::EdgeCollapse::DoCollapse (TriMeshType &m, EdgeType &c, const Point3< ScalarType > &p)
template<class DodMeshType >
void vcg::tri::Dodecahedron (DodMeshType &in)
 vcg::tri::EdgeCollapse::EdgeCollapse ()
 Default Constructor.
void vcg::tri::TopoEdgeFlip::Execute (TRIMESH_TYPE &m)
void vcg::tri::PlanarEdgeFlip::Execute (TRIMESH_TYPE &m)
void vcg::tri::TriEdgeCollapse::Execute (TriMeshType &m)
bool vcg::tri::Resampler::Walker::Exist (const vcg::Point3i &p1, const vcg::Point3i &p2, VertexPointer &v)
static void vcg::tri::Smooth::FaceColorLaplacian (MeshType &m, int step, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
CoordType vcg::tri::Smooth::FaceErrorGrad (CoordType &p, CoordType &p0, CoordType &p1, CoordType &m)
template<class MeshType >
void vcg::tri::FaceGrid (MeshType &in, const std::vector< int > &grid, int w, int h)
template<class MeshType >
void vcg::tri::FaceGrid (MeshType &in, int w, int h)
static void vcg::tri::Smooth::FaceNormalAngleThreshold (MeshType &m, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TD, ScalarType sigma)
void vcg::tri::Smooth::FaceNormalFuzzyVectorSB (MeshType &m, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TD, ScalarType sigma)
static void vcg::tri::Smooth::FaceNormalLaplacianFF (MeshType &m, int step=1, bool SmoothSelected=false)
static void vcg::tri::Smooth::FaceNormalLaplacianVF (MeshType &m)
static void vcg::tri::Smooth::FastFitMesh (MeshType &m, SimpleTempData< typename MeshType::VertContainer, PDVertInfo > &TDV, SimpleTempData< typename MeshType::FaceContainer, PDFaceInfo > &TDF, bool OnlySelected=false)
void vcg::tri::EdgeCollapse::FindSets (EdgeType &p)
void vcg::tri::Smooth::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::GetMark ()
PosType vcg::tri::PlanarEdgeFlip::GetPos ()
int vcg::tri::Resampler::Walker::GetSliceIndex (int x, int z)
void vcg::tri::Resampler::Walker::GetXIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, VertexPointer &v)
 if there is a vertex in z axis of a cell return the vertex or create it
void vcg::tri::Resampler::Walker::GetYIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, VertexPointer &v)
 if there is a vertex in y axis of a cell return the vertex or create it
void vcg::tri::Resampler::Walker::GetZIntercept (const vcg::Point3i &p1, const vcg::Point3i &p2, VertexPointer &v)
 if there is a vertex in z axis of a cell return the vertex or create it
static int & vcg::tri::PlanarEdgeFlip::GlobalMark ()
static int & vcg::tri::TriEdgeCollapse::GlobalMark ()
 mark for up_dating
template<class MeshType >
void vcg::tri::Grid (MeshType &in, int w, int h, float wl, float hl, float *data)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEEAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEFAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEHAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEVAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFEAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFFAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFHAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFVAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHEAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHFAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHNextAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHOppAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHPrevAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHVAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class MESH_TYPE >
bool vcg::tri::HasPerFaceAttribute (const MESH_TYPE &m, std::string name)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceColor (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceFlags (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceMark (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceNormal (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceQuality (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceVFAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class MESH_TYPE >
bool vcg::tri::HasPerMeshAttribute (const MESH_TYPE &m, std::string name)
template<class MESH_TYPE >
bool vcg::tri::HasPerVertexAttribute (const MESH_TYPE &m, std::string name)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexColor (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexCurvature (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexCurvatureDir (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexFlags (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexMark (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexNormal (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexQuality (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexRadius (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexTexCoord (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexVFAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeColor (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeNormal (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeTexCoord (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasVEAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasVHAdjacency (const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &)
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)
const char * vcg::tri::PlanarEdgeFlip::Info (TRIMESH_TYPE &m)
virtual const char * vcg::tri::TriEdgeCollapse::Info (TriMeshType &m)
static void vcg::tri::TopoEdgeFlip::Init (TRIMESH_TYPE &m, HeapType &heap)
static void vcg::tri::PlanarEdgeFlip::Init (TRIMESH_TYPE &mesh, HeapType &heap)
static void vcg::tri::TriEdgeCollapse::Init (TriMeshType &m, HeapType &h_ret)
static void vcg::tri::TriEdgeCollapse::FailStat::Init ()
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::Insert (HeapType &heap, PosType &p, int mark)
NewCoordType vcg::tri::Resampler::Walker::Interpolate (const vcg::Point3i &p1, const vcg::Point3i &p2, int dir)
 interpolate
virtual bool vcg::tri::PlanarEdgeFlip::IsFeasible ()
bool vcg::tri::TriEdgeCollapse::IsFeasible ()
 return true if no constraint disallow this operation to be performed (ex: change of topology in edge collapses)
template<class MeshType >
bool vcg::tri::IsMarked (MeshType &m, typename MeshType::ConstFacePointer f)
template<class MeshType >
bool vcg::tri::IsMarked (MeshType &m, typename MeshType::ConstVertexPointer v)
ModifierType vcg::tri::PlanarEdgeFlip::IsOfType ()
ModifierType vcg::tri::TriEdgeCollapse::IsOfType ()
 return the type of operation
static bool vcg::tri::TriEdgeCollapse::IsSymmetric ()
bool vcg::tri::PlanarEdgeFlip::IsUpToDate ()
bool vcg::tri::TriEdgeCollapse::IsUpToDate ()
 return true if the data have not changed since it was created
 vcg::tri::Smooth::LaplacianInfo::LaplacianInfo ()
static int & vcg::tri::TriEdgeCollapse::FailStat::LinkConditionEdge ()
static int & vcg::tri::TriEdgeCollapse::FailStat::LinkConditionFace ()
bool vcg::tri::EdgeCollapse::LinkConditions (EdgeType pos)
bool vcg::tri::EdgeCollapse::LinkConditionsOld (EdgeType pos)
static int & vcg::tri::TriEdgeCollapse::FailStat::LinkConditionVert ()
template<class MeshType >
void vcg::tri::Mark (MeshType &m, typename MeshType::FacePointer f)
template<class MeshType >
void vcg::tri::Mark (MeshType &m, typename MeshType::VertexPointer v)
field_value vcg::tri::Resampler::Walker::MultiDistanceFromMesh (Point3f &pp, Old_Mesh *)
void vcg::tri::Resampler::Walker::NextSlice ()
template<class OctMeshType >
void vcg::tri::Octahedron (OctMeshType &in)
static int & vcg::tri::TriEdgeCollapse::FailStat::OutOfDate ()
 vcg::tri::PlanarEdgeFlip::PlanarEdgeFlip (const PlanarEdgeFlip &par)
 vcg::tri::PlanarEdgeFlip::PlanarEdgeFlip (PosType pos, int mark)
 vcg::tri::PlanarEdgeFlip::PlanarEdgeFlip ()
virtual ScalarType vcg::tri::PlanarEdgeFlip::Priority () const
virtual ScalarType vcg::tri::TriEdgeCollapse::Priority () const
 Return the priority to be used in the heap (implement static priority).
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler::Walker::ProcessSlice (EXTRACTOR_TYPE &extractor)
static void vcg::tri::Resampler::Resample (Old_Mesh &old_mesh, New_Mesh &new_mesh, Box3f 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 >
void vcg::tri::Sphere (MeshType &in, const int subdiv=3)
template<class MeshType >
void vcg::tri::Square (MeshType &in)
template<class TetraMeshType >
void vcg::tri::Tetrahedron (TetraMeshType &in)
 vcg::tri::TopoEdgeFlip::TopoEdgeFlip (const TopoEdgeFlip &par)
 vcg::tri::TopoEdgeFlip::TopoEdgeFlip (const PosType pos, int mark)
 vcg::tri::TopoEdgeFlip::TopoEdgeFlip ()
CoordType vcg::tri::Smooth::TriAreaGradient (CoordType &p, CoordType &p0, CoordType &p1)
 vcg::tri::TriEdgeCollapse::TriEdgeCollapse (const EdgeType &p, int mark)
 Constructor with postype.
 vcg::tri::TriEdgeCollapse::TriEdgeCollapse ()
 Default Constructor.
 vcg::tri::TriEdgeFlip::TriEdgeFlip (const TriEdgeFlip &par)
 vcg::tri::TriEdgeFlip::TriEdgeFlip (const PosType pos, int mark)
 vcg::tri::TriEdgeFlip::TriEdgeFlip ()
template<class MeshType >
void vcg::tri::UnMarkAll (MeshType &m)
 Unmark the mesh.
void vcg::tri::TopoEdgeFlip::UpdateHeap (HeapType &heap)
virtual void vcg::tri::PlanarEdgeFlip::UpdateHeap (HeapType &heap)
void vcg::tri::TriEdgeCollapse::UpdateHeap (HeapType &h_ret)
float vcg::tri::Resampler::Walker::V (int x, int y, int z)
float vcg::tri::Resampler::Walker::V (const Point3i &p)
static void vcg::tri::Smooth::VertexColorLaplacian (MeshType &m, int step, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth::VertexCoordLaplacian (MeshType &m, int step, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth::VertexCoordLaplacianAngleWeighted (MeshType &m, int step, ScalarType delta)
static void vcg::tri::Smooth::VertexCoordLaplacianBlend (MeshType &m, int step, float alpha, bool SmoothSelected=false)
void vcg::tri::Smooth::VertexCoordLaplacianCurvatureFlow (MeshType &m, int step, ScalarType delta)
static void vcg::tri::Smooth::VertexCoordLaplacianHC (MeshType &m, int step, bool SmoothSelected=false)
static void vcg::tri::Smooth::VertexCoordLaplacianQuality (MeshType &m, int step, bool SmoothSelected=false)
static void vcg::tri::Smooth::VertexCoordPasoDoble (MeshType &m, int step, typename MeshType::ScalarType Sigma=0, int FitStep=10, typename MeshType::ScalarType FitLambda=0.05)
static void vcg::tri::Smooth::VertexCoordPasoDobleFast (MeshType &m, int NormalSmoothStep, typename MeshType::ScalarType Sigma=0, int FitStep=50, bool SmoothSelected=false)
static void vcg::tri::Smooth::VertexCoordPlanarLaplacian (MeshType &m, int step, float AngleThrRad=math::ToRad(1.0), bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth::VertexCoordScaleDependentLaplacian_Fujiwara (MeshType &m, int step, ScalarType delta)
static void vcg::tri::Smooth::VertexCoordTaubin (MeshType &m, int step, float lambda, float mu, bool SmoothSelected=false, vcg::CallBackPos *cb=0)
static void vcg::tri::Smooth::VertexCoordViewDepth (MeshType &m, const CoordType &viewpoint, const ScalarType alpha, int step, bool SmoothBorder=false)
static void vcg::tri::Smooth::VertexNormalLaplacian (MeshType &m, int step, bool SmoothSelected=false)
static void vcg::tri::Smooth::VertexQualityLaplacian (MeshType &m, int step=1, bool SmoothSelected=false)
std::pair< bool, float > vcg::tri::Resampler::Walker::VV (int x, int y, int z)
 vcg::tri::Resampler::Walker::Walker (const Box3f &_bbox, Point3i _siz)
 vcg::tri::EdgeCollapse::~EdgeCollapse ()
 vcg::tri::PlanarEdgeFlip::~PlanarEdgeFlip ()
 vcg::tri::TriEdgeCollapse::~TriEdgeCollapse ()
 vcg::tri::Resampler::Walker::~Walker ()

Variables

GridType vcg::tri::Resampler::Walker::_g
int vcg::tri::PlanarEdgeFlip::_localMark
New_Mesh * vcg::tri::Resampler::Walker::_newM
Old_Mesh * vcg::tri::Resampler::Walker::_oldM
PosType vcg::tri::PlanarEdgeFlip::_pos
ScalarType vcg::tri::PlanarEdgeFlip::_priority
ScalarType vcg::tri::TriEdgeCollapse::_priority
 priority in the heap
field_value * vcg::tri::Resampler::Walker::_v_cs
field_value * vcg::tri::Resampler::Walker::_v_ns
VertexIndex * vcg::tri::Resampler::Walker::_x_cs
VertexIndex * vcg::tri::Resampler::Walker::_x_ns
VertexIndex * vcg::tri::Resampler::Walker::_y_cs
VertexIndex * vcg::tri::Resampler::Walker::_z_cs
VertexIndex * vcg::tri::Resampler::Walker::_z_ns
unsigned int vcg::tri::Smooth::ColorSmoothInfo::a
bool vcg::tri::Resampler::Walker::AbsDistFlag
unsigned int vcg::tri::Smooth::ColorSmoothInfo::b
int vcg::tri::Smooth::QualitySmoothInfo::cnt
int vcg::tri::Smooth::ColorSmoothInfo::cnt
int vcg::tri::Smooth::HCSmoothInfo::cnt
ScalarType vcg::tri::Smooth::LaplacianInfo::cnt
int vcg::tri::Resampler::Walker::CurrentSlice
bool vcg::tri::Resampler::Walker::DiscretizeFlag
unsigned int vcg::tri::Smooth::ColorSmoothInfo::g
ScalarType vcg::tri::Smooth::ScaleLaplacianInfo::LenSum
int vcg::tri::TriEdgeCollapse::localMark
 mark for up_dating
MarkerFace vcg::tri::Resampler::Walker::markerFunctor
float vcg::tri::Resampler::Walker::max_dim
TriMeshType * vcg::tri::TriEdgeCollapse::mt
bool vcg::tri::Resampler::Walker::MultiSampleFlag
float vcg::tri::Resampler::Walker::offset
EdgeType vcg::tri::TriEdgeCollapse::pos
 the pair to collapse
int vcg::tri::Resampler::Walker::SliceSize
CoordType vcg::tri::Smooth::HCSmoothInfo::sum
CoordType vcg::tri::Smooth::LaplacianInfo::sum

Detailed Description


Typedef Documentation

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

Definition at line 131 of file smooth.h.

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

Definition at line 123 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef FaceType::VertexType::CoordType vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::CoordType [inherited]
template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::CoordType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::CoordType [protected, inherited]

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

Definition at line 411 of file tri_edge_flip.h.

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

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

Definition at line 342 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>
typedef TRIMESH_TYPE::CoordType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::CoordType [protected, inherited]
template<class TriMeshType, class MYTYPE>
typedef FaceType::VertexType::CoordType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::CoordType [protected, inherited]
template<class TRI_MESH_TYPE>
typedef TriMeshType::FaceType::EdgeType vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::EdgeType [inherited]
template<class TriMeshType, class MYTYPE>
typedef VertexType::EdgeType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::EdgeType [protected, inherited]
template<class TRI_MESH_TYPE>
typedef std::vector<EdgeType> vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::EdgeVec [inherited]

vector of pos

Definition at line 85 of file trimesh/edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef Old_Mesh::FaceContainer vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::FaceCont [private, inherited]

Definition at line 63 of file resampler.h.

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

Definition at line 130 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef TriMeshType::FaceContainer vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::FaceContainer [inherited]

the container of tetrahedron type

Definition at line 79 of file trimesh/edge_collapse.h.

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

Definition at line 129 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef TriMeshType::FaceIterator vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::FaceIterator [inherited]

The tetra iterator type.

Definition at line 73 of file trimesh/edge_collapse.h.

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

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

Definition at line 417 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>
typedef TRIMESH_TYPE::FaceIterator vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FaceIterator [protected, inherited]

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

Definition at line 58 of file tri_edge_flip.h.

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

Definition at line 128 of file smooth.h.

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

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

Definition at line 409 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>
typedef TRIMESH_TYPE::FacePointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::FacePointer [protected, inherited]

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

Definition at line 57 of file tri_edge_flip.h.

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

Definition at line 127 of file smooth.h.

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

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

Definition at line 408 of file tri_edge_flip.h.

template<class TriMeshType, class MYTYPE>
typedef TriMeshType::FaceType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::FaceType [protected, inherited]
template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef std::pair<bool,float> vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::field_value [protected, inherited]

Definition at line 83 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef vcg::GridStaticPtr<typename Old_Mesh::FaceType> vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::GridType [private, inherited]

Reimplemented from vcg::BasicGrid< float >.

Definition at line 64 of file resampler.h.

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

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

Definition at line 414 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>
typedef LocalOptimization<TRIMESH_TYPE>::HeapElem vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapElem [protected, inherited]

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

Definition at line 64 of file tri_edge_flip.h.

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

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

Definition at line 415 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>
typedef LocalOptimization<TRIMESH_TYPE>::HeapType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::HeapType [protected, inherited]

Reimplemented from vcg::LocalModification< MeshType >.

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

Definition at line 65 of file tri_edge_flip.h.

template<class TriMeshType, class MYTYPE>
typedef LocalOptimization<TriMeshType>::HeapType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::HeapType [protected, inherited]
template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef tri::FaceTmark<Old_Mesh> vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::MarkerFace [protected, inherited]

Definition at line 70 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef vcg::tri::MarchingCubes<New_Mesh, MyWalker> vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::MyMarchingCubes [inherited]

Definition at line 605 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef Walker vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::MyWalker [inherited]

Definition at line 603 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef NEW_MESH_TYPE vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::New_Mesh [private, inherited]

Definition at line 60 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef NEW_MESH_TYPE vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::New_Mesh [private, inherited]

Definition at line 52 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef New_Mesh::CoordType vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::NewCoordType [private, inherited]

Definition at line 61 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef OLD_MESH_TYPE vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::Old_Mesh [private, inherited]

Definition at line 59 of file resampler.h.

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

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

Definition at line 412 of file tri_edge_flip.h.

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

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

Definition at line 343 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>
typedef vcg::face::Pos<FaceType> vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PosType [protected, inherited]
template<class SmoothMeshType >
typedef MeshType::ScalarType vcg::tri::Smooth< SmoothMeshType >::ScalarType [inherited]

Definition at line 126 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef TriMeshType::VertexType::ScalarType vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::ScalarType [inherited]
template<class TRIMESH_TYPE , class MYTYPE >
typedef TRIMESH_TYPE::ScalarType vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::ScalarType [protected, inherited]

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

Definition at line 410 of file tri_edge_flip.h.

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

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

Definition at line 341 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>
typedef TRIMESH_TYPE::ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ScalarType [protected, inherited]
template<class TriMeshType, class MYTYPE>
typedef TriMeshType::VertexType::ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::ScalarType [protected, inherited]
template<class TRI_MESH_TYPE>
typedef TriMeshType::VertContainer vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VertContainer [inherited]

the container of vertex type

Definition at line 81 of file trimesh/edge_collapse.h.

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

Definition at line 125 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef TriMeshType::VertexIterator vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VertexIterator [inherited]

The vertex iterator type.

Definition at line 71 of file trimesh/edge_collapse.h.

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

Definition at line 418 of file tri_edge_flip.h.

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

Definition at line 124 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef FaceType::VertexPointer vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VertexPointer [inherited]

Definition at line 69 of file trimesh/edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
typedef New_Mesh::VertexType* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::VertexPointer [private, inherited]

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 TRIMESH_TYPE::VertexPointer vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::VertexPointer [protected, inherited]

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

Definition at line 61 of file tri_edge_flip.h.

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

Definition at line 122 of file smooth.h.

template<class TRI_MESH_TYPE>
typedef FaceType::VertexType vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VertexType [inherited]
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, inherited]

Definition at line 59 of file tri_edge_flip.h.

template<class TriMeshType, class MYTYPE>
typedef TriMeshType::FaceType::VertexType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::VertexType [protected, inherited]
template<class TRI_MESH_TYPE>
typedef vcg::face::VFIterator<FaceType> vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VFI [inherited]

of VFIterator

Definition at line 87 of file trimesh/edge_collapse.h.

template<class TRI_MESH_TYPE>
typedef std::vector<vcg::face::VFIterator<FaceType> > vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::VFIVec [inherited]

vector of VFIterator

Definition at line 89 of file trimesh/edge_collapse.h.

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

Definition at line 132 of file smooth.h.


Function Documentation

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

Definition at line 281 of file smooth.h.

template<class TRI_MESH_TYPE>
static VFIVec& vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::AV0 (  )  [inline, static, inherited]

Definition at line 102 of file trimesh/edge_collapse.h.

template<class TRI_MESH_TYPE>
static VFIVec& vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::AV01 (  )  [inline, static, inherited]

Definition at line 104 of file trimesh/edge_collapse.h.

template<class TRI_MESH_TYPE>
static VFIVec& vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::AV1 (  )  [inline, static, inherited]

Definition at line 103 of file trimesh/edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::Begin (  )  [inline, inherited]

Definition at line 387 of file resampler.h.

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

Definition at line 96 of file tri_edge_collapse.h.

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

Definition at line 482 of file platonic.h.

template<class MeshType , class V , class F >
void vcg::tri::Build ( MeshType &  in,
const V &  v,
const F &  f 
) [inline]

Definition at line 535 of file platonic.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
template<class EXTRACTOR_TYPE >
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::BuildMesh ( Old_Mesh old_mesh,
New_Mesh new_mesh,
EXTRACTOR_TYPE &  extractor,
vcg::CallBackPos cb 
) [inline, inherited]

Definition at line 327 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::ComputeConsensus ( int  slice,
field_value slice_values 
) [inline, inherited]

Definition at line 257 of file resampler.h.

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

Compute the priority of this optimization

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

Definition at line 447 of file tri_edge_flip.h.

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

Compute the priority of this optimization

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

Definition at line 372 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>
virtual ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::ComputePriority (  )  [inline, virtual, inherited]
template<class TriMeshType, class MYTYPE>
ScalarType vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::ComputePriority (  )  [inline, virtual, inherited]
template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::ComputeSliceValues ( int  slice,
field_value slice_values 
) [inline, inherited]

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 238 of file resampler.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 
) [inline]

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

Definition at line 389 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>
static ScalarType& vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::CoplanarAngleThresholdDeg (  )  [inline, static, inherited]

Parameter

Definition at line 141 of file tri_edge_flip.h.

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

Definition at line 1147 of file smooth.h.

template<class MeshType >
void vcg::tri::Cylinder ( int  slices,
int  stacks,
MeshType &  m 
) [inline]

Definition at line 722 of file platonic.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
field_value vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::DistanceFromMesh ( Point3f pp,
Old_Mesh  
) [inline, inherited]

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

Definition at line 151 of file resampler.h.

template<class TRI_MESH_TYPE>
int vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::DoCollapse ( TriMeshType m,
EdgeType c,
const Point3< ScalarType > &  p 
) [inline, inherited]

Definition at line 301 of file trimesh/edge_collapse.h.

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

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

Definition at line 75 of file platonic.h.

template<class TRI_MESH_TYPE>
vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::EdgeCollapse (  )  [inline, inherited]

Default Constructor.

Definition at line 94 of file trimesh/edge_collapse.h.

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

Execute the flipping of the edge

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

Definition at line 488 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>
void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Execute ( TRIMESH_TYPE &  m  )  [inline, inherited]

Execute the flipping of the edge

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

Definition at line 258 of file tri_edge_flip.h.

template<class TriMeshType, class MYTYPE>
void vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::Execute ( TriMeshType m  )  [inline, inherited]
template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
bool vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::Exist ( const vcg::Point3i p1,
const vcg::Point3i p2,
VertexPointer v 
) [inline, inherited]

Definition at line 405 of file resampler.h.

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

Definition at line 650 of file smooth.h.

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

Definition at line 1170 of file smooth.h.

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

Definition at line 653 of file platonic.h.

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

Definition at line 613 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, inherited]

Definition at line 1066 of file smooth.h.

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

Definition at line 909 of file smooth.h.

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

Definition at line 1023 of file smooth.h.

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

Definition at line 964 of file smooth.h.

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

Definition at line 1210 of file smooth.h.

template<class TRI_MESH_TYPE>
void vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::FindSets ( EdgeType p  )  [inline, inherited]

Definition at line 107 of file trimesh/edge_collapse.h.

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

Definition at line 1180 of file smooth.h.

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

Definition at line 781 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 (  )  [inline, inherited]

Definition at line 152 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 (  )  [inline, inherited]

Definition at line 147 of file tri_edge_flip.h.

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

Definition at line 361 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::GetXIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
VertexPointer v 
) [inline, inherited]

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

Definition at line 498 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::GetYIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
VertexPointer v 
) [inline, inherited]

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

Definition at line 537 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::GetZIntercept ( const vcg::Point3i p1,
const vcg::Point3i p2,
VertexPointer v 
) [inline, inherited]

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

Definition at line 560 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>
static int& vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::GlobalMark (  )  [inline, static, protected, inherited]

mark for up_dating

Definition at line 85 of file tri_edge_flip.h.

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

mark for up_dating

Definition at line 121 of file tri_edge_collapse.h.

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

Definition at line 588 of file platonic.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEEAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 572 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEFAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 575 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEHAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 578 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasEVAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 569 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFEAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 557 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFFAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 554 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFHAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 581 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasFVAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 560 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHEAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 587 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHFAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 590 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHNextAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 593 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHOppAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 599 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHPrevAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 596 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasHVAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 584 of file complex/trimesh/base.h.

template<class MESH_TYPE >
bool vcg::tri::HasPerFaceAttribute ( const MESH_TYPE &  m,
std::string  name 
) [inline]

Definition at line 625 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceColor ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceFlags ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceMark ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceNormal ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceQuality ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerFaceVFAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class MESH_TYPE >
bool vcg::tri::HasPerMeshAttribute ( const MESH_TYPE &  m,
std::string  name 
) [inline]

Definition at line 634 of file complex/trimesh/base.h.

template<class MESH_TYPE >
bool vcg::tri::HasPerVertexAttribute ( const MESH_TYPE &  m,
std::string  name 
) [inline]

Definition at line 617 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexColor ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexCurvature ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexCurvatureDir ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 509 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexFlags ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexMark ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexNormal ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 521 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexQuality ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexRadius ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexTexCoord ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 515 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerVertexVFAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeColor ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 533 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeNormal ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 530 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasPerWedgeTexCoord ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

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

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasVEAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 563 of file complex/trimesh/base.h.

template<class ContainerType0 , class ContainerType1 , class ContainerType2 , class ContainerType3 >
bool vcg::tri::HasVHAdjacency ( const TriMesh< ContainerType0, ContainerType1, ContainerType2, ContainerType3 > &   )  [inline]

Definition at line 566 of file complex/trimesh/base.h.

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

Definition at line 273 of file platonic.h.

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

Definition at line 216 of file platonic.h.

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

Access function to the incremental mark.

Definition at line 473 of file complex/trimesh/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>
const char* vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Info ( TRIMESH_TYPE &  m  )  [inline, inherited]

Definition at line 276 of file tri_edge_flip.h.

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

Definition at line 156 of file tri_edge_collapse.h.

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

Definition at line 512 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>
static void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Init ( TRIMESH_TYPE &  mesh,
HeapType heap 
) [inline, static, inherited]

Definition at line 285 of file tri_edge_flip.h.

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

Definition at line 97 of file tri_edge_collapse.h.

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

Initialize the imark-system of the faces.

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

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

Initialize the imark-system of the vertices.

Definition at line 463 of file complex/trimesh/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 
) [inline, static, protected, inherited]

Definition at line 91 of file tri_edge_flip.h.

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

interpolate

Definition at line 487 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>
virtual bool vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::IsFeasible (  )  [inline, virtual, inherited]

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

Implements vcg::LocalModification< MeshType >.

Definition at line 184 of file tri_edge_flip.h.

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

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, MYTYPE, HelperType >, and vcg::tri::TriEdgeCollapseQuadric< MyMesh, MyTriEdgeCollapse, QInfoStandard< MyVertex > >.

Definition at line 237 of file tri_edge_collapse.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:
v Face pointer

Definition at line 482 of file complex/trimesh/base.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:
v Vertex pointer

Definition at line 478 of file complex/trimesh/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, inherited]

Return the LocalOptimization type

Implements vcg::LocalModification< MeshType >.

Definition at line 161 of file tri_edge_flip.h.

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

return the type of operation

Implements vcg::LocalModification< MeshType >.

Definition at line 235 of file tri_edge_collapse.h.

template<class TriMeshType, class MYTYPE>
static bool vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::IsSymmetric (  )  [inline, static, inherited]
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 (  )  [inline, virtual, inherited]

Check if the pos is updated

Implements vcg::LocalModification< MeshType >.

Definition at line 170 of file tri_edge_flip.h.

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

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

Implements vcg::LocalModification< MeshType >.

Definition at line 241 of file tri_edge_collapse.h.

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

Definition at line 265 of file smooth.h.

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

Definition at line 93 of file tri_edge_collapse.h.

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

Definition at line 92 of file tri_edge_collapse.h.

template<class TRI_MESH_TYPE>
bool vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::LinkConditions ( EdgeType  pos  )  [inline, inherited]

Definition at line 166 of file trimesh/edge_collapse.h.

template<class TRI_MESH_TYPE>
bool vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::LinkConditionsOld ( EdgeType  pos  )  [inline, inherited]

Definition at line 245 of file trimesh/edge_collapse.h.

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

Definition at line 94 of file tri_edge_collapse.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:
v Vertex pointer

Definition at line 490 of file complex/trimesh/base.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:
v Vertex pointer

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

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
field_value vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::MultiDistanceFromMesh ( Point3f pp,
Old_Mesh  
) [inline, inherited]

Definition at line 211 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::NextSlice (  )  [inline, inherited]

Definition at line 368 of file resampler.h.

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

Definition at line 182 of file platonic.h.

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

Definition at line 95 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>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::PlanarEdgeFlip ( const PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc > &  par  )  [inline, inherited]

Copy Constructor

Definition at line 123 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 
) [inline, inherited]

Constructor with pos type

Definition at line 112 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 (  )  [inline, inherited]

Default constructor

Definition at line 104 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>
virtual ScalarType vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::Priority (  )  const [inline, virtual, inherited]

Return the priority of this optimization

Implements vcg::LocalModification< MeshType >.

Definition at line 250 of file tri_edge_flip.h.

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

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

Implements vcg::LocalModification< MeshType >.

Definition at line 268 of file tri_edge_collapse.h.

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

Definition at line 306 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
static void vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Resample ( Old_Mesh old_mesh,
New_Mesh new_mesh,
Box3f  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, inherited]

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 608 of file resampler.h.

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

Definition at line 358 of file platonic.h.

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

Definition at line 322 of file platonic.h.

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

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 45 of file platonic.h.

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

Copy Constructor

Definition at line 439 of file tri_edge_flip.h.

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

Constructor with pos type

Definition at line 429 of file tri_edge_flip.h.

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

Default constructor

Definition at line 424 of file tri_edge_flip.h.

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

Definition at line 1126 of file smooth.h.

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

Constructor with postype.

Definition at line 134 of file tri_edge_collapse.h.

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

Default Constructor.

Definition at line 131 of file tri_edge_collapse.h.

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

Copy Constructor

Definition at line 364 of file tri_edge_flip.h.

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

Constructor with pos type

Definition at line 354 of file tri_edge_flip.h.

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

Default constructor

Definition at line 349 of file tri_edge_flip.h.

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

Unmark the mesh.

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

template<class TRIMESH_TYPE , class MYTYPE >
void vcg::tri::TopoEdgeFlip< TRIMESH_TYPE, MYTYPE >::UpdateHeap ( HeapType heap  )  [inline, inherited]

Definition at line 531 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>
virtual void vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::UpdateHeap ( HeapType heap  )  [inline, virtual, inherited]

Definition at line 306 of file tri_edge_flip.h.

template<class TriMeshType, class MYTYPE>
void vcg::tri::TriEdgeCollapse< TriMeshType, MYTYPE >::UpdateHeap ( HeapType h_ret  )  [inline, inherited]
template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
float vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::V ( int  x,
int  y,
int  z 
) [inline, inherited]

Definition at line 145 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
float vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::V ( const Point3i p  )  [inline, inherited]

Definition at line 125 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, inherited]

Definition at line 575 of file smooth.h.

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

Definition at line 325 of file smooth.h.

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

Definition at line 152 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, inherited]

Definition at line 396 of file smooth.h.

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

Definition at line 144 of file smooth.h.

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

Definition at line 503 of file smooth.h.

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

Definition at line 471 of file smooth.h.

template<class SmoothMeshType >
static void vcg::tri::Smooth< SmoothMeshType >::VertexCoordPasoDoble ( MeshType m,
int  step,
typename MeshType::ScalarType  Sigma = 0,
int  FitStep = 10,
typename MeshType::ScalarType  FitLambda = 0.05 
) [inline, static, inherited]

Definition at line 1247 of file smooth.h.

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

Definition at line 1276 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, inherited]

Definition at line 345 of file smooth.h.

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

Definition at line 200 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, inherited]

Definition at line 437 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, inherited]

Definition at line 813 of file smooth.h.

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

Definition at line 755 of file smooth.h.

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

Definition at line 698 of file smooth.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
std::pair<bool,float> vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::VV ( int  x,
int  y,
int  z 
) [inline, inherited]

Definition at line 131 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::Walker ( const Box3f _bbox,
Point3i  _siz 
) [inline, inherited]

Definition at line 97 of file resampler.h.

template<class TRI_MESH_TYPE>
vcg::tri::EdgeCollapse< TRI_MESH_TYPE >::~EdgeCollapse (  )  [inline, inherited]

Definition at line 98 of file trimesh/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>
vcg::tri::PlanarEdgeFlip< TRIMESH_TYPE, MYTYPE, QualityFunc >::~PlanarEdgeFlip (  )  [inline, inherited]

Definition at line 133 of file tri_edge_flip.h.

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

Definition at line 141 of file tri_edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::~Walker (  )  [inline, inherited]

Definition at line 121 of file resampler.h.


Variable Documentation

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
GridType vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_g [protected, inherited]

Definition at line 89 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, inherited]

Mark for updating

Definition at line 80 of file tri_edge_flip.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
New_Mesh* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_newM [protected, inherited]

Definition at line 87 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
Old_Mesh* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_oldM [protected, inherited]

Definition at line 88 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, inherited]

the pos of the flipping

Definition at line 70 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, inherited]

priority in the heap

Definition at line 75 of file tri_edge_flip.h.

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

priority in the heap

Definition at line 127 of file tri_edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
field_value* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_v_cs [protected, inherited]

Definition at line 84 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
field_value* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_v_ns [protected, inherited]

Definition at line 85 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
VertexIndex* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_x_cs [protected, inherited]

Definition at line 74 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
VertexIndex* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_x_ns [protected, inherited]

Definition at line 77 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
VertexIndex* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_y_cs [protected, inherited]

Definition at line 75 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
VertexIndex* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_z_cs [protected, inherited]

Definition at line 76 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
VertexIndex* vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::_z_ns [protected, inherited]

Definition at line 78 of file resampler.h.

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

Definition at line 571 of file smooth.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
bool vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::AbsDistFlag [inherited]

Definition at line 96 of file resampler.h.

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

Definition at line 570 of file smooth.h.

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

Definition at line 694 of file smooth.h.

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

Definition at line 572 of file smooth.h.

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

Definition at line 500 of file smooth.h.

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

Definition at line 267 of file smooth.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
int vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::CurrentSlice [protected, inherited]

Definition at line 69 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
bool vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::DiscretizeFlag [inherited]

Definition at line 94 of file resampler.h.

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

Definition at line 569 of file smooth.h.

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

Definition at line 138 of file smooth.h.

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

mark for up_dating

Definition at line 124 of file tri_edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
MarkerFace vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::markerFunctor [protected, inherited]

Definition at line 71 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
float vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::max_dim [inherited]

Definition at line 92 of file resampler.h.

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

Definition at line 116 of file tri_edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
bool vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::MultiSampleFlag [inherited]

Definition at line 95 of file resampler.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
float vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::offset [inherited]

Definition at line 93 of file resampler.h.

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

the pair to collapse

Definition at line 118 of file tri_edge_collapse.h.

template<class OLD_MESH_TYPE , class NEW_MESH_TYPE , class FLT , class DISTFUNCTOR = vcg::face::PointDistanceBaseFunctor<typename OLD_MESH_TYPE::ScalarType >>
int vcg::tri::Resampler< OLD_MESH_TYPE, NEW_MESH_TYPE, FLT, DISTFUNCTOR >::Walker::SliceSize [protected, inherited]

Definition at line 68 of file resampler.h.

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

Definition at line 499 of file smooth.h.

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

Definition at line 266 of file smooth.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


vcglib
Author(s): Christian Bersch
autogenerated on Fri Jan 11 09:21:30 2013