ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
cloudViewer::PointCloudTpl< T > Class Template Reference

#include <PointCloudTpl.h>

Inheritance diagram for cloudViewer::PointCloudTpl< T >:
Collaboration diagram for cloudViewer::PointCloudTpl< T >:

Public Member Functions

 PointCloudTpl ()
 Default constructor. More...
 
virtual ~PointCloudTpl ()
 Default destructor. More...
 
unsigned size () const override
 
void forEach (GenericCloud::genericPointAction action) override
 
void getBoundingBox (CCVector3 &bbMin, CCVector3 &bbMax) override
 
void placeIteratorAtBeginning () override
 
const CCVector3getNextPoint () override
 
bool enableScalarField () override
 
bool isScalarFieldEnabled () const override
 
void setPointScalarValue (unsigned pointIndex, ScalarType value) override
 
ScalarType getPointScalarValue (unsigned pointIndex) const override
 
const CCVector3getPoint (unsigned index) const override
 
CCVector3getPointPtr (size_t index)
 
std::vector< CCVector3 > & getPoints ()
 
const std::vector< CCVector3 > & getPoints () const
 
void getPoint (unsigned index, CCVector3 &P) const override
 
void getPoint (unsigned index, double P[3]) const override
 
const CCVector3getPointPersistentPtr (unsigned index) override
 
const CCVector3getPointPersistentPtr (unsigned index) const
 
virtual bool resize (unsigned newCount)
 Resizes the point database. More...
 
virtual bool reserve (unsigned newCapacity)
 Reserves memory for the point database. More...
 
void reset ()
 Clears the cloud database. More...
 
void addPoint (const CCVector3 &P)
 Adds a 3D point to the database. More...
 
void setPoint (size_t index, const CCVector3 &P)
 
void setEigenPoint (size_t index, const Eigen::Vector3d &point)
 
void addEigenPoint (const Eigen::Vector3d &point)
 
void addPoint (double x, double y, double z)
 
void addPoint (double xyz[3])
 
void addPoints (const std::vector< CCVector3 > &points)
 
void addPoints (const std::vector< Eigen::Vector3d > &points)
 
Eigen::Vector3d getEigenPoint (size_t index) const
 
std::vector< Eigen::Vector3d > getEigenPoints () const
 
void setEigenPoints (const std::vector< Eigen::Vector3d > &points)
 
virtual void invalidateBoundingBox ()
 Invalidates bounding box. More...
 
unsigned getNumberOfScalarFields () const
 Returns the number of associated (and active) scalar fields. More...
 
ScalarFieldgetScalarField (int index) const
 Returns a pointer to a specific scalar field. More...
 
const char * getScalarFieldName (int index) const
 Returns the name of a specific scalar field. More...
 
int getScalarFieldIndexByName (const char *name) const
 Returns the index of a scalar field represented by its name. More...
 
ScalarFieldgetCurrentInScalarField () const
 Returns the scalar field currently associated to the cloud input. More...
 
ScalarFieldgetCurrentOutScalarField () const
 Returns the scalar field currently associated to the cloud output. More...
 
void setCurrentInScalarField (int index)
 Sets the INPUT scalar field. More...
 
int getCurrentInScalarFieldIndex ()
 Returns current INPUT scalar field index (or -1 if none) More...
 
void setCurrentOutScalarField (int index)
 Sets the OUTPUT scalar field. More...
 
int getCurrentOutScalarFieldIndex ()
 Returns current OUTPUT scalar field index (or -1 if none) More...
 
void setCurrentScalarField (int index)
 Sets both the INPUT & OUTPUT scalar field. More...
 
virtual int addScalarField (const char *uniqueName)
 Creates a new scalar field and registers it. More...
 
bool renameScalarField (int index, const char *newName)
 Renames a specific scalar field. More...
 
virtual void deleteScalarField (int index)
 Deletes a specific scalar field. More...
 
virtual void deleteAllScalarFields ()
 Deletes all scalar fields associated to this cloud. More...
 
unsigned capacity () const
 Returns cloud capacity (i.e. reserved size) More...
 

Protected Member Functions

virtual void swapPoints (unsigned firstIndex, unsigned secondIndex)
 Swaps two points (and their associated scalar values!) More...
 
CCVector3point (unsigned index)
 Returns non const access to a given point. More...
 
const CCVector3point (unsigned index) const
 Returns const access to a given point. More...
 

Protected Attributes

std::vector< CCVector3m_points
 3D Points database More...
 
BoundingBox m_bbox
 Bounding-box. More...
 
unsigned m_currentPointIndex
 'Iterator' on the points db More...
 
std::vector< ScalarField * > m_scalarFields
 Associated scalar fields. More...
 
int m_currentInScalarFieldIndex
 Index of current scalar field used for input. More...
 
int m_currentOutScalarFieldIndex
 Index of current scalar field used for output. More...
 

Detailed Description

template<class T>
class cloudViewer::PointCloudTpl< T >

A storage-efficient point cloud structure that can also handle an unlimited number of scalar fields

Definition at line 23 of file PointCloudTpl.h.

Constructor & Destructor Documentation

◆ PointCloudTpl()

template<class T >
cloudViewer::PointCloudTpl< T >::PointCloudTpl ( )
inline

Default constructor.

Definition at line 29 of file PointCloudTpl.h.

◆ ~PointCloudTpl()

template<class T >
virtual cloudViewer::PointCloudTpl< T >::~PointCloudTpl ( )
inlinevirtual

Default destructor.

Definition at line 36 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::deleteAllScalarFields().

Member Function Documentation

◆ addEigenPoint()

◆ addPoint() [1/3]

template<class T >
void cloudViewer::PointCloudTpl< T >::addPoint ( const CCVector3 P)
inline

Adds a 3D point to the database.

To assure the best efficiency, the database memory must have already been reserved (with PointCloud::reserve). Otherwise nothing happens.

Parameters
Pa 3D point

Definition at line 246 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_bbox, cloudViewer::PointCloudTpl< T >::m_points, cloudViewer::BoundingBoxTpl< T >::setValidity(), Tuple3Tpl< Type >::x, Tuple3Tpl< Type >::y, and Tuple3Tpl< Type >::z.

Referenced by ccPointPairRegistrationDlg::addAlignedPoint(), cloudViewer::PointCloudTpl< T >::addEigenPoint(), qCanupo2DViewDialog::addOrSelectPoint(), cloudViewer::PointCloudTpl< T >::addPoint(), cloudViewer::PointCloudTpl< T >::addPoints(), ccGraphicalSegmentationTool::addPointToPolyline(), ccPointPairRegistrationDlg::addReferencePoint(), AddVertex(), MeshWrapper< Real >::addVertex(), cloudViewer::PointProjectionTools::applyTransformation(), cloudViewer::visualization::Visualizer::CaptureDepthPointCloud(), ccTracePolylineTool::ccTracePolylineTool(), ccEntityAction::computeNormals(), cloudViewer::DistanceComputationTools::computePoint2MeshDistancesWithOctree(), ccTopologyRelation::constructGraphic(), contourPoly(), contourPoly2(), DistanceMapGenerationTool::ConvertConicalMapToMesh(), DistanceMapGenerationTool::ConvertMapToCloud(), DistanceMapGenerationTool::ConvertProfileToMesh(), cloudViewer::PointProjectionTools::developCloudOnCone(), cloudViewer::PointProjectionTools::developCloudOnCylinder(), ccGraphicalSegmentationTool::doActionUseExistingPolyline(), ccAlignDlg::estimateDelta(), ccCompass::estimateP21(), ccCompass::estimateStructureNormals(), GrainsAsEllipsoids::exportResultsAsCloud(), ccPointListPickingDlg::exportToNewCloud(), ccPointListPickingDlg::exportToNewPolyline(), ccContourExtractor::ExtractConcaveHull2D(), ccContourExtractor::ExtractFlatContour(), cloudViewer::FPCSRegistrationTools::FilterCandidates(), cloudViewer::FPCSRegistrationTools::FindCongruentBases(), FromFbxMesh(), ccRasterizeTool::generateContours(), GetConeProfile(), getDensity(), getMortarMaps(), ImportSourceVertices(), STEPFilter::importStepFile(), InitializeOutputCloud(), ProfileLoader::Load(), LoadCloud(), CSVMatrixFilter::loadFile(), SalomeHydroFilter::loadFile(), SinusxFilter::loadFile(), SoiFilter::loadFile(), LASFWFFilter::loadFile(), LASFilter::loadFile(), RDBFilter::loadFile(), DistanceMapGenerationDlg::loadOverlaySymbols(), LoadScan(), MergeOldTriangles(), ccTracePolylineTool::onItemPicked(), MainWindow::onItemPicked(), masc::ContextBasedFeature::prepare(), CommandCrop2D::process(), cloudViewer::visualization::MessageProcessor::ProcessMessage(), cloudViewer::ICPRegistrationTools::Register(), cloudViewer::CloudSamplingTools::resampleCellAtLevel(), qCanupo2DViewDialog::resetBoundary(), rotY(), cloudViewer::MeshSamplingTools::samplePointsOnMesh(), DistanceMapGenerationDlg::toggleOverlayGrid(), Cloth::toMesh(), qCanupoTools::TrainClassifier(), cloudViewer::Neighbourhood::triangulateFromQuadric(), and cloudViewer::Neighbourhood::triangulateOnPlane().

◆ addPoint() [2/3]

template<class T >
void cloudViewer::PointCloudTpl< T >::addPoint ( double  x,
double  y,
double  z 
)
inline

Definition at line 292 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::addPoint().

◆ addPoint() [3/3]

template<class T >
void cloudViewer::PointCloudTpl< T >::addPoint ( double  xyz[3])
inline

◆ addPoints() [1/2]

template<class T >
void cloudViewer::PointCloudTpl< T >::addPoints ( const std::vector< CCVector3 > &  points)
inline

◆ addPoints() [2/2]

◆ addScalarField()

template<class T >
virtual int cloudViewer::PointCloudTpl< T >::addScalarField ( const char *  uniqueName)
inlinevirtual

Creates a new scalar field and registers it.

Warnings:

  • the name must be unique (the method will fail if a SF with the same name already exists)
  • this method DOES resize the scalar field to match the current cloud size
    Parameters
    uniqueNamescalar field name (must be unique)
    Returns
    index of this new scalar field (or -1 if an error occurred)

Reimplemented in ccPointCloud.

Definition at line 448 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::getScalarFieldIndexByName(), cloudViewer::PointCloudTpl< T >::m_scalarFields, CCShareable::release(), cloudViewer::ScalarField::resizeSafe(), and cloudViewer::PointCloudTpl< T >::size().

Referenced by cloudViewer::PointCloudTpl< T >::enableScalarField().

◆ capacity()

◆ deleteAllScalarFields()

template<class T >
virtual void cloudViewer::PointCloudTpl< T >::deleteAllScalarFields ( )
inlinevirtual

◆ deleteScalarField()

template<class T >
virtual void cloudViewer::PointCloudTpl< T >::deleteScalarField ( int  index)
inlinevirtual

Deletes a specific scalar field.

WARNING: this operation may modify the scalar fields order (especially if the deleted SF is not the last one). However current IN & OUT scalar fields will stay up-to-date (while their index may change).

Parameters
indexindex of scalar field to be deleted

Reimplemented in ccPointCloud.

Definition at line 499 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_currentInScalarFieldIndex, cloudViewer::PointCloudTpl< T >::m_currentOutScalarFieldIndex, cloudViewer::PointCloudTpl< T >::m_scalarFields, and std::swap().

◆ enableScalarField()

◆ forEach()

◆ getBoundingBox()

◆ getCurrentInScalarField()

◆ getCurrentInScalarFieldIndex()

template<class T >
int cloudViewer::PointCloudTpl< T >::getCurrentInScalarFieldIndex ( )
inline

Returns current INPUT scalar field index (or -1 if none)

Definition at line 413 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_currentInScalarFieldIndex.

Referenced by GetScalarFieldIndex(), and ccRegistrationTools::ICP().

◆ getCurrentOutScalarField()

◆ getCurrentOutScalarFieldIndex()

template<class T >
int cloudViewer::PointCloudTpl< T >::getCurrentOutScalarFieldIndex ( )
inline

Returns current OUTPUT scalar field index (or -1 if none)

Definition at line 426 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_currentOutScalarFieldIndex.

Referenced by CommandSFConvertToRGB::process().

◆ getEigenPoint()

template<class T >
Eigen::Vector3d cloudViewer::PointCloudTpl< T >::getEigenPoint ( size_t  index) const
inline

Definition at line 320 of file PointCloudTpl.h.

References Vector3Tpl< double >::fromArray(), and cloudViewer::PointCloudTpl< T >::point().

Referenced by cloudViewer::pipelines::registration::AdvancedMatching(), cloudViewer::pipelines::registration::CorrespondenceCheckerBasedOnEdgeLength::Check(), cloudViewer::pipelines::registration::CorrespondenceCheckerBasedOnDistance::Check(), cloudViewer::pipelines::registration::TransformationEstimationForColoredICP::ComputeRMSE(), cloudViewer::pipelines::registration::TransformationEstimationForGeneralizedICP::ComputeRMSE(), cloudViewer::pipelines::registration::TransformationEstimationPointToPoint::ComputeRMSE(), cloudViewer::pipelines::registration::TransformationEstimationPointToPlane::ComputeRMSE(), cloudViewer::pipelines::registration::TransformationEstimationForColoredICP::ComputeTransformation(), cloudViewer::pipelines::registration::TransformationEstimationForGeneralizedICP::ComputeTransformation(), cloudViewer::pipelines::registration::TransformationEstimationPointToPoint::ComputeTransformation(), cloudViewer::pipelines::registration::TransformationEstimationPointToPlane::ComputeTransformation(), cloudViewer::visualization::rendering::PointCloudBuffersBuilder::ConstructBuffers(), cloudViewer::pipelines::registration::EvaluateRANSACBasedOnCorrespondence(), cloudViewer::pipelines::registration::GetInformationMatrixFromPointClouds(), cloudViewer::pipelines::registration::GetRegistrationResultAndCorrespondences(), cloudViewer::pipelines::registration::OptimizePairwiseRegistration(), cloudViewer::io::WritePointCloudInMemoryToXYZ(), cloudViewer::io::WritePointCloudToPLY(), cloudViewer::io::WritePointCloudToPTS(), cloudViewer::io::WritePointCloudToXYZ(), cloudViewer::io::WritePointCloudToXYZN(), and cloudViewer::io::WritePointCloudToXYZRGB().

◆ getEigenPoints()

template<class T >
std::vector<Eigen::Vector3d> cloudViewer::PointCloudTpl< T >::getEigenPoints ( ) const
inline

◆ getNextPoint()

template<class T >
const CCVector3* cloudViewer::PointCloudTpl< T >::getNextPoint ( )
inlineoverride

◆ getNumberOfScalarFields()

template<class T >
unsigned cloudViewer::PointCloudTpl< T >::getNumberOfScalarFields ( ) const
inline

◆ getPoint() [1/3]

template<class T >
const CCVector3* cloudViewer::PointCloudTpl< T >::getPoint ( unsigned  index) const
inlineoverride

Definition at line 143 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::point().

Referenced by ccPointPairRegistrationDlg::addAlignedPoint(), ccPointPairRegistrationDlg::addReferencePoint(), ccTrace::calculateOptimumSearchRadius(), ccPointPairRegistrationDlg::callHornRegistration(), qCanupoProcess::Classify(), G3Point::G3PointAction::cleanLabels(), cloud2binary(), G3Point::G3PointAction::cluster(), qVoxFallProcess::Compute(), ComputeM3C2DistForPoint(), DistanceMapGenerationTool::ComputeMinAndMaxLatitude_rad(), DistanceMapGenerationTool::ComputeRadialDist(), DistanceMapGenerationTool::ComputeSurfacesAndVolumes(), contourPoly(), contourPoly2(), ConverFromTo(), DistanceMapGenerationTool::ConvertCloudToConical(), DistanceMapGenerationTool::ConvertCloudToCylindrical(), DistanceMapGenerationTool::CreateMap(), ccCropTool::Crop(), qCSF::doAction(), qHoughNormals::doAction(), ccGraphicalSegmentationTool::doActionUseExistingPolyline(), ccGraphicalSegmentationTool::doExportSegmentationPolyline(), ccTrace::drawMeOnly(), ccCompass::estimateP21(), ccCompass::estimateStrain(), ccCompass::estimateStructureNormals(), ccRasterizeTool::exportContourLines(), FastMarchingForFacetExtraction::ExtractPlanarFacets(), cloudViewer::FPCSRegistrationTools::FindCongruentBases(), GrainsAsEllipsoids::fitEllipsoidToGrain(), get_subset(), getCommonPtsIdx(), getDensity(), getMortarMaps(), PointCloudWrapper< Real >::getPoint(), ccTrace::getSegmentCostGrad(), GrainsAsEllipsoids::GrainsAsEllipsoids(), qM3C2Tools::GuessBestParams(), ccCompass::importFoliations(), ccCompassImport::importFoliations(), ccCompass::importLineations(), ccCompassImport::importLineations(), ccTrace::insertWaypoint(), G3Point::G3PointAction::CloudAdaptor::kdtree_get_pt(), MainWindow::onItemPicked(), ccTrace::optimizeSegment(), optRotY(), DimScalarFieldWrapper::pointValue(), ccTracePolylineTool::polylineOverSampling(), masc::ContextBasedFeature::prepare(), CommandCSF::process(), ccPointListPickingDlg::processPickedPoint(), RefinePointClassif(), cloudViewer::ICPRegistrationTools::Register(), ccPointPairRegistrationDlg::removeAlignedPoint(), ccPointPairRegistrationDlg::removeRefPoint(), rotY(), LasSaver::saveNextPoint(), SimpleBinFilter::saveToFile(), LASFWFFilter::saveToFile(), G3Point::G3PointAction::segment(), toTranslatedVector(), ccTracePolylineTool::updatePolyLineTip(), and G3Point::G3PointAction::wolman().

◆ getPoint() [2/3]

template<class T >
void cloudViewer::PointCloudTpl< T >::getPoint ( unsigned  index,
CCVector3 P 
) const
inlineoverride

Definition at line 151 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::point().

◆ getPoint() [3/3]

template<class T >
void cloudViewer::PointCloudTpl< T >::getPoint ( unsigned  index,
double  P[3] 
) const
inlineoverride

◆ getPointPersistentPtr() [1/2]

template<class T >
const CCVector3* cloudViewer::PointCloudTpl< T >::getPointPersistentPtr ( unsigned  index) const
inline

Definition at line 163 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::point().

◆ getPointPersistentPtr() [2/2]

◆ getPointPtr()

template<class T >
CCVector3* cloudViewer::PointCloudTpl< T >::getPointPtr ( size_t  index)
inline

◆ getPoints() [1/2]

◆ getPoints() [2/2]

template<class T >
const std::vector<CCVector3>& cloudViewer::PointCloudTpl< T >::getPoints ( ) const
inline

Definition at line 150 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_points.

◆ getPointScalarValue()

◆ getScalarField()

template<class T >
ScalarField* cloudViewer::PointCloudTpl< T >::getScalarField ( int  index) const
inline

Returns a pointer to a specific scalar field.

Parameters
indexa scalar field index
Returns
a pointer to a ScalarField structure, or 0 if the index is invalid.

Definition at line 354 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_scalarFields.

Referenced by ccCloudLayersHelper::apply(), ccScalarFieldArithmeticsDlg::Apply(), ccTrace::buildCurvatureCost(), ccTrace::buildGradientCost(), CCCloudToDraco(), ccRasterizeTool::ccRasterizeTool(), ccCloudLayersHelper::changeCode(), masc::Classifier::classify(), qCanupoProcess::Classify(), qM3C2Process::Compute(), DistanceMapGenerationTool::ComputeRadialDist(), ccVolumeCalcTool::convertGridToCloud(), ccVolumeCalcTool::ConvertGridToCloud(), ccRasterizeTool::convertGridToCloud(), ccEntityAction::convertNormalsTo(), ccCropTool::Crop(), ccComparisonDlg::determineBestOctreeLevel(), qPCV::doAction(), qSRA::doProjectCloudDistsInGrid(), ccEntityAction::enhanceRGBWithIntensities(), ccCompass::estimateStructureNormals(), masc::Classifier::evaluate(), GrainsAsEllipsoids::exportResultsAsCloud(), qFacets::extractFacets(), LasSaveDialog::fieldsToSave(), LasExtraScalarFieldCard::fillField(), TreeIso::Final_seg_pcd(), G3Point::G3PointAction::fit(), ccRasterizeTool::generateHillshade(), masc::Tools::GetClassificationSF(), cloudViewer::PointCloudTpl< T >::getCurrentInScalarField(), cloudViewer::PointCloudTpl< T >::getCurrentOutScalarField(), LasField::GetLASFields(), getMortarMaps(), GetScalarField(), ccTrace::getSegmentCostCurve(), ccTrace::getSegmentCostGrad(), GetSource(), LasSaveDialog::handleComboBoxChange(), ccCompass::importFoliations(), ccCompassImport::importFoliations(), ccCompass::importLineations(), ccCompassImport::importLineations(), ccEntityAction::importToSF(), TreeIso::Init_seg_pcd(), TreeIso::Intermediate_seg_pcd(), LasExtraScalarField::MatchExtraBytesToScalarFields(), ccCloudLayersHelper::mouseMove(), ccCloudLayersHelper::moveItem(), ccTrace::optimizePath(), masc::Feature::PrepareSF(), CommandSFRename::process(), PCVCommand::Process(), cloudViewer::geometry::pybind_pointcloud(), cloudViewer::PointCloudTpl< T >::renameScalarField(), ccCloudLayersHelper::restoreState(), masc::PointFeature::retrieveField(), masc::Tools::RetrieveSF(), ccColorScaleEditorDialog::saveCurrentScale(), SaveScan(), ccCloudLayersHelper::saveState(), SimpleBinFilter::saveToFile(), LASFWFFilter::saveToFile(), LASFilter::saveToFile(), LasDetails::SelectBestVersion(), ccEntityAction::sfAddIdField(), ccColorFromScalarDlg::updateChannel(), ccColorFromScalarDlg::updateSpinBoxLimits(), and G3Point::G3PointAction::wolman().

◆ getScalarFieldIndexByName()

template<class T >
int cloudViewer::PointCloudTpl< T >::getScalarFieldIndexByName ( const char *  name) const
inline

Returns the index of a scalar field represented by its name.

Parameters
namea scalar field name
Returns
an index (-1 if the scalar field couldn't be found)

Definition at line 375 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_scalarFields, and name.

Referenced by ccRasterizeTool::activeLayerChanged(), cloudViewer::PointCloudTpl< T >::addScalarField(), ccScalarFieldArithmeticsDlg::Apply(), ccComparisonDlg::applyAndExit(), ccLibAlgorithms::ApplyCCLibAlgorithm(), ccComparisonDlg::cancelAndExit(), masc::Feature::CheckSFExistence(), masc::PointFeature::checkValidity(), masc::Classifier::classify(), qCanupoProcess::Classify(), qVoxFallProcess::Compute(), ccComparisonDlg::computeApproxDistances(), ccComparisonDlg::computeDistances(), ccLibAlgorithms::ComputeGeomCharacteristic(), DistanceMapGenerationTool::ComputeRadialDist(), ccRasterizeTool::convertGridToCloud(), ccEntityAction::convertNormalsTo(), ccMeasurementDevice::deleteScalarFieldFromCloud(), ccComparisonDlg::determineBestOctreeLevel(), qPCV::doAction(), qSRA::doProjectCloudDistsInGrid(), cloudViewer::PointCloudTpl< T >::enableScalarField(), ccEntityAction::enhanceRGBWithIntensities(), ccCompass::estimateStrain(), masc::Classifier::evaluate(), qFacets::extractFacets(), LasSaveDialog::fieldsToSave(), LasExtraScalarFieldCard::fillField(), TreeIso::Final_seg_pcd(), G3Point::G3PointAction::fit(), ccRasterizeTool::generateHillshade(), masc::Tools::GetClassificationSF(), ccEntityAction::GetFirstAvailableSFName(), G3Point::G3PointAction::GetG3PointAction(), getMortarMaps(), GetScalarFieldIndex(), ccTrace::getSegmentCostCurve(), ccTrace::getSegmentCostGrad(), GetSource(), LasSaveDialog::handleComboBoxChange(), BasePclModule::hasSelectedScalarField(), ccRegistrationTools::ICP(), ccCompass::importFoliations(), ccCompass::importLineations(), ccEntityAction::importToSF(), TreeIso::Init_seg_pcd(), TreeIso::Intermediate_seg_pcd(), ccTrace::isCurvaturePrecomputed(), ccTrace::isGradientPrecomputed(), LoadScan(), LasExtraScalarField::MatchExtraBytesToScalarFields(), ccTrace::optimizePath(), masc::ContextBasedFeature::prepare(), masc::Feature::PrepareSF(), CommandExtractCCs::process(), CommandStatTest::process(), CommandSFRename::process(), PCVCommand::Process(), cloudViewer::geometry::pybind_pointcloud(), SFCollector::releaseSFs(), RemoveScalarField(), cloudViewer::PointCloudTpl< T >::renameScalarField(), masc::Tools::RetrieveSF(), ccEntityAction::rgbGaussianFilter(), SaveScan(), LASFWFFilter::saveToFile(), LasDetails::SelectBestVersion(), ccEntityAction::sfAddIdField(), ccEntityAction::sfGaussianFilter(), ccEntityAction::statisticalTest(), and G3Point::G3PointAction::wolman().

◆ getScalarFieldName()

◆ invalidateBoundingBox()

template<class T >
virtual void cloudViewer::PointCloudTpl< T >::invalidateBoundingBox ( )
inlinevirtual

Invalidates bounding box.

Bounding box will be recomputed next time a request is made to 'getBoundingBox'.

Reimplemented in ccPointCloud.

Definition at line 338 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_bbox, and cloudViewer::BoundingBoxTpl< T >::setValidity().

Referenced by cloudViewer::ICPRegistrationTools::Register(), and cloudViewer::PointCloudTpl< T >::reset().

◆ isScalarFieldEnabled()

template<class T >
bool cloudViewer::PointCloudTpl< T >::isScalarFieldEnabled ( ) const
inlineoverride

◆ placeIteratorAtBeginning()

template<class T >
void cloudViewer::PointCloudTpl< T >::placeIteratorAtBeginning ( )
inlineoverride

◆ point() [1/2]

template<class T >
CCVector3* cloudViewer::PointCloudTpl< T >::point ( unsigned  index)
inlineprotected

◆ point() [2/2]

template<class T >
const CCVector3* cloudViewer::PointCloudTpl< T >::point ( unsigned  index) const
inlineprotected

Returns const access to a given point.

WARNING: index must be valid

Parameters
indexpoint index
Returns
pointer on point stored data

Definition at line 574 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_points, and cloudViewer::PointCloudTpl< T >::size().

◆ renameScalarField()

template<class T >
bool cloudViewer::PointCloudTpl< T >::renameScalarField ( int  index,
const char *  newName 
)
inline

Renames a specific scalar field.

Warning: name must not be already given to another SF!

Parameters
indexscalar field index
newNamenew name
Returns
success

Definition at line 481 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::getScalarField(), cloudViewer::PointCloudTpl< T >::getScalarFieldIndexByName(), and cloudViewer::ScalarField::setName().

Referenced by ccComparisonDlg::applyAndExit(), and cloudViewer::geometry::pybind_pointcloud().

◆ reserve()

◆ reset()

◆ resize()

template<class T >
virtual bool cloudViewer::PointCloudTpl< T >::resize ( unsigned  newCount)
inlinevirtual

Resizes the point database.

The cloud database is resized with the specified size. If the new size is smaller, the overflooding points will be deleted. If its greater, the database is filled with blank points (warning, the PointCloud::addPoint method will insert points after those ones).

Parameters
newNumberOfPointsthe new number of points
Returns
true if the method succeeds, false otherwise

Reimplemented in ccSymbolCloud, ccPointCloud, and cloudViewer::PointCloud.

Definition at line 175 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_points, and cloudViewer::PointCloudTpl< T >::m_scalarFields.

◆ setCurrentInScalarField()

template<class T >
void cloudViewer::PointCloudTpl< T >::setCurrentInScalarField ( int  index)
inline

◆ setCurrentOutScalarField()

◆ setCurrentScalarField()

◆ setEigenPoint()

template<class T >
void cloudViewer::PointCloudTpl< T >::setEigenPoint ( size_t  index,
const Eigen::Vector3d &  point 
)
inline

◆ setEigenPoints()

template<class T >
void cloudViewer::PointCloudTpl< T >::setEigenPoints ( const std::vector< Eigen::Vector3d > &  points)
inline

◆ setPoint()

◆ setPointScalarValue()

◆ size()

template<class T >
unsigned cloudViewer::PointCloudTpl< T >::size ( ) const
inlineoverride

Definition at line 38 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_points.

Referenced by ccPointPairRegistrationDlg::addAlignedPoint(), qCanupo2DViewDialog::addOrSelectPoint(), ccGraphicalSegmentationTool::addPointToPolyline(), ccPointPairRegistrationDlg::addReferencePoint(), cloudViewer::PointCloudTpl< T >::addScalarField(), AddVertex(), ccTrace::bakePathToScalarField(), ccTrace::buildCurvatureCost(), ccTrace::buildGradientCost(), G3Point::G3PointAction::buildStacksFromG3PointLabelSF(), ccTrace::calculateOptimumSearchRadius(), ccPointPairRegistrationDlg::callHornRegistration(), ccCloudLayersHelper::ccCloudLayersHelper(), ccWaveDialog::ccWaveDialog(), masc::ContextBasedFeature::checkValidity(), MeshWrapper< Real >::checkVertexCapacity(), masc::Classifier::classify(), qCanupoProcess::Classify(), cloud2binary(), qM3C2Process::Compute(), ccComparisonDlg::computeDistances(), ComputeFeatures(), ComputeKmeansClustering(), DistanceMapGenerationTool::ComputeMinAndMaxLatitude_rad(), DistanceMapGenerationTool::ComputeRadialDist(), ccEntityAction::computeStatParams(), DistanceMapGenerationTool::ComputeSurfacesAndVolumes(), cloudViewer::visualization::rendering::PointCloudBuffersBuilder::ConstructBuffers(), contourPoly(), ConverFromTo(), convert(), DistanceMapGenerationTool::ConvertCloudToConical(), DistanceMapGenerationTool::ConvertCloudToCylindrical(), ccRasterizeTool::convertGridToCloud(), DistanceMapGenerationTool::ConvertMapToCloud(), DistanceMapGenerationTool::CreateMap(), ccCropTool::Crop(), qCSF::doAction(), qHoughNormals::doAction(), qPoissonRecon::doAction(), qCanupoPlugin::doTrainAction(), ccAlignDlg::estimateDelta(), ccCompass::estimateP21(), ccCompass::estimateStrain(), ccCompass::estimateStructureNormals(), masc::Classifier::evaluate(), ccRasterizeTool::exportContourLines(), GrainsAsEllipsoids::exportResultsAsCloud(), qFacets::extractFacets(), FastMarchingForFacetExtraction::ExtractPlanarFacets(), cloudViewer::pipelines::integration::ScalableTSDFVolume::ExtractTriangleMesh(), cloudViewer::pipelines::integration::UniformTSDFVolume::ExtractTriangleMesh(), cloudViewer::pipelines::registration::FastGlobalRegistrationBasedOnFeatureMatching(), TreeIso::Final_seg_pcd(), cloudViewer::FPCSRegistrationTools::FindCongruentBases(), GrainsAsEllipsoids::fitEllipsoidToGrain(), cloudViewer::PointCloudTpl< T >::forEach(), ccDBRoot::gatherRecursiveInformation(), ccRasterizeTool::generateHillshade(), G3Point::G3PointAction::getBorders(), PointCloudWrapper< Real >::getColor(), getCommonPtsIdx(), GetKeyCluster(), getMortarMaps(), PointCloudWrapper< Real >::getNormal(), PointCloudWrapper< Real >::getPoint(), cloudViewer::pipelines::registration::GetRegistrationResultAndCorrespondences(), qM3C2Tools::GuessBestParams(), LasWaveformSaver::handlePoint(), LasScalarFieldLoader::handleRGBValue(), ccCommandLineParser::importFile(), ccCompass::importFoliations(), ccCompassImport::importFoliations(), ccCompass::importLineations(), ccCompassImport::importLineations(), ImportSourceVertices(), STEPFilter::importStepFile(), ccEntityAction::importToSF(), StereogramWidget::init(), TreeIso::Init_seg_pcd(), TreeIso::Intermediate_seg_pcd(), G3Point::G3PointAction::CloudAdaptor::kdtree_get_point_count(), cloudViewer::t::geometry::LegacySelectByIndex(), CSVMatrixFilter::loadFile(), SalomeHydroFilter::loadFile(), SinusxFilter::loadFile(), DRCFilter::loadFile(), LASFWFFilter::loadFile(), LASFilter::loadFile(), RDBFilter::loadFile(), DistanceMapGenerationDlg::loadOverlaySymbols(), LasWaveformLoader::loadWaveform(), main(), G3Point::G3PointAction::merge(), MergeOldTriangles(), ccCloudLayersHelper::mouseMove(), ccColorFromScalarDlg::onApply(), ccTracePolylineTool::onItemPicked(), MainWindow::onItemPicked(), ccPointPairRegistrationDlg::onPointCountChanged(), ccTrace::optimizeSegment(), optRotY(), ccGraphicalSegmentationTool::pauseSegmentationMode(), cloudViewer::PointCloudTpl< T >::point(), ccTracePolylineTool::polylineOverSampling(), masc::CorePoints::prepare(), masc::ContextBasedFeature::prepare(), masc::Feature::PrepareSF(), CommandCrossSection::process(), CommandFilterBySFValue::process(), CommandSampleMesh::process(), CommandCSF::process(), ccCloudLayersHelper::projectCloud(), cloudViewer::geometry::pybind_pointcloud(), cloudViewer::geometry::pybind_trianglemesh(), masc::Tools::RandomSubset(), cloudViewer::io::ReadPointCloud(), cloudViewer::io::ReadTriangleMeshFromOBJ(), cloudViewer::ICPRegistrationTools::Register(), cloudViewer::pipelines::registration::RegistrationRANSACBasedOnFeatureMatching(), ccPointPairRegistrationDlg::removeAlignedPoint(), ccPointPairRegistrationDlg::removeRefPoint(), ccCloudLayersHelper::restoreState(), masc::PointFeature::retrieveField(), rotY(), LasSaver::saveNextPoint(), SaveScan(), ccCloudLayersHelper::saveState(), PcdFilter::saveToFile(), SimpleBinFilter::saveToFile(), LASFWFFilter::saveToFile(), G3Point::G3PointAction::segment(), cloudViewer::ModelViewerWidget::SelectObject(), cloudViewer::PointCloudTpl< T >::setEigenPoint(), ecvFilterByLabelDlg::setInputEntity(), cloudViewer::PointCloudTpl< T >::setPoint(), ccCloudLayersHelper::setVisible(), ccEntityAction::sfAddIdField(), ccEntityAction::sfConvertToRandomRGB(), ccComparisonDlg::showHisto(), masc::CorePoints::size(), PointCloudWrapper< Real >::size(), NormDipAndDipDirFieldWrapper::size(), DimScalarFieldWrapper::size(), ColorScalarFieldWrapper::size(), ecvPoissonReconDlg::start(), ecvFilterByLabelDlg::start(), toTranslatedVector(), masc::Classifier::train(), ccPointPairRegistrationDlg::unstackAligned(), ccPointPairRegistrationDlg::unstackRef(), ccPointPairRegistrationDlg::updateAlignInfo(), StereogramDialog::updateFacetsFilter(), cloudViewer::visualization::VisualizerWithVertexSelection::UpdateGeometry(), GrainsAsEllipsoids::updateMeshAndLineSet(), ccGraphicalSegmentationTool::updatePolyLine(), ccTracePolylineTool::updatePolyLineTip(), DistanceMapGenerationDlg::updateZoom(), G3Point::G3PointAction::wolman(), cloudViewer::io::WritePointCloud(), cloudViewer::io::WritePointCloudInMemoryToXYZ(), cloudViewer::io::WritePointCloudToPLY(), cloudViewer::io::WritePointCloudToPTS(), cloudViewer::io::WritePointCloudToXYZ(), cloudViewer::io::WritePointCloudToXYZN(), and cloudViewer::io::WritePointCloudToXYZRGB().

◆ swapPoints()

template<class T >
virtual void cloudViewer::PointCloudTpl< T >::swapPoints ( unsigned  firstIndex,
unsigned  secondIndex 
)
inlineprotectedvirtual

Swaps two points (and their associated scalar values!)

Reimplemented in ccPointCloud.

Definition at line 546 of file PointCloudTpl.h.

References cloudViewer::PointCloudTpl< T >::m_points, cloudViewer::PointCloudTpl< T >::m_scalarFields, and std::swap().

Member Data Documentation

◆ m_bbox

◆ m_currentInScalarFieldIndex

◆ m_currentOutScalarFieldIndex

◆ m_currentPointIndex

template<class T >
unsigned cloudViewer::PointCloudTpl< T >::m_currentPointIndex
protected

◆ m_points

◆ m_scalarFields


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