Main Class of the Sampling framework. More...
#include <point_sampling.h>
Classes | |
struct | PoissonDiskParam |
class | RRParam |
Public Types | |
typedef GridStaticPtr < FaceType, ScalarType > | TriMeshGrid |
Static Public Member Functions | |
static void | AllEdge (MeshType &m, VertexSampler &ps) |
static void | AllFace (MeshType &m, VertexSampler &ps) |
static void | AllVertex (MeshType &m, VertexSampler &ps) |
static void | AllVertex (MeshType &m, VertexSampler &ps, bool onlySelected) |
static bool | checkPoissonDisk (SampleSHT &sht, const Point3< ScalarType > &p, ScalarType radius) |
static ScalarType | ComputePoissonDiskRadius (MeshType &origMesh, int sampleNum) |
Estimate the radius r that you should give to get a certain number of samples in a Poissson Disk Distribution of radius r. | |
static int | ComputePoissonSampleNum (MeshType &origMesh, ScalarType diskRadius) |
static void | EdgeMeshUniform (MeshType &m, VertexSampler &ps, float radius, bool conservative=true) |
static void | EdgeMontecarlo (MeshType &m, VertexSampler &ps, int sampleNum, bool sampleAllEdges) |
static void | EdgeUniform (MeshType &m, VertexSampler &ps, int sampleNum, bool sampleFauxEdge=true) |
static void | FaceSimilar (MeshType &m, VertexSampler &ps, int sampleNum, bool dualFlag, bool randomFlag) |
static void | FaceSubdivision (MeshType &m, VertexSampler &ps, int sampleNum, bool randSample) |
Compute a sampling of the surface where the points are regularly scattered over the face surface using a recursive longest-edge subdivision rule. | |
static void | FaceSubdivisionOld (MeshType &m, VertexSampler &ps, int sampleNum, bool randSample) |
Compute a sampling of the surface where the points are regularly scattered over the face surface using a recursive longest-edge subdivision rule. | |
static void | FaceUniform (MeshType &m, VertexSampler &ps, int sampleNum) |
static void | FillAndShuffleFacePointerVector (MeshType &m, std::vector< FacePointer > &faceVec) |
static void | FillAndShuffleVertexPointerVector (MeshType &m, std::vector< VertexPointer > &vertVec) |
static VertexPointer | getBestPrecomputedMontecarloSample (Point3i &cell, MontecarloSHT &samplepool, ScalarType diskRadius, const PoissonDiskParam &pp) |
static VertexPointer | getSampleFromCell (Point3i &cell, MontecarloSHT &samplepool) |
static void | HierarchicalPoissonDisk (MeshType &origMesh, VertexSampler &ps, MeshType &montecarloMesh, ScalarType diskRadius, const struct PoissonDiskParam pp=PoissonDiskParam()) |
static void | InitRadiusHandleFromQuality (MeshType &sampleMesh, PerVertexFloatAttribute &rH, ScalarType diskRadius, ScalarType radiusVariance, bool invert) |
static void | InitSpatialHashTable (MeshType &montecarloMesh, MontecarloSHT &montecarloSHT, ScalarType diskRadius, struct PoissonDiskParam pp=PoissonDiskParam()) |
static double | LnFac (int n) |
static void | Montecarlo (MeshType &m, VertexSampler &ps, int sampleNum) |
static void | MontecarloPoisson (MeshType &m, VertexSampler &ps, int sampleNum) |
static int | Poisson (double lambda) |
static void | PoissonDiskPruning (VertexSampler &ps, MeshType &montecarloMesh, ScalarType diskRadius, PoissonDiskParam &pp) |
static void | PoissonDiskPruningByNumber (VertexSampler &ps, MeshType &m, size_t sampleNum, ScalarType &diskRadius, PoissonDiskParam &pp, float tolerance=0.04, int maxIter=20) |
static int | PoissonRatioUniforms (double L) |
static CoordType | RandomBarycentric () |
static double | RandomDouble01 () |
static unsigned int | RandomInt (unsigned int i) |
static CoordType | RandomPointInTriangle (const FaceType &f) |
static void | RegularRecursiveOffset (MeshType &m, std::vector< CoordType > &pvec, ScalarType offset, float minDiag) |
static math::MarsenneTwisterRNG & | SamplingRandomGenerator () |
static void | SingleFaceRaster (typename MeshType::FaceType &f, VertexSampler &ps, const Point2< typename MeshType::ScalarType > &v0, const Point2< typename MeshType::ScalarType > &v1, const Point2< typename MeshType::ScalarType > &v2, bool correctSafePointsBaryCoords=true) |
static int | SingleFaceSimilar (FacePointer fp, VertexSampler &ps, int n_samples_per_edge) |
static int | SingleFaceSimilarDual (FacePointer fp, VertexSampler &ps, int n_samples_per_edge, bool randomFlag) |
static int | SingleFaceSubdivision (int sampleNum, const CoordType &v0, const CoordType &v1, const CoordType &v2, VertexSampler &ps, FacePointer fp, bool randSample) |
static int | SingleFaceSubdivisionOld (int sampleNum, const CoordType &v0, const CoordType &v1, const CoordType &v2, VertexSampler &ps, FacePointer fp, bool randSample) |
static void | StratifiedMontecarlo (MeshType &m, VertexSampler &ps, int sampleNum) |
static void | SubdivideAndSample (MeshType &m, std::vector< CoordType > &pvec, const Box3< ScalarType > bb, RRParam &rrp, float curDiag) |
static void | Texture (MeshType &m, VertexSampler &ps, int textureWidth, int textureHeight, bool correctSafePointsBaryCoords=true) |
static void | VertexAreaUniform (MeshType &m, VertexSampler &ps, int sampleNum) |
static void | VertexBorder (MeshType &m, VertexSampler &ps) |
Sample all the border vertices. | |
static void | VertexBorderCorner (MeshType &m, VertexSampler &ps, float angleRad) |
Sample all the border corner vertices. | |
static void | VertexCrease (MeshType &m, VertexSampler &ps) |
static void | VertexUniform (MeshType &m, VertexSampler &ps, int sampleNum, bool onlySelected) |
Sample the vertices in a uniform way. Each vertex has the same probabiltiy of being chosen. | |
static void | VertexUniform (MeshType &m, VertexSampler &ps, int sampleNum) |
static void | VertexWeighted (MeshType &m, VertexSampler &ps, int sampleNum) |
static ScalarType | WeightedArea (FaceType &f, PerVertexFloatAttribute &wH) |
static void | WeightedMontecarlo (MeshType &m, VertexSampler &ps, int sampleNum, float variance) |
Private Types | |
typedef MeshType::BoxType | BoxType |
typedef MeshType::CoordType | CoordType |
typedef MeshType::EdgeIterator | EdgeIterator |
typedef MeshType::EdgeType | EdgeType |
typedef MeshType::FaceContainer | FaceContainer |
typedef MeshType::FaceIterator | FaceIterator |
typedef MeshType::FacePointer | FacePointer |
typedef MeshType::FaceType | FaceType |
typedef vcg::SpatialHashTable < FaceType, ScalarType > | MeshSHT |
typedef vcg::SpatialHashTable < FaceType, ScalarType > ::CellIterator | MeshSHTIterator |
typedef vcg::SpatialHashTable < VertexType, ScalarType > | MontecarloSHT |
typedef vcg::SpatialHashTable < VertexType, ScalarType > ::CellIterator | MontecarloSHTIterator |
typedef MeshType::template PerVertexAttributeHandle < float > | PerVertexFloatAttribute |
typedef vcg::SpatialHashTable < VertexType, ScalarType > | SampleSHT |
typedef vcg::SpatialHashTable < VertexType, ScalarType > ::CellIterator | SampleSHTIterator |
typedef MeshType::ScalarType | ScalarType |
typedef MeshType::VertexIterator | VertexIterator |
typedef MeshType::VertexPointer | VertexPointer |
typedef MeshType::VertexType | VertexType |
Main Class of the Sampling framework.
This class allows you to perform various kind of random/procedural point sampling over a triangulated surface. The class is templated over the PointSampler object that allows to customize the use of the generated samples.
Definition at line 451 of file point_sampling.h.
typedef MeshType::BoxType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::BoxType [private] |
Definition at line 454 of file point_sampling.h.
typedef MeshType::CoordType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::CoordType [private] |
Definition at line 453 of file point_sampling.h.
typedef MeshType::EdgeIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::EdgeIterator [private] |
Definition at line 460 of file point_sampling.h.
typedef MeshType::EdgeType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::EdgeType [private] |
Definition at line 459 of file point_sampling.h.
typedef MeshType::FaceContainer vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceContainer [private] |
Definition at line 464 of file point_sampling.h.
typedef MeshType::FaceIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceIterator [private] |
Definition at line 463 of file point_sampling.h.
typedef MeshType::FacePointer vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FacePointer [private] |
Definition at line 462 of file point_sampling.h.
typedef MeshType::FaceType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceType [private] |
Definition at line 461 of file point_sampling.h.
typedef vcg::SpatialHashTable<FaceType, ScalarType> vcg::tri::SurfaceSampling< MeshType, VertexSampler >::MeshSHT [private] |
Definition at line 466 of file point_sampling.h.
typedef vcg::SpatialHashTable<FaceType, ScalarType>::CellIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::MeshSHTIterator [private] |
Definition at line 467 of file point_sampling.h.
typedef vcg::SpatialHashTable<VertexType, ScalarType> vcg::tri::SurfaceSampling< MeshType, VertexSampler >::MontecarloSHT [private] |
Definition at line 468 of file point_sampling.h.
typedef vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::MontecarloSHTIterator [private] |
Definition at line 469 of file point_sampling.h.
typedef MeshType::template PerVertexAttributeHandle<float> vcg::tri::SurfaceSampling< MeshType, VertexSampler >::PerVertexFloatAttribute [private] |
Definition at line 473 of file point_sampling.h.
typedef vcg::SpatialHashTable<VertexType, ScalarType> vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SampleSHT [private] |
Definition at line 470 of file point_sampling.h.
typedef vcg::SpatialHashTable<VertexType, ScalarType>::CellIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SampleSHTIterator [private] |
Definition at line 471 of file point_sampling.h.
typedef MeshType::ScalarType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::ScalarType [private] |
Definition at line 455 of file point_sampling.h.
typedef GridStaticPtr<FaceType, ScalarType > vcg::tri::SurfaceSampling< MeshType, VertexSampler >::TriMeshGrid |
Definition at line 2077 of file point_sampling.h.
typedef MeshType::VertexIterator vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexIterator [private] |
Definition at line 458 of file point_sampling.h.
typedef MeshType::VertexPointer vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexPointer [private] |
Definition at line 457 of file point_sampling.h.
typedef MeshType::VertexType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexType [private] |
Definition at line 456 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::AllEdge | ( | MeshType & | m, |
VertexSampler & | ps | ||
) | [inline, static] |
Definition at line 933 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::AllFace | ( | MeshType & | m, |
VertexSampler & | ps | ||
) | [inline, static] |
Definition at line 922 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::AllVertex | ( | MeshType & | m, |
VertexSampler & | ps | ||
) | [inline, static] |
Definition at line 612 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::AllVertex | ( | MeshType & | m, |
VertexSampler & | ps, | ||
bool | onlySelected | ||
) | [inline, static] |
Definition at line 617 of file point_sampling.h.
static bool vcg::tri::SurfaceSampling< MeshType, VertexSampler >::checkPoissonDisk | ( | SampleSHT & | sht, |
const Point3< ScalarType > & | p, | ||
ScalarType | radius | ||
) | [inline, static] |
Definition at line 1612 of file point_sampling.h.
static ScalarType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::ComputePoissonDiskRadius | ( | MeshType & | origMesh, |
int | sampleNum | ||
) | [inline, static] |
Estimate the radius r that you should give to get a certain number of samples in a Poissson Disk Distribution of radius r.
Definition at line 1711 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::ComputePoissonSampleNum | ( | MeshType & | origMesh, |
ScalarType | diskRadius | ||
) | [inline, static] |
Definition at line 1726 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::EdgeMeshUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
float | radius, | ||
bool | conservative = true |
||
) | [inline, static] |
Perform an uniform sampling over an EdgeMesh.
It assumes that the mesh is 1-manifold. each connected component is sampled in a independent way. For each component of lenght <L> we place on it floor(L/radius)+1 samples. (if conservative argument is false we place ceil(L/radius)+1 samples)
Definition at line 751 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::EdgeMontecarlo | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | sampleAllEdges | ||
) | [inline, static] |
This function computes a montecarlo distribution with an EXACT number of samples. it works by generating a sequence of consecutive segments proportional to the triangle areas and actually shooting sample over this line
Definition at line 1056 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::EdgeUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | sampleFauxEdge = true |
||
) | [inline, static] |
Definition at line 949 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceSimilar | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | dualFlag, | ||
bool | randomFlag | ||
) | [inline, static] |
Definition at line 1432 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceSubdivision | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | randSample | ||
) | [inline, static] |
Compute a sampling of the surface where the points are regularly scattered over the face surface using a recursive longest-edge subdivision rule.
Definition at line 1232 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceSubdivisionOld | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | randSample | ||
) | [inline, static] |
Compute a sampling of the surface where the points are regularly scattered over the face surface using a recursive longest-edge subdivision rule.
Definition at line 1323 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FaceUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
Definition at line 908 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FillAndShuffleFacePointerVector | ( | MeshType & | m, |
std::vector< FacePointer > & | faceVec | ||
) | [inline, static] |
Definition at line 694 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::FillAndShuffleVertexPointerVector | ( | MeshType & | m, |
std::vector< VertexPointer > & | vertVec | ||
) | [inline, static] |
Definition at line 704 of file point_sampling.h.
static VertexPointer vcg::tri::SurfaceSampling< MeshType, VertexSampler >::getBestPrecomputedMontecarloSample | ( | Point3i & | cell, |
MontecarloSHT & | samplepool, | ||
ScalarType | diskRadius, | ||
const PoissonDiskParam & | pp | ||
) | [inline, static] |
Definition at line 1687 of file point_sampling.h.
static VertexPointer vcg::tri::SurfaceSampling< MeshType, VertexSampler >::getSampleFromCell | ( | Point3i & | cell, |
MontecarloSHT & | samplepool | ||
) | [inline, static] |
Definition at line 1677 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::HierarchicalPoissonDisk | ( | MeshType & | origMesh, |
VertexSampler & | ps, | ||
MeshType & | montecarloMesh, | ||
ScalarType | diskRadius, | ||
const struct PoissonDiskParam | pp = PoissonDiskParam() |
||
) | [inline, static] |
Compute a Poisson-disk sampling of the surface. The radius of the disk is computed according to the estimated sampling density.
This algorithm is an adaptation of the algorithm of White et al. :
"Poisson Disk Point Set by Hierarchical Dart Throwing" K. B. White, D. Cline, P. K. Egbert, IEEE Symposium on Interactive Ray Tracing, 2007, 10-12 Sept. 2007, pp. 129-132.
Definition at line 1940 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::InitRadiusHandleFromQuality | ( | MeshType & | sampleMesh, |
PerVertexFloatAttribute & | rH, | ||
ScalarType | diskRadius, | ||
ScalarType | radiusVariance, | ||
bool | invert | ||
) | [inline, static] |
When performing an adptive pruning for each sample we expect a varying radius to be removed. The radius is a PerVertex attribute that we compute from the current quality
the expected radius of the sample is computed so that it linearly maps the quality between diskradius and diskradius*variance in other words the radius
Definition at line 1740 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::InitSpatialHashTable | ( | MeshType & | montecarloMesh, |
MontecarloSHT & | montecarloSHT, | ||
ScalarType | diskRadius, | ||
struct PoissonDiskParam | pp = PoissonDiskParam() |
||
) | [inline, static] |
Definition at line 1758 of file point_sampling.h.
static double vcg::tri::SurfaceSampling< MeshType, VertexSampler >::LnFac | ( | int | n | ) | [inline, static] |
Definition at line 497 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::Montecarlo | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
This function computes a montecarlo distribution with an EXACT number of samples. it works by generating a sequence of consecutive segments proportional to the triangle areas and actually shooting sample over this line
Definition at line 1097 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::MontecarloPoisson | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
This function compute montecarlo distribution with an approximate number of samples exploiting the poisson distribution approximation of the binomial distribution.
For a given triangle t of area a_t, in a Mesh of area A, if we take n_s sample over the mesh, the number of samples that falls in t follows the poisson distribution of P(lambda ) with lambda = n_s * (a_t/A).
To approximate the Binomial we use a Poisson distribution with parameter = np can be used as an approximation to B(n,p) (it works if n is sufficiently large and p is sufficiently small).
Definition at line 1030 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::Poisson | ( | double | lambda | ) | [inline, static] |
algorithm poisson random number (Knuth): init: Let L ← e^−λ, k ← 0 and p ← 1. do: k ← k + 1. Generate uniform random number u in [0,1] and let p ← p × u. while p > L. return k − 1.
Definition at line 596 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::PoissonDiskPruning | ( | VertexSampler & | ps, |
MeshType & | montecarloMesh, | ||
ScalarType | diskRadius, | ||
PoissonDiskParam & | pp | ||
) | [inline, static] |
This is the main function that is used to build a poisson distribuition starting from a dense sample cloud. Trivial approach that puts all the samples in a hashed UG and randomly choose a sample and remove all the points in the sphere centered on the chosen sample
Definition at line 1852 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::PoissonDiskPruningByNumber | ( | VertexSampler & | ps, |
MeshType & | m, | ||
size_t | sampleNum, | ||
ScalarType & | diskRadius, | ||
PoissonDiskParam & | pp, | ||
float | tolerance = 0.04 , |
||
int | maxIter = 20 |
||
) | [inline, static] |
Definition at line 1793 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::PoissonRatioUniforms | ( | double | L | ) | [inline, static] |
Definition at line 534 of file point_sampling.h.
static CoordType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::RandomBarycentric | ( | ) | [inline, static] |
Definition at line 982 of file point_sampling.h.
static double vcg::tri::SurfaceSampling< MeshType, VertexSampler >::RandomDouble01 | ( | ) | [inline, static] |
Definition at line 491 of file point_sampling.h.
static unsigned int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::RandomInt | ( | unsigned int | i | ) | [inline, static] |
Definition at line 485 of file point_sampling.h.
static CoordType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::RandomPointInTriangle | ( | const FaceType & | f | ) | [inline, static] |
Definition at line 988 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::RegularRecursiveOffset | ( | MeshType & | m, |
std::vector< CoordType > & | pvec, | ||
ScalarType | offset, | ||
float | minDiag | ||
) | [inline, static] |
Definition at line 2088 of file point_sampling.h.
static math::MarsenneTwisterRNG& vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SamplingRandomGenerator | ( | ) | [inline, static] |
Definition at line 477 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SingleFaceRaster | ( | typename MeshType::FaceType & | f, |
VertexSampler & | ps, | ||
const Point2< typename MeshType::ScalarType > & | v0, | ||
const Point2< typename MeshType::ScalarType > & | v1, | ||
const Point2< typename MeshType::ScalarType > & | v2, | ||
bool | correctSafePointsBaryCoords = true |
||
) | [inline, static] |
Definition at line 1473 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SingleFaceSimilar | ( | FacePointer | fp, |
VertexSampler & | ps, | ||
int | n_samples_per_edge | ||
) | [inline, static] |
Definition at line 1353 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SingleFaceSimilarDual | ( | FacePointer | fp, |
VertexSampler & | ps, | ||
int | n_samples_per_edge, | ||
bool | randomFlag | ||
) | [inline, static] |
Definition at line 1370 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SingleFaceSubdivision | ( | int | sampleNum, |
const CoordType & | v0, | ||
const CoordType & | v1, | ||
const CoordType & | v2, | ||
VertexSampler & | ps, | ||
FacePointer | fp, | ||
bool | randSample | ||
) | [inline, static] |
Definition at line 1172 of file point_sampling.h.
static int vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SingleFaceSubdivisionOld | ( | int | sampleNum, |
const CoordType & | v0, | ||
const CoordType & | v1, | ||
const CoordType & | v2, | ||
VertexSampler & | ps, | ||
FacePointer | fp, | ||
bool | randSample | ||
) | [inline, static] |
Definition at line 1261 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::StratifiedMontecarlo | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
Definition at line 994 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::SubdivideAndSample | ( | MeshType & | m, |
std::vector< CoordType > & | pvec, | ||
const Box3< ScalarType > | bb, | ||
RRParam & | rrp, | ||
float | curDiag | ||
) | [inline, static] |
Definition at line 2105 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::Texture | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | textureWidth, | ||
int | textureHeight, | ||
bool | correctSafePointsBaryCoords = true |
||
) | [inline, static] |
Definition at line 2061 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexAreaUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
Sample the vertices in a uniform way. Each vertex has a probability of being chosen that is proportional to the area it represent.
Definition at line 674 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexBorder | ( | MeshType & | m, |
VertexSampler & | ps | ||
) | [inline, static] |
Sample all the border vertices.
It assumes that the border flag have been set over the mesh. All the vertices on the border are sampled.
Definition at line 874 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexBorderCorner | ( | MeshType & | m, |
VertexSampler & | ps, | ||
float | angleRad | ||
) | [inline, static] |
Sample all the border corner vertices.
It assumes that the border flag have been set over the mesh both for vertex and for faces. All the vertices on the border where the surface forms an angle smaller than the given threshold are sampled.
Definition at line 844 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexCrease | ( | MeshType & | m, |
VertexSampler & | ps | ||
) | [inline, static] |
Sample all the crease vertices. It assumes that the crease edges had been marked as non-faux edges for example by using tri::UpdateFlags<MeshType>::FaceFauxCrease(mesh,creaseAngleRad); Then it chooses all the vertices where there are at least three non faux edges.
Definition at line 885 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
bool | onlySelected | ||
) | [inline, static] |
Sample the vertices in a uniform way. Each vertex has the same probabiltiy of being chosen.
Definition at line 716 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexUniform | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
Definition at line 738 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::VertexWeighted | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum | ||
) | [inline, static] |
Sample the vertices in a weighted way. Each vertex has a probability of being chosen that is proportional to its quality. It assumes that you are asking a number of vertices smaller than nv; Algorithm: 1) normalize quality so that sum q == 1; 2) shuffle vertices. 3) for each vertices choose it if rand > thr;
Definition at line 636 of file point_sampling.h.
static ScalarType vcg::tri::SurfaceSampling< MeshType, VertexSampler >::WeightedArea | ( | FaceType & | f, |
PerVertexFloatAttribute & | wH | ||
) | [inline, static] |
Definition at line 1126 of file point_sampling.h.
static void vcg::tri::SurfaceSampling< MeshType, VertexSampler >::WeightedMontecarlo | ( | MeshType & | m, |
VertexSampler & | ps, | ||
int | sampleNum, | ||
float | variance | ||
) | [inline, static] |
Compute a sampling of the surface that is weighted by the quality and a variance
We use the quality as linear distortion of density. We consider each triangle as scaled between 1 and 1/variance linearly according quality.
In practice with variance 2 the average distance between sample will double where the quality is maxima. If you have two same area region A with q==-1 and B with q==1, if variance==2 the A will have 4 times more samples than B
Definition at line 1140 of file point_sampling.h.