Classes | Public Types | Static Public Member Functions | Private Types | Static Private Member Functions
vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor > Class Template Reference

#include <voronoi_processing.h>

List of all members.

Classes

struct  QuadricSumDistance
class  VoronoiEdge

Public Types

typedef MeshType::template
PerFaceAttributeHandle
< VertexPointer
PerFacePointerHandle
typedef MeshType::template
PerVertexAttributeHandle< bool > 
PerVertexBoolHandle
typedef MeshType::template
PerVertexAttributeHandle
< float > 
PerVertexFloatHandle
typedef MeshType::template
PerVertexAttributeHandle
< VertexPointer
PerVertexPointerHandle

Static Public Member Functions

static void BuildBiasedSeedVec (MeshType &m, DistanceFunctor &df, std::vector< VertexPointer > &seedVec, std::vector< VertexPointer > &frontierVec, std::vector< VertDist > &biasedFrontierVec, VoronoiProcessingParameter &vpp)
static void BuildSeedMap (MeshType &m, std::vector< VertexType * > &seedVec, std::map< VertexPointer, int > &seedMap)
static void BuildVoronoiEdgeVec (MeshType &m, std::vector< VoronoiEdge > &edgeVec)
static bool CheckVoronoiTopology (MeshType &m, std::vector< VertexType * > &seedVec)
 Check the topological correcteness of the induced Voronoi diagram.
static VertexPointer CommonSourceBetweenBorderCorner (FacePointer f0, FacePointer f1, typename MeshType::template PerVertexAttributeHandle< VertexPointer > &sources)
static void ComputePerVertexSources (MeshType &m, std::vector< VertexType * > &seedVec, DistanceFunctor &df)
static void ConvertDelaunayTriangulationToMesh (MeshType &m, MeshType &outMesh, std::vector< VertexType * > &seedVec, bool refineFlag=true)
 Build a mesh of the Delaunay triangulation induced by the given seeds.
static void ConvertVoronoiDiagramToMesh (MeshType &m, MeshType &outMesh, MeshType &outPoly, std::vector< VertexType * > &seedVec, VoronoiProcessingParameter &vpp)
static void ConvertVoronoiDiagramToMeshOld (MeshType &m, MeshType &outMesh, MeshType &outPoly, std::vector< VertexType * > &seedVec, VoronoiProcessingParameter &vpp)
 Build a mesh of voronoi diagram from the given seeds.
static void DeleteUnreachedRegions (MeshType &m, PerVertexPointerHandle &sources)
static void FaceAssociateRegion (MeshType &m)
static int FaceSelectAssociateRegion (MeshType &m, VertexPointer vp)
static int FaceSelectRegion (MeshType &m, VertexPointer vp)
static void FixVertexVector (MeshType &m, std::vector< VertexType * > &vertToFixVec)
 Mark a vector of seeds to be fixed.
static void GenerateMidPointMap (MeshType &m, map< std::pair< VertexPointer, VertexPointer >, VertexPointer > &midMap)
static bool GeodesicRelax (MeshType &m, std::vector< VertexType * > &seedVec, std::vector< VertexPointer > &frontierVec, std::vector< VertexType * > &newSeeds, DistanceFunctor &df, VoronoiProcessingParameter &vpp)
 Relax the Seeds of a Voronoi diagram according to the geodesic rule.
static void GetAreaAndFrontier (MeshType &m, PerVertexPointerHandle &sources, std::vector< std::pair< float, VertexPointer > > &regionArea, std::vector< VertexPointer > &frontierVec)
static void GetFaceCornerVec (MeshType &m, PerVertexPointerHandle &sources, std::vector< FacePointer > &cornerVec, std::vector< FacePointer > &borderCornerVec)
static bool isBorderCorner (FaceType *f, typename MeshType::template PerVertexAttributeHandle< VertexPointer > &sources)
template<class genericType >
static std::pair< genericType,
genericType > 
ordered_pair (const genericType &a, const genericType &b)
template<class MidPointType >
static void PreprocessForVoronoi (MeshType &m, ScalarType radius, MidPointType mid, VoronoiProcessingParameter &vpp)
static void PreprocessForVoronoi (MeshType &m, float radius, VoronoiProcessingParameter &vpp)
static void PruneSeedByRegionArea (std::vector< VertexType * > &seedVec, std::vector< std::pair< float, VertexPointer > > &regionArea, VoronoiProcessingParameter &vpp)
static bool QuadricRelax (MeshType &m, std::vector< VertexType * > &seedVec, std::vector< VertexPointer > &frontierVec, std::vector< VertexType * > &newSeeds, DistanceFunctor &df, VoronoiProcessingParameter &vpp)
 Relax the seeds of a Voronoi diagram according to the quadric distance rule.
static void RelaxRefineTriangulationLaplacian (MeshType &m, MeshType &delaMesh, int refineStep=3, int relaxStep=10)
static void RelaxRefineTriangulationSpring (MeshType &m, MeshType &delaMesh, int relaxStep=10, int refineStep=3)
static int RestrictedVoronoiRelaxing (MeshType &m, std::vector< CoordType > &seedPosVec, std::vector< bool > &fixedVec, int relaxStep, VoronoiProcessingParameter &vpp, vcg::CallBackPos *cb=0)
static void SeedToVertexConversion (MeshType &m, std::vector< CoordType > &seedPVec, std::vector< VertexType * > &seedVVec, bool compactFlag=true)
static void TopologicalVertexColoring (MeshType &m, std::vector< VertexType * > &seedVec)
static void VoronoiAreaColoring (MeshType &m, std::vector< VertexType * > &seedVec, std::vector< std::pair< float, VertexPointer > > &regionArea)
static void VoronoiColoring (MeshType &m, bool frontierFlag=true)
static int VoronoiRelaxing (MeshType &m, std::vector< VertexType * > &seedVec, int relaxIter, DistanceFunctor &df, VoronoiProcessingParameter &vpp, vcg::CallBackPos *cb=0)
 Perform a Lloyd relaxation cycle over a mesh It uses two conventions: 1) a few vertexes can remain fixed, you have to set a per vertex bool attribute named 'fixed' 2)

Private Types

typedef MeshType::CoordType CoordType
typedef MeshType::FaceContainer FaceContainer
typedef MeshType::FaceIterator FaceIterator
typedef MeshType::FacePointer FacePointer
typedef MeshType::FaceType FaceType
typedef MeshType::ScalarType ScalarType
typedef tri::Geodesic
< MeshType >::VertDist 
VertDist
typedef MeshType::VertexIterator VertexIterator
typedef MeshType::VertexPointer VertexPointer
typedef MeshType::VertexType VertexType

Static Private Member Functions

static math::MarsenneTwisterRNGRandomGenerator ()

Detailed Description

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
class vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >

Definition at line 104 of file voronoi_processing.h.


Member Typedef Documentation

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::CoordType vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::CoordType [private]

Definition at line 106 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::FaceContainer vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceContainer [private]

Definition at line 114 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::FaceIterator vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceIterator [private]

Definition at line 112 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::FacePointer vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FacePointer [private]

Definition at line 111 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::FaceType vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceType [private]

Definition at line 113 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::template PerFaceAttributeHandle<VertexPointer> vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PerFacePointerHandle

Definition at line 128 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::template PerVertexAttributeHandle<bool> vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PerVertexBoolHandle

Definition at line 126 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::template PerVertexAttributeHandle<float> vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PerVertexFloatHandle

Definition at line 127 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::template PerVertexAttributeHandle<VertexPointer> vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PerVertexPointerHandle

Definition at line 125 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::ScalarType vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ScalarType [private]

Definition at line 107 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef tri::Geodesic<MeshType>::VertDist vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VertDist [private]

Definition at line 115 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::VertexIterator vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VertexIterator [private]

Definition at line 110 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::VertexPointer vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VertexPointer [private]

Definition at line 109 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
typedef MeshType::VertexType vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VertexType [private]

Definition at line 108 of file voronoi_processing.h.


Member Function Documentation

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::BuildBiasedSeedVec ( MeshType &  m,
DistanceFunctor &  df,
std::vector< VertexPointer > &  seedVec,
std::vector< VertexPointer > &  frontierVec,
std::vector< VertDist > &  biasedFrontierVec,
VoronoiProcessingParameter vpp 
) [inline, static]

Definition at line 889 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::BuildSeedMap ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
std::map< VertexPointer, int > &  seedMap 
) [inline, static]

Definition at line 1573 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::BuildVoronoiEdgeVec ( MeshType &  m,
std::vector< VoronoiEdge > &  edgeVec 
) [inline, static]

Definition at line 832 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static bool vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::CheckVoronoiTopology ( MeshType &  m,
std::vector< VertexType * > &  seedVec 
) [inline, static]

Check the topological correcteness of the induced Voronoi diagram.

This function assumes that you have just run a geodesic like algorithm over your mesh using a seed set as starting points and that there is an PerVertex Attribute called 'sources' with pointers to the seed source. Usually you can initialize it with something like

DistanceFunctor &df, tri::Geodesic<MeshType>::Compute(m, seedVec, df, std::numeric_limits<ScalarType>::max(),0,&sources);

Definition at line 1485 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static VertexPointer vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::CommonSourceBetweenBorderCorner ( FacePointer  f0,
FacePointer  f1,
typename MeshType::template PerVertexAttributeHandle< VertexPointer > &  sources 
) [inline, static]

Definition at line 403 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ComputePerVertexSources ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
DistanceFunctor &  df 
) [inline, static]

Definition at line 163 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ConvertDelaunayTriangulationToMesh ( MeshType &  m,
MeshType &  outMesh,
std::vector< VertexType * > &  seedVec,
bool  refineFlag = true 
) [inline, static]

Build a mesh of the Delaunay triangulation induced by the given seeds.

This function assumes that you have just run a geodesic like algorithm over your mesh using a seed set as starting points and that there is an PerVertex Attribute called 'sources' with pointers to the seed source. Usually you can initialize it with something like

DistanceFunctor &df, tri::Geodesic<MeshType>::Compute(m, seedVec, df, std::numeric_limits<ScalarType>::max(),0,&sources);

The function can also

Definition at line 1594 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ConvertVoronoiDiagramToMesh ( MeshType &  m,
MeshType &  outMesh,
MeshType &  outPoly,
std::vector< VertexType * > &  seedVec,
VoronoiProcessingParameter vpp 
) [inline, static]

Definition at line 426 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ConvertVoronoiDiagramToMeshOld ( MeshType &  m,
MeshType &  outMesh,
MeshType &  outPoly,
std::vector< VertexType * > &  seedVec,
VoronoiProcessingParameter vpp 
) [inline, static]

Build a mesh of voronoi diagram from the given seeds.

This function assumes that you have just run a geodesic like algorithm over your mesh using a seed set as starting points and that there is an PerVertex Attribute called 'sources' with pointers to the seed source. Usually you can initialize it with something like

DistanceFunctor &df, tri::Geodesic<MeshType>::Compute(m, seedVec, df, std::numeric_limits<ScalarType>::max(),0,&sources);

Definition at line 567 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::DeleteUnreachedRegions ( MeshType &  m,
PerVertexPointerHandle sources 
) [inline, static]

Definition at line 974 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceAssociateRegion ( MeshType &  m) [inline, static]

Definition at line 223 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static int vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceSelectAssociateRegion ( MeshType &  m,
VertexPointer  vp 
) [inline, static]

Definition at line 273 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static int vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FaceSelectRegion ( MeshType &  m,
VertexPointer  vp 
) [inline, static]

Definition at line 295 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::FixVertexVector ( MeshType &  m,
std::vector< VertexType * > &  vertToFixVec 
) [inline, static]

Mark a vector of seeds to be fixed.

Vertex pointers must belong to the mesh. The framework use a boolean attribute called "fixed" to store this info.

Definition at line 1198 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::GenerateMidPointMap ( MeshType &  m,
map< std::pair< VertexPointer, VertexPointer >, VertexPointer > &  midMap 
) [inline, static]

For each edge of the delaunay triangulation it search a 'good' middle point: E.g the point that belongs on the corresponding edge of the voronoi diagram (e.g. on a frontier face) and that has minimal distance from the two seeds.

Note: if the edge connects two "constrained" vertices (e.g. selected) we must search only among the constrained.

Definition at line 1423 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static bool vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::GeodesicRelax ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
std::vector< VertexPointer > &  frontierVec,
std::vector< VertexType * > &  newSeeds,
DistanceFunctor &  df,
VoronoiProcessingParameter vpp 
) [inline, static]

Relax the Seeds of a Voronoi diagram according to the geodesic rule.

For each region, given the frontiers, it chooses the point with the highest distance from the frontier This strategy automatically moves the vertices onto the boundary (if any).

It return true if at least one seed changed position.

Definition at line 1116 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::GetAreaAndFrontier ( MeshType &  m,
PerVertexPointerHandle sources,
std::vector< std::pair< float, VertexPointer > > &  regionArea,
std::vector< VertexPointer > &  frontierVec 
) [inline, static]

Given a mesh with for each vertex the link to the closest seed (e.g. for all vertexes we know what is the corresponding voronoi region) we compute: area of all the voronoi regions the vector of the frontier vertexes (e.g. vert of faces shared by at least two regions)

Area is computed only for triangles that fully belong to a given source.

Definition at line 330 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::GetFaceCornerVec ( MeshType &  m,
PerVertexPointerHandle sources,
std::vector< FacePointer > &  cornerVec,
std::vector< FacePointer > &  borderCornerVec 
) [inline, static]

Given a mesh with for each vertex the link to the closest seed we compute: the vector of the corner faces (ie the faces shared exactly by three regions) the vector of the frontier faces that are on the boundary.

Definition at line 369 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static bool vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::isBorderCorner ( FaceType f,
typename MeshType::template PerVertexAttributeHandle< VertexPointer > &  sources 
) [inline, static]

Definition at line 392 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
template<class genericType >
static std::pair<genericType, genericType> vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::ordered_pair ( const genericType &  a,
const genericType &  b 
) [inline, static]

Definition at line 1410 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
template<class MidPointType >
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PreprocessForVoronoi ( MeshType &  m,
ScalarType  radius,
MidPointType  mid,
VoronoiProcessingParameter vpp 
) [inline, static]

Definition at line 1663 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PreprocessForVoronoi ( MeshType &  m,
float  radius,
VoronoiProcessingParameter vpp 
) [inline, static]

Definition at line 1682 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::PruneSeedByRegionArea ( std::vector< VertexType * > &  seedVec,
std::vector< std::pair< float, VertexPointer > > &  regionArea,
VoronoiProcessingParameter vpp 
) [inline, static]

Definition at line 1172 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static bool vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::QuadricRelax ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
std::vector< VertexPointer > &  frontierVec,
std::vector< VertexType * > &  newSeeds,
DistanceFunctor &  df,
VoronoiProcessingParameter vpp 
) [inline, static]

Relax the seeds of a Voronoi diagram according to the quadric distance rule.

For each region it search the vertex that minimize the sum of the squared distance from all the points of the region.

It uses a vector of QuadricSumDistances; for simplicity it is sized as the vertex vector even if only the ones of the quadric corresponding to seeds are actually used.

It return true if at least one seed changed position.

Definition at line 1036 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static math::MarsenneTwisterRNG& vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::RandomGenerator ( ) [inline, static, private]

Definition at line 117 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::RelaxRefineTriangulationLaplacian ( MeshType &  m,
MeshType &  delaMesh,
int  refineStep = 3,
int  relaxStep = 10 
) [inline, static]

Definition at line 1769 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::RelaxRefineTriangulationSpring ( MeshType &  m,
MeshType &  delaMesh,
int  relaxStep = 10,
int  refineStep = 3 
) [inline, static]

Definition at line 1688 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static int vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::RestrictedVoronoiRelaxing ( MeshType &  m,
std::vector< CoordType > &  seedPosVec,
std::vector< bool > &  fixedVec,
int  relaxStep,
VoronoiProcessingParameter vpp,
vcg::CallBackPos cb = 0 
) [inline, static]

Definition at line 1209 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::SeedToVertexConversion ( MeshType &  m,
std::vector< CoordType > &  seedPVec,
std::vector< VertexType * > &  seedVVec,
bool  compactFlag = true 
) [inline, static]

Definition at line 133 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::TopologicalVertexColoring ( MeshType &  m,
std::vector< VertexType * > &  seedVec 
) [inline, static]

Definition at line 1377 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VoronoiAreaColoring ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
std::vector< std::pair< float, VertexPointer > > &  regionArea 
) [inline, static]

Definition at line 209 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static void vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VoronoiColoring ( MeshType &  m,
bool  frontierFlag = true 
) [inline, static]

Definition at line 176 of file voronoi_processing.h.

template<class MeshType, class DistanceFunctor = EuclideanDistance<MeshType>>
static int vcg::tri::VoronoiProcessing< MeshType, DistanceFunctor >::VoronoiRelaxing ( MeshType &  m,
std::vector< VertexType * > &  seedVec,
int  relaxIter,
DistanceFunctor &  df,
VoronoiProcessingParameter vpp,
vcg::CallBackPos cb = 0 
) [inline, static]

Perform a Lloyd relaxation cycle over a mesh It uses two conventions: 1) a few vertexes can remain fixed, you have to set a per vertex bool attribute named 'fixed' 2)

Definition at line 1282 of file voronoi_processing.h.


The documentation for this class was generated from the following file:


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