![]() |
ACloudViewer
3.9.4
A Modern Library for 3D Data Processing
|
#include <Neighbourhood.h>

Public Types | |
| enum | GeomElement { FLAG_DEPRECATED = 0 , FLAG_GRAVITY_CENTER = 1 , FLAG_LS_PLANE = 2 , FLAG_QUADRIC = 4 } |
| enum | CurvatureType { GAUSSIAN_CURV = 1 , MEAN_CURV , NORMAL_CHANGE_RATE } |
| Curvature type. More... | |
| enum | InputVectorsUsage { UseOXYasBase , UseYAsUpDir , None } |
| enum | GeomFeature { EigenValuesSum = 1 , Omnivariance , EigenEntropy , Anisotropy , Planarity , Linearity , PCA1 , PCA2 , SurfaceVariation , Sphericity , Verticality , EigenValue1 , EigenValue2 , EigenValue3 } |
| Geometric feature computed from eigen values/vectors. More... | |
Public Member Functions | |
| Neighbourhood (GenericIndexedCloudPersist *associatedCloud) | |
| Default constructor. More... | |
| virtual | ~Neighbourhood ()=default |
| Default destructor. More... | |
| virtual void | reset () |
| Resets structure (depreactes all associated geometrical fetaures) More... | |
| GenericIndexedCloudPersist * | associatedCloud () const |
| Returns associated cloud. More... | |
| GenericIndexedMesh * | triangulateOnPlane (bool duplicateVertices, PointCoordinateType maxEdgeLength, std::string &outputErrorStr) |
| Applies 2D Delaunay triangulation. More... | |
| GenericIndexedMesh * | triangulateFromQuadric (unsigned stepsX, unsigned stepsY) |
| template<class Vec2D > | |
| bool | projectPointsOn2DPlane (std::vector< Vec2D > &points2D, const PointCoordinateType *planeEquation=nullptr, CCVector3 *O=nullptr, CCVector3 *X=nullptr, CCVector3 *Y=nullptr, InputVectorsUsage vectorsUsage=None) |
| Projects points on the best fitting LS plane. More... | |
| double | computeFeature (GeomFeature feature) |
| Computes the given feature on a set of point. More... | |
| ScalarType | computeMomentOrder1 (const CCVector3 &P) |
| ScalarType | computeRoughness (const CCVector3 &P, const CCVector3 *roughnessUpDir=nullptr) |
| ScalarType | computeCurvature (const CCVector3 &P, CurvatureType cType) |
| Computes the curvature of a set of point (by fitting a 2.5D quadric) More... | |
| const CCVector3 * | getGravityCenter () |
| Returns gravity center. More... | |
| void | setGravityCenter (const CCVector3 &G) |
| Sets gravity center. More... | |
| const PointCoordinateType * | getLSPlane () |
| Returns best interpolating plane equation (Least-square) More... | |
| void | setLSPlane (const PointCoordinateType eq[4], const CCVector3 &X, const CCVector3 &Y, const CCVector3 &N) |
| Sets the best interpolating plane equation (Least-square) More... | |
| const CCVector3 * | getLSPlaneX () |
| Returns best interpolating plane (Least-square) 'X' base vector. More... | |
| const CCVector3 * | getLSPlaneY () |
| Returns best interpolating plane (Least-square) 'Y' base vector. More... | |
| const CCVector3 * | getLSPlaneNormal () |
| Returns best interpolating plane (Least-square) normal vector. More... | |
| const PointCoordinateType * | getQuadric (Tuple3ub *dims=nullptr) |
| Returns the best interpolating 2.5D quadric. More... | |
| bool | compute3DQuadric (double quadricEquation[10]) |
| Computes the best interpolating quadric (Least-square) More... | |
| cloudViewer::SquareMatrixd | computeCovarianceMatrix () |
| Computes the covariance matrix. More... | |
| PointCoordinateType | computeLargestRadius () |
Static Public Attributes | |
| static constexpr int | IGNORE_MAX_EDGE_LENGTH = 0 |
| static constexpr bool | DUPLICATE_VERTICES = true |
| static constexpr bool | DO_NOT_DUPLICATE_VERTICES = false |
Protected Member Functions | |
| void | computeGravityCenter () |
| Computes the gravity center. More... | |
| bool | computeLeastSquareBestFittingPlane () |
| Computes the least-square best fitting plane. More... | |
| bool | computeQuadric () |
| Computes best fitting 2.5D quadric. More... | |
Protected Attributes | |
| PointCoordinateType | m_quadricEquation [6] |
| 2.5D Quadric equation More... | |
| Tuple3ub | m_quadricEquationDirections |
| 2.5D Quadric equation dimensions More... | |
| PointCoordinateType | m_lsPlaneEquation [4] |
| Least-square best fitting plane parameters. More... | |
| CCVector3 | m_lsPlaneVectors [3] |
| Least-square best fitting plane base vectors. More... | |
| CCVector3 | m_gravityCenter |
| Gravity center. More... | |
| unsigned char | m_structuresValidity |
| Geometrical elements validity (flags) More... | |
| GenericIndexedCloudPersist * | m_associatedCloud |
| Associated cloud. More... | |
A specific point could structure to handle subsets of points, provided with several geometric processings Typically suited for "nearest neighbours". It implements the GenericIndexCloud interface by inheriting the ReferenceCloud class.
Definition at line 25 of file Neighbourhood.h.
Curvature type.
| Enumerator | |
|---|---|
| GAUSSIAN_CURV | |
| MEAN_CURV | |
| NORMAL_CHANGE_RATE | |
Definition at line 42 of file Neighbourhood.h.
Geometric properties/elements that can be computed from the set of points (see Neighbourhood::getGeometricalElement)
| Enumerator | |
|---|---|
| FLAG_DEPRECATED | |
| FLAG_GRAVITY_CENTER | |
| FLAG_LS_PLANE | |
| FLAG_QUADRIC | |
Definition at line 34 of file Neighbourhood.h.
Geometric feature computed from eigen values/vectors.
Most of them are defined in "Contour detection in unstructured 3D point clouds", Hackel et al, 2016 PCA1 and PCA2 are defined in "3D terrestrial lidar data classification of complex natural scenes using a multi-scale dimensionality criterion: Applications in geomorphology", Brodu and Lague, 2012
| Enumerator | |
|---|---|
| EigenValuesSum | |
| Omnivariance | |
| EigenEntropy | |
| Anisotropy | |
| Planarity | |
| Linearity | |
| PCA1 | |
| PCA2 | |
| SurfaceVariation | |
| Sphericity | |
| Verticality | |
| EigenValue1 | |
| EigenValue2 | |
| EigenValue3 | |
Definition at line 161 of file Neighbourhood.h.
| Enumerator | |
|---|---|
| UseOXYasBase | |
| UseYAsUpDir | |
| None | |
Definition at line 76 of file Neighbourhood.h.
|
explicit |
Default constructor.
| associatedCloud | reference cloud |
Definition at line 46 of file Neighbourhood.cpp.
References m_associatedCloud, m_lsPlaneEquation, and m_quadricEquation.
|
virtualdefault |
Default destructor.
|
inline |
Returns associated cloud.
Definition at line 56 of file Neighbourhood.h.
| bool Neighbourhood::compute3DQuadric | ( | double | quadricEquation[10] | ) |
Computes the best interpolating quadric (Least-square)
| [out] | quadricEquation | an array of 10 coefficients [a,b,c,d,e,f,g,l,m,n] such as a.x^2+b.y^2+c.z^2+2e.x.y+2f.y.z+2g.z.x+2l.x+2m.y+2n.z+d = 0 |
Definition at line 524 of file Neighbourhood.cpp.
References count, getGravityCenter(), cloudViewer::GenericIndexedCloud::getPoint(), m_associatedCloud, cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
| cloudViewer::SquareMatrixd Neighbourhood::computeCovarianceMatrix | ( | ) |
Computes the covariance matrix.
Definition at line 144 of file Neighbourhood.cpp.
References count, getGravityCenter(), cloudViewer::GenericIndexedCloud::getPoint(), m_associatedCloud, cloudViewer::SquareMatrixTpl< Scalar >::m_values, cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
Referenced by ComputeCorePointNormal(), computeCurvature(), computeFeature(), computeLeastSquareBestFittingPlane(), computeMomentOrder1(), DimensionalityScaleParamsComputer::computeScaleParams(), and ccTrace::fitPlane().
| ScalarType Neighbourhood::computeCurvature | ( | const CCVector3 & | P, |
| CurvatureType | cType | ||
| ) |
Computes the curvature of a set of point (by fitting a 2.5D quadric)
Definition at line 906 of file Neighbourhood.cpp.
References abs(), computeCovarianceMatrix(), GAUSSIAN_CURV, getGravityCenter(), getQuadric(), m_associatedCloud, m_quadricEquationDirections, MEAN_CURV, NAN_VALUE, NORMAL_CHANGE_RATE, cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::u, Tuple3Tpl< Type >::x, X, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
Referenced by cloudViewer::GeometricalAnalysisTools::ComputeGeomCharacteristicAtLevel(), masc::NeighborhoodFeature::computeValue(), and ccTrace::getSegmentCostCurve().
| double Neighbourhood::computeFeature | ( | GeomFeature | feature | ) |
Computes the given feature on a set of point.
Definition at line 796 of file Neighbourhood.cpp.
References abs(), Anisotropy, computeCovarianceMatrix(), EigenEntropy, EigenValuesSum, Linearity, m_associatedCloud, Omnivariance, PCA1, Planarity, cloudViewer::GenericCloud::size(), and Jacobi< Scalar >::SortEigenValuesAndVectors().
Referenced by cloudViewer::GeometricalAnalysisTools::ComputeGeomCharacteristicAtLevel(), and masc::NeighborhoodFeature::computeValue().
|
protected |
Computes the gravity center.
Definition at line 122 of file Neighbourhood.cpp.
References count, FLAG_GRAVITY_CENTER, cloudViewer::GenericIndexedCloud::getPoint(), m_associatedCloud, m_structuresValidity, setGravityCenter(), cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
Referenced by getGravityCenter().
| PointCoordinateType Neighbourhood::computeLargestRadius | ( | ) |
Returns the set 'radius' (i.e. the distance between the gravity center and the its farthest point)
Definition at line 184 of file Neighbourhood.cpp.
References getGravityCenter(), cloudViewer::GenericIndexedCloud::getPoint(), m_associatedCloud, PC_NAN, and cloudViewer::GenericCloud::size().
Referenced by Candidate::Candidate(), and triangulateOnPlane().
|
protected |
Computes the least-square best fitting plane.
Definition at line 206 of file Neighbourhood.cpp.
References computeCovarianceMatrix(), Vector3Tpl< Type >::cross(), CV_LOCAL_MODEL_MIN_SIZE, Vector3Tpl< Type >::dot(), FLAG_LS_PLANE, Vector3Tpl< PointCoordinateType >::fromArray(), getGravityCenter(), Jacobi< Scalar >::GetMaxEigenValueAndVector(), Jacobi< Scalar >::GetMinEigenValueAndVector(), cloudViewer::GenericIndexedCloud::getPoint(), cloudViewer::LessThanEpsilon(), LS, m_associatedCloud, m_lsPlaneEquation, m_lsPlaneVectors, m_structuresValidity, Vector3Tpl< Type >::normalize(), cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::u, Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
Referenced by getLSPlane(), getLSPlaneNormal(), getLSPlaneX(), and getLSPlaneY().
| ScalarType Neighbourhood::computeMomentOrder1 | ( | const CCVector3 & | P | ) |
Computes the 1st order moment of a set of point (based on the eigenvalues)
Definition at line 760 of file Neighbourhood.cpp.
References computeCovarianceMatrix(), Vector3Tpl< Type >::dot(), Vector3Tpl< double >::fromArray(), Jacobi< Scalar >::GetEigenVector(), cloudViewer::GenericIndexedCloud::getPoint(), m_associatedCloud, NAN_VALUE, cloudViewer::GenericCloud::size(), Jacobi< Scalar >::SortEigenValuesAndVectors(), and Tuple3Tpl< Type >::u.
Referenced by cloudViewer::GeometricalAnalysisTools::ComputeGeomCharacteristicAtLevel(), and masc::NeighborhoodFeature::computeValue().
|
protected |
Computes best fitting 2.5D quadric.
Definition at line 302 of file Neighbourhood.cpp.
References cloudViewer::ConjugateGradient< N, Scalar >::A(), cloudViewer::ConjugateGradient< N, Scalar >::b(), count, CV_LOCAL_MODEL_MIN_SIZE, FLAG_QUADRIC, getGravityCenter(), getLSPlane(), cloudViewer::GenericIndexedCloud::getPoint(), cloudViewer::ConjugateGradient< N, Scalar >::initConjugateGradient(), cloudViewer::ConjugateGradient< N, Scalar >::iterConjugateGradient(), m_associatedCloud, m_quadricEquation, m_quadricEquationDirections, m_structuresValidity, cloudViewer::SquareMatrixTpl< Scalar >::m_values, max(), min(), QUADRIC, cloudViewer::GenericCloud::size(), Tuple3Tpl< Type >::u, Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
Referenced by getQuadric().
| ScalarType Neighbourhood::computeRoughness | ( | const CCVector3 & | P, |
| const CCVector3 * | roughnessUpDir = nullptr |
||
| ) |
Computes the roughness of a point (by fitting a 2D plane on its neighbors)
| P | point for which to compute the roughness value |
| roughnessUpDir | up direction to compute a signed roughness value (optional) |
Definition at line 886 of file Neighbourhood.cpp.
References abs(), cloudViewer::DistanceComputationTools::computePoint2PlaneDistance(), getLSPlane(), NAN_VALUE, Tuple3Tpl< Type >::u, and Vector3Tpl< PointCoordinateType >::vdot().
Referenced by cloudViewer::GeometricalAnalysisTools::ComputeGeomCharacteristicAtLevel(), and masc::NeighborhoodFeature::computeValue().
| const CCVector3 * Neighbourhood::getGravityCenter | ( | ) |
Returns gravity center.
Definition at line 58 of file Neighbourhood.cpp.
References computeGravityCenter(), FLAG_GRAVITY_CENTER, m_gravityCenter, and m_structuresValidity.
Referenced by ccLibAlgorithms::ApplyScaleMatchingAlgorithm(), Candidate::Candidate(), compute3DQuadric(), ComputeCellStats(), computeCovarianceMatrix(), computeCurvature(), ComputeFacetExtensions(), computeLargestRadius(), computeLeastSquareBestFittingPlane(), computeQuadric(), masc::NeighborhoodFeature::computeValue(), cloudViewer::GeometricalAnalysisTools::DetectCircle(), ccKdTreeForFacetExtraction::FuseCells(), cloudViewer::LocalModel::New(), CommandMatchBestFitPlane::process(), cloudViewer::CloudSamplingTools::resampleCellAtLevel(), and triangulateFromQuadric().
| const PointCoordinateType * Neighbourhood::getLSPlane | ( | ) |
Returns best interpolating plane equation (Least-square)
Returns an array of the form [a,b,c,d] such as: ax + by + cz = d
Definition at line 69 of file Neighbourhood.cpp.
References computeLeastSquareBestFittingPlane(), FLAG_LS_PLANE, m_lsPlaneEquation, and m_structuresValidity.
Referenced by cloudViewer::CloudSamplingTools::applyNoiseFilterAtLevel(), ccLibAlgorithms::ApplyScaleMatchingAlgorithm(), ComputeCellStats(), ComputeCorePointDescriptor(), computeQuadric(), computeRoughness(), cloudViewer::GeometricalAnalysisTools::DetectCircle(), ccKdTreeForFacetExtraction::FuseCells(), qM3C2Tools::GuessBestParams(), cloudViewer::LocalModel::New(), and cloudViewer::TrueKdTree::split().
| const CCVector3 * Neighbourhood::getLSPlaneNormal | ( | ) |
Returns best interpolating plane (Least-square) normal vector.
This corresponds to the smallest eigen value (i.e. the second largest cloud dimension)
Definition at line 102 of file Neighbourhood.cpp.
References computeLeastSquareBestFittingPlane(), FLAG_LS_PLANE, m_lsPlaneVectors, and m_structuresValidity.
Referenced by masc::NeighborhoodFeature::computeValue(), and cloudViewer::GeometricalAnalysisTools::DetectCircle().
| const CCVector3 * Neighbourhood::getLSPlaneX | ( | ) |
Returns best interpolating plane (Least-square) 'X' base vector.
This corresponds to the largest eigen value (i.e. the largest cloud dimension)
Definition at line 88 of file Neighbourhood.cpp.
References computeLeastSquareBestFittingPlane(), FLAG_LS_PLANE, m_lsPlaneVectors, and m_structuresValidity.
Referenced by ccLibAlgorithms::ApplyScaleMatchingAlgorithm(), cloudViewer::GeometricalAnalysisTools::DetectCircle(), and ccCompass::estimateStructureNormals().
| const CCVector3 * Neighbourhood::getLSPlaneY | ( | ) |
Returns best interpolating plane (Least-square) 'Y' base vector.
This corresponds to the second largest eigen value (i.e. the second largest cloud dimension)
Definition at line 95 of file Neighbourhood.cpp.
References computeLeastSquareBestFittingPlane(), FLAG_LS_PLANE, m_lsPlaneVectors, and m_structuresValidity.
| const PointCoordinateType * Neighbourhood::getQuadric | ( | Tuple3ub * | dims = nullptr | ) |
Returns the best interpolating 2.5D quadric.
Returns an array of the form [a,b,c,d,e,f] such as: Z = a + b.X + c.Y + d.X^2 + e.X.Y + f.Y^2
Definition at line 109 of file Neighbourhood.cpp.
References computeQuadric(), FLAG_QUADRIC, m_quadricEquation, m_quadricEquationDirections, and m_structuresValidity.
Referenced by computeCurvature(), cloudViewer::LocalModel::New(), and triangulateFromQuadric().
|
inline |
Projects points on the best fitting LS plane.
Projected points are stored in the points2D vector.
| points2D | output set |
| planeEquation | custom plane equation (otherwise the default Neighbouhood's one is used) |
| O | if set, the local plane base origin will be output here |
| X | if set, the local plane base X vector will be output here |
| Y | if set, the local plane base Y vector will be output here |
| useOXYasBase | whether O, X and Y should be used as input base |
Definition at line 89 of file Neighbourhood.h.
References cloudViewer::CCMiscTools::ComputeBaseVectors(), count, Vector3Tpl< Type >::cross(), Vector3Tpl< Type >::dot(), Vector3Tpl< Type >::normalize(), and X.
Referenced by ccContourExtractor::ExtractFlatContour(), and cloudViewer::Delaunay2dMesh::TesselateContour().
|
virtual |
Resets structure (depreactes all associated geometrical fetaures)
Definition at line 56 of file Neighbourhood.cpp.
References FLAG_DEPRECATED, and m_structuresValidity.
| void Neighbourhood::setGravityCenter | ( | const CCVector3 & | G | ) |
Sets gravity center.
Handle with care!
| G | gravity center |
Definition at line 64 of file Neighbourhood.cpp.
References FLAG_GRAVITY_CENTER, m_gravityCenter, and m_structuresValidity.
Referenced by computeGravityCenter().
| void Neighbourhood::setLSPlane | ( | const PointCoordinateType | eq[4], |
| const CCVector3 & | X, | ||
| const CCVector3 & | Y, | ||
| const CCVector3 & | N | ||
| ) |
Sets the best interpolating plane equation (Least-square)
Handle with care!
| eq | plane equation (ax + by + cz = d) |
| X | local base X vector |
| Y | local base Y vector |
| N | normal vector |
Definition at line 76 of file Neighbourhood.cpp.
References FLAG_LS_PLANE, m_lsPlaneEquation, m_lsPlaneVectors, m_structuresValidity, and X.
| GenericIndexedMesh * Neighbourhood::triangulateFromQuadric | ( | unsigned | stepsX, |
| unsigned | stepsY | ||
| ) |
Fit a quadric on point set (see getQuadric) then triangulates it inside bounding box
Definition at line 682 of file Neighbourhood.cpp.
References cloudViewer::PointCloudTpl< T >::addPoint(), cloudViewer::SimpleMesh::addTriangle(), cloudViewer::GenericCloud::getBoundingBox(), getGravityCenter(), getQuadric(), m_associatedCloud, m_quadricEquationDirections, cloudViewer::SimpleMesh::reserve(), cloudViewer::PointCloudTpl< T >::reserve(), Tuple3Tpl< Type >::u, Tuple3Tpl< Type >::x, X, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.
| GenericIndexedMesh * Neighbourhood::triangulateOnPlane | ( | bool | duplicateVertices, |
| PointCoordinateType | maxEdgeLength, | ||
| std::string & | outputErrorStr | ||
| ) |
Applies 2D Delaunay triangulation.
Cloud selection is first projected on the best least-square plane.
| duplicateVertices | whether to duplicate vertices (a new point cloud is created) or to use the associated one) |
| maxEdgeLength | max edge length for output triangles (IGNORE_MAX_EDGE_LENGTH = ignored) |
| outputErrorStr | error (if any) |
Definition at line 620 of file Neighbourhood.cpp.
References cloudViewer::PointCloudTpl< T >::addPoint(), cloudViewer::Delaunay2dMesh::buildMesh(), computeLargestRadius(), count, CV_LOCAL_MODEL_MIN_SIZE, cloudViewer::GenericIndexedCloud::getPoint(), cloudViewer::LessThanEpsilon(), cloudViewer::Delaunay2dMesh::linkMeshWith(), m_associatedCloud, cloudViewer::Delaunay2dMesh::removeTrianglesWithEdgesLongerThan(), cloudViewer::PointCloudTpl< T >::reserve(), cloudViewer::GenericCloud::size(), cloudViewer::Delaunay2dMesh::size(), TRI, and cloudViewer::Delaunay2dMesh::USE_ALL_POINTS.
Referenced by cloudViewer::PointProjectionTools::computeTriangulation(), and cloudViewer::LocalModel::New().
|
staticconstexpr |
Definition at line 30 of file Neighbourhood.h.
Referenced by cloudViewer::PointProjectionTools::computeTriangulation().
|
staticconstexpr |
Definition at line 29 of file Neighbourhood.h.
Referenced by cloudViewer::LocalModel::New().
|
staticconstexpr |
Definition at line 27 of file Neighbourhood.h.
Referenced by cloudViewer::LocalModel::New().
|
protected |
Associated cloud.
Definition at line 319 of file Neighbourhood.h.
Referenced by compute3DQuadric(), computeCovarianceMatrix(), computeCurvature(), computeFeature(), computeGravityCenter(), computeLargestRadius(), computeLeastSquareBestFittingPlane(), computeMomentOrder1(), computeQuadric(), Neighbourhood(), triangulateFromQuadric(), and triangulateOnPlane().
|
protected |
Gravity center.
Only valid if 'structuresValidity & GRAVITY_CENTER != 0'.
Definition at line 306 of file Neighbourhood.h.
Referenced by getGravityCenter(), and setGravityCenter().
|
protected |
Least-square best fitting plane parameters.
Array [a,b,c,d] such that ax+by+cz = d Only valid if 'structuresValidity & LS_PLANE != 0'.
Definition at line 296 of file Neighbourhood.h.
Referenced by computeLeastSquareBestFittingPlane(), getLSPlane(), Neighbourhood(), and setLSPlane().
|
protected |
Least-square best fitting plane base vectors.
Only valid if 'structuresValidity & LS_PLANE != 0'.
Definition at line 301 of file Neighbourhood.h.
Referenced by computeLeastSquareBestFittingPlane(), getLSPlaneNormal(), getLSPlaneX(), getLSPlaneY(), and setLSPlane().
|
protected |
2.5D Quadric equation
Array [a,b,c,d,e,f] such that Z = a + b.X + c.Y + d.X^2 + e.X.Y + f.Y^2.
Definition at line 284 of file Neighbourhood.h.
Referenced by computeQuadric(), getQuadric(), and Neighbourhood().
|
protected |
2.5D Quadric equation dimensions
Array (index(X),index(Y),index(Z)) where: 0=x, 1=y, 2=z Only valid if 'structuresValidity & QUADRIC != 0'.
Definition at line 290 of file Neighbourhood.h.
Referenced by computeCurvature(), computeQuadric(), getQuadric(), and triangulateFromQuadric().
|
protected |
Geometrical elements validity (flags)
Definition at line 309 of file Neighbourhood.h.
Referenced by computeGravityCenter(), computeLeastSquareBestFittingPlane(), computeQuadric(), getGravityCenter(), getLSPlane(), getLSPlaneNormal(), getLSPlaneX(), getLSPlaneY(), getQuadric(), reset(), setGravityCenter(), and setLSPlane().