Point Cloud Library (PCL)
1.10.1
|
PointCloud represents the base class in PCL for storing collections of 3D points. More...
#include <pcl/common/projection_matrix.h>
Public Types | |
using | PointType = PointT |
using | VectorType = std::vector< PointT, Eigen::aligned_allocator< PointT > > |
using | CloudVectorType = std::vector< PointCloud< PointT >, Eigen::aligned_allocator< PointCloud< PointT > > > |
using | Ptr = shared_ptr< PointCloud< PointT > > |
using | ConstPtr = shared_ptr< const PointCloud< PointT > > |
using | value_type = PointT |
using | reference = PointT & |
using | const_reference = const PointT & |
using | difference_type = typename VectorType::difference_type |
using | size_type = typename VectorType::size_type |
using | iterator = typename VectorType::iterator |
using | const_iterator = typename VectorType::const_iterator |
Public Member Functions | |
PointCloud ()=default | |
Default constructor. More... | |
PointCloud (const PointCloud< PointT > &pc, const std::vector< int > &indices) | |
Copy constructor from point cloud subset. More... | |
PointCloud (std::uint32_t width_, std::uint32_t height_, const PointT &value_=PointT()) | |
Allocate constructor from point cloud subset. More... | |
PointCloud & | operator+= (const PointCloud &rhs) |
Add a point cloud to the current cloud. More... | |
PointCloud | operator+ (const PointCloud &rhs) |
Add a point cloud to another cloud. More... | |
const PointT & | at (int column, int row) const |
Obtain the point given by the (column, row) coordinates. More... | |
PointT & | at (int column, int row) |
Obtain the point given by the (column, row) coordinates. More... | |
const PointT & | operator() (std::size_t column, std::size_t row) const |
Obtain the point given by the (column, row) coordinates. More... | |
PointT & | operator() (std::size_t column, std::size_t row) |
Obtain the point given by the (column, row) coordinates. More... | |
bool | isOrganized () const |
Return whether a dataset is organized (e.g., arranged in a structured grid). More... | |
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > | getMatrixXfMap (int dim, int stride, int offset) |
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. More... | |
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > | getMatrixXfMap (int dim, int stride, int offset) const |
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud. More... | |
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > | getMatrixXfMap () |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud. More... | |
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > | getMatrixXfMap () const |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud. More... | |
iterator | begin () |
iterator | end () |
const_iterator | begin () const |
const_iterator | end () const |
std::size_t | size () const |
void | reserve (std::size_t n) |
bool | empty () const |
void | resize (std::size_t n) |
Resize the cloud. More... | |
const PointT & | operator[] (std::size_t n) const |
PointT & | operator[] (std::size_t n) |
const PointT & | at (std::size_t n) const |
PointT & | at (std::size_t n) |
const PointT & | front () const |
PointT & | front () |
const PointT & | back () const |
PointT & | back () |
void | push_back (const PointT &pt) |
Insert a new point in the cloud, at the end of the container. More... | |
template<class... Args> | |
reference | emplace_back (Args &&...args) |
Emplace a new point in the cloud, at the end of the container. More... | |
iterator | insert (iterator position, const PointT &pt) |
Insert a new point in the cloud, given an iterator. More... | |
void | insert (iterator position, std::size_t n, const PointT &pt) |
Insert a new point in the cloud N times, given an iterator. More... | |
template<class InputIterator > | |
void | insert (iterator position, InputIterator first, InputIterator last) |
Insert a new range of points in the cloud, at a certain position. More... | |
template<class... Args> | |
iterator | emplace (iterator position, Args &&...args) |
Emplace a new point in the cloud, given an iterator. More... | |
iterator | erase (iterator position) |
Erase a point in the cloud. More... | |
iterator | erase (iterator first, iterator last) |
Erase a set of points given by a (first, last) iterator pair. More... | |
void | swap (PointCloud< PointT > &rhs) |
Swap a point cloud with another cloud. More... | |
void | clear () |
Removes all points in a cloud and sets the width and height to 0. More... | |
Ptr | makeShared () const |
Copy the cloud to the heap and return a smart pointer Note that deep copy is performed, so avoid using this function on non-empty clouds. More... | |
Static Public Member Functions | |
static bool | concatenate (pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2) |
static bool | concatenate (const pcl::PointCloud< PointT > &cloud1, const pcl::PointCloud< PointT > &cloud2, pcl::PointCloud< PointT > &cloud_out) |
Public Attributes | |
pcl::PCLHeader | header |
The point cloud header. More... | |
std::vector< PointT, Eigen::aligned_allocator< PointT > > | points |
The point data. More... | |
std::uint32_t | width = 0 |
The point cloud width (if organized as an image-structure). More... | |
std::uint32_t | height = 0 |
The point cloud height (if organized as an image-structure). More... | |
bool | is_dense = true |
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields). More... | |
Eigen::Vector4f | sensor_origin_ = Eigen::Vector4f::Zero () |
Sensor acquisition pose (origin/translation). More... | |
Eigen::Quaternionf | sensor_orientation_ = Eigen::Quaternionf::Identity () |
Sensor acquisition pose (rotation). More... | |
Protected Member Functions | |
PCL_DEPRECATED ("rewrite your code to avoid using this protected field") shared_ptr< MsgFieldMap > mapping_ | |
Friends | |
shared_ptr< MsgFieldMap > & | detail::getMapping (pcl::PointCloud< PointT > &p) |
PointCloud represents the base class in PCL for storing collections of 3D points.
The class is templated, which means you need to specify the type of data that it should contain. For example, to create a point cloud that holds 4 random XYZ data points, use:
The PointCloud class contains the following elements:
Definition at line 52 of file projection_matrix.h.
using pcl::PointCloud< PointT >::CloudVectorType = std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > > |
Definition at line 414 of file point_cloud.h.
using pcl::PointCloud< PointT >::const_iterator = typename VectorType::const_iterator |
Definition at line 428 of file point_cloud.h.
using pcl::PointCloud< PointT >::const_reference = const PointT& |
Definition at line 422 of file point_cloud.h.
using pcl::PointCloud< PointT >::ConstPtr = shared_ptr<const PointCloud<PointT> > |
Definition at line 416 of file point_cloud.h.
using pcl::PointCloud< PointT >::difference_type = typename VectorType::difference_type |
Definition at line 423 of file point_cloud.h.
using pcl::PointCloud< PointT >::iterator = typename VectorType::iterator |
Definition at line 427 of file point_cloud.h.
using pcl::PointCloud< PointT >::PointType = PointT |
Definition at line 412 of file point_cloud.h.
using pcl::PointCloud< PointT >::Ptr = shared_ptr<PointCloud<PointT> > |
Definition at line 415 of file point_cloud.h.
using pcl::PointCloud< PointT >::reference = PointT& |
Definition at line 421 of file point_cloud.h.
using pcl::PointCloud< PointT >::size_type = typename VectorType::size_type |
Definition at line 424 of file point_cloud.h.
using pcl::PointCloud< PointT >::value_type = PointT |
Definition at line 420 of file point_cloud.h.
using pcl::PointCloud< PointT >::VectorType = std::vector<PointT, Eigen::aligned_allocator<PointT> > |
Definition at line 413 of file point_cloud.h.
|
default |
Default constructor.
Sets is_dense to true, width and height to 0, and the sensor_origin_ and sensor_orientation_ to identity.
|
inline |
Copy constructor from point cloud subset.
[in] | pc | the cloud to copy into this |
[in] | indices | the subset to copy |
Definition at line 193 of file point_cloud.h.
|
inline |
Allocate constructor from point cloud subset.
[in] | width_ | the cloud width |
[in] | height_ | the cloud height |
[in] | value_ | default value |
Definition at line 209 of file point_cloud.h.
|
inline |
Obtain the point given by the (column, row) coordinates.
Only works on organized datasets (those that have height != 1).
[in] | column | the column coordinate |
[in] | row | the row coordinate |
Definition at line 284 of file point_cloud.h.
|
inline |
Obtain the point given by the (column, row) coordinates.
Only works on organized datasets (those that have height != 1).
[in] | column | the column coordinate |
[in] | row | the row coordinate |
Definition at line 270 of file point_cloud.h.
Referenced by pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::filters::Pyramid< PointT >::compute(), pcl::occlusion_reasoning::filter(), pcl::occlusion_reasoning::getOccludedCloud(), and pcl::PointCloudDepthAndRGBtoXYZRGBA().
|
inline |
Definition at line 456 of file point_cloud.h.
|
inline |
Definition at line 455 of file point_cloud.h.
|
inline |
Definition at line 460 of file point_cloud.h.
|
inline |
Definition at line 459 of file point_cloud.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getEdgeIndex(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getFaceIndex(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getHalfEdgeIndex(), and pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getVertexIndex().
|
inline |
Definition at line 429 of file point_cloud.h.
Referenced by pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::cleanUp(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances(), pcl::common::deleteCols(), pcl::common::deleteRows(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud(), pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::validateTransformation().
|
inline |
Definition at line 431 of file point_cloud.h.
|
inline |
Removes all points in a cloud and sets the width and height to 0.
Definition at line 592 of file point_cloud.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::approximatePolygon2D(), pcl::DisparityMapConverter< PointDEM >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::gpu::extractEuclideanClusters(), pcl::VoxelGridCovariance< PointTarget >::getDisplayCloud(), pcl::SurfaceReconstruction< PointNT >::reconstruct(), and pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::setSearchSurface().
|
inlinestatic |
Definition at line 256 of file point_cloud.h.
|
inlinestatic |
Definition at line 239 of file point_cloud.h.
Referenced by pcl::concatenate().
|
inline |
Emplace a new point in the cloud, given an iterator.
[in] | position | iterator before which the point will be emplaced |
[in] | args | the parameters to forward to the point to construct |
Definition at line 538 of file point_cloud.h.
|
inline |
Emplace a new point in the cloud, at the end of the container.
[in] | args | the parameters to forward to the point to construct |
Definition at line 480 of file point_cloud.h.
|
inline |
Definition at line 437 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::compute3DCentroid(), pcl::computeNDCentroid(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::SupervoxelClustering< PointT >::setInputCloud(), pcl::PCDWriter::writeASCII(), and pcl::PCDWriter::writeBinary().
|
inline |
Definition at line 430 of file point_cloud.h.
Referenced by pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances(), pcl::common::deleteRows(), pcl::common::duplicateRows(), pcl::common::expandRows(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud(), pcl::common::mirrorRows(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), and pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation().
|
inline |
Definition at line 432 of file point_cloud.h.
|
inline |
Erase a set of points given by a (first, last) iterator pair.
[in] | first | where to start erasing points from |
[in] | last | where to stop erasing points from |
Definition at line 567 of file point_cloud.h.
|
inline |
Erase a point in the cloud.
[in] | position | what data point to erase |
Definition at line 552 of file point_cloud.h.
Referenced by pcl::common::deleteCols(), and pcl::common::deleteRows().
|
inline |
Definition at line 458 of file point_cloud.h.
|
inline |
Definition at line 457 of file point_cloud.h.
Referenced by pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getEdgeIndex(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getFaceIndex(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getHalfEdgeIndex(), and pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::getVertexIndex().
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition at line 377 of file point_cloud.h.
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition at line 388 of file point_cloud.h.
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
[in] | dim | the number of dimensions to consider for each point |
[in] | stride | the number of values in each point (will be the number of values that separate two of the columns) |
[in] | offset | the number of dimensions to skip from the beginning of each point (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point) |
Definition at line 339 of file point_cloud.h.
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.
[in] | dim | the number of dimensions to consider for each point |
[in] | stride | the number of values in each point (will be the number of values that separate two of the columns) |
[in] | offset | the number of dimensions to skip from the beginning of each point (stride = offset + dim + x, where x is the number of dimensions to skip from the end of each point) |
Definition at line 363 of file point_cloud.h.
|
inline |
Insert a new point in the cloud, given an iterator.
[in] | position | where to insert the point |
[in] | pt | the point to insert |
Definition at line 495 of file point_cloud.h.
Referenced by pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), and pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing().
|
inline |
Insert a new range of points in the cloud, at a certain position.
[in] | position | where to insert the data |
[in] | first | where to start inserting the points from |
[in] | last | where to stop inserting the points from |
Definition at line 524 of file point_cloud.h.
|
inline |
Insert a new point in the cloud N times, given an iterator.
[in] | position | where to insert the point |
[in] | n | the number of times to insert the point |
[in] | pt | the point to insert |
Definition at line 510 of file point_cloud.h.
|
inline |
Return whether a dataset is organized (e.g., arranged in a structured grid).
Definition at line 318 of file point_cloud.h.
Referenced by pcl::visualization::ImageViewer::addMask(), pcl::HypothesisVerification< ModelT, SceneT >::addModels(), pcl::visualization::ImageViewer::addPlanarPolygon(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRectangle(), pcl::common::deleteCols(), pcl::common::duplicateColumns(), pcl::common::expandColumns(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::common::mirrorColumns(), and pcl::PCDGrabber< PointT >::publish().
|
inline |
Copy the cloud to the heap and return a smart pointer Note that deep copy is performed, so avoid using this function on non-empty clouds.
The changes of the returned cloud are not mirrored back to this one.
Definition at line 605 of file point_cloud.h.
Referenced by pcl::Edge< PointInT, PointOutT >::canny(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::estimateFeatures(), and pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection().
|
inline |
Obtain the point given by the (column, row) coordinates.
Only works on organized datasets (those that have height != 1).
[in] | column | the column coordinate |
[in] | row | the row coordinate |
Definition at line 309 of file point_cloud.h.
|
inline |
Obtain the point given by the (column, row) coordinates.
Only works on organized datasets (those that have height != 1).
[in] | column | the column coordinate |
[in] | row | the row coordinate |
Definition at line 298 of file point_cloud.h.
|
inline |
Add a point cloud to another cloud.
[in] | rhs | the cloud to add to the current cloud |
Definition at line 233 of file point_cloud.h.
|
inline |
Add a point cloud to the current cloud.
[in] | rhs | the cloud to add to the current cloud |
Definition at line 222 of file point_cloud.h.
|
inline |
Definition at line 454 of file point_cloud.h.
|
inline |
Definition at line 453 of file point_cloud.h.
|
protected |
|
inline |
Insert a new point in the cloud, at the end of the container.
[in] | pt | the point to insert |
Definition at line 467 of file point_cloud.h.
Referenced by pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::addData(), pcl::MovingLeastSquares< PointInT, PointOutT >::addProjectedPointNormal(), pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::approximatePolygon2D(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::MarchingCubes< PointNT >::createSurface(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::gpu::extractEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::VoxelGridCovariance< PointTarget >::getDisplayCloud(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), and pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track().
|
inline |
Definition at line 436 of file point_cloud.h.
Referenced by pcl::approximatePolygon2D(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::computeTracking(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::MarchingCubes< PointNT >::performReconstruction(), and pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack().
|
inline |
Resize the cloud.
[in] | n | the new cloud size |
Definition at line 442 of file point_cloud.h.
Referenced by pcl::approximatePolygon(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::cleanUp(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::DisparityMapConverter< PointDEM >::compute(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeRoberts(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::Morphology< PointT >::dilationBinary(), pcl::Morphology< PointT >::dilationGray(), pcl::Morphology< PointT >::erosionBinary(), pcl::Morphology< PointT >::erosionGray(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::Morphology< PointT >::intersectionBinary(), pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud(), pcl::search::Search< PointXYZRGB >::nearestKSearchT(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::Poisson< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ColorGradientModality< PointXYZT >::processInputData(), pcl::search::Search< PointXYZRGB >::radiusSearchT(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segment(), pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segmentAndRefine(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::Morphology< PointT >::unionBinary(), and pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::validateTransformation().
|
inline |
Definition at line 435 of file point_cloud.h.
Referenced by pcl::visualization::ImageViewer::addMask(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate(), pcl::recognition::TrimmedICP< pcl::PointXYZ, float >::align(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::approximatePolygon(), pcl::approximatePolygon2D(), pcl::calculatePolygonArea(), pcl::PlaneClipper3D< PointT >::clipPointCloud3D(), pcl::BoxClipper3D< PointT >::clipPointCloud3D(), pcl::computeCovarianceMatrix(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::computeMeanAndCovarianceMatrix(), pcl::computePointNormal(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::copyPointCloud(), pcl::LineRGBD< PointXYZT, PointRGBT >::createAndAddTemplate(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeRoberts(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::gpu::extractEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects(), pcl::getMeanPointDensity(), pcl::Morphology< PointT >::intersectionBinary(), pcl::LineRGBD< PointXYZT, PointRGBT >::loadTemplates(), pcl::search::Search< PointXYZRGB >::nearestKSearch(), pcl::search::Search< PointXYZRGB >::nearestKSearchT(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::PointCloud< pcl::RGB >::PointCloud(), pcl::io::pointCloudTovtkPolyData(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::search::Search< PointXYZRGB >::radiusSearch(), pcl::search::Search< PointXYZRGB >::radiusSearchT(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::setEdgeDataCloud(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::setFaceDataCloud(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::setHalfEdgeDataCloud(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setInputSource(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), pcl::poisson::Octree< Degree >::setTree(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::setVertexDataCloud(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::Morphology< PointT >::unionBinary(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::validateTransformation().
|
inline |
Swap a point cloud with another cloud.
[in,out] | rhs | point cloud to swap this with |
Definition at line 579 of file point_cloud.h.
Referenced by pcl::MarchingCubes< PointNT >::performReconstruction().
|
friend |
pcl::PCLHeader pcl::PointCloud< PointT >::header |
The point cloud header.
It contains information about the acquisition time.
Definition at line 394 of file point_cloud.h.
Referenced by pcl::Registration< PointSource, PointTarget >::align(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::Feature< PointInT, pcl::SHOT352 >::compute(), pcl::features::computeApproximateNormals(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::concatenateFields(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::gpu::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::extractLabeledEuclideanClusters(), pcl::Filter< pcl::PointXYZRGBL >::filter(), pcl::fromPCLPointCloud2(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCircle3D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelSphere< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointNT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::SegmentDifferences< PointT >::segment(), pcl::PointCloud< pcl::RGB >::swap(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), and pcl::transformPointCloudWithNormals().
std::uint32_t pcl::PointCloud< PointT >::height = 0 |
The point cloud height (if organized as an image-structure).
Definition at line 402 of file point_cloud.h.
Referenced by pcl::visualization::ImageViewer::addMask(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRectangle(), pcl::visualization::ImageViewer::addRGBImage(), pcl::Registration< PointSource, PointTarget >::align(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), pcl::FastBilateralFilter< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::SamplingSurfaceNormal< PointT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< pcl::PointXYZRGBL >::applyFilter(), pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::DisparityMapConverter< PointDEM >::compute(), pcl::Feature< PointInT, pcl::SHOT352 >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeFeature(), pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeFeature(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradientsSobel(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::GaussianKernel::convolve(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::common::deleteCols(), pcl::common::deleteRows(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeRoberts(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::Morphology< PointT >::dilationBinary(), pcl::Morphology< PointT >::dilationGray(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::downsample(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::Morphology< PointT >::erosionBinary(), pcl::Morphology< PointT >::erosionGray(), pcl::estimateProjectionMatrix(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::io::PointCloudImageExtractorWithScaling< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromNormalField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromRGBField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromLabelField< PointT >::extractImpl(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::occlusion_reasoning::filter(), pcl::fromPCLPointCloud2(), pcl::PCDWriter::generateHeader(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::Morphology< PointT >::intersectionBinary(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloudDepthAndRGBtoXYZRGBA(), pcl::PointCloudRGBtoI(), pcl::io::pointCloudTovtkStructuredGrid(), pcl::PointCloudXYZRGBAtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZI(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointXYZT >::processInputData(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCircle3D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelSphere< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode::queryBBIncludes(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointNT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< pcl::RGB >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::io::vtkPolyDataToPointCloud(), pcl::io::vtkStructuredGridToPointCloud(), and pcl::PCDWriter::writeASCII().
bool pcl::PointCloud< PointT >::is_dense = true |
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition at line 405 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::Registration< PointSource, PointTarget >::align(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::RandomSample< PointT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::RadiusOutlierRemoval< PointT >::applyFilter(), pcl::StatisticalOutlierRemoval< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::PassThrough< PointInT >::applyFilter(), pcl::ModelOutlierRemoval< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< pcl::PointXYZRGBL >::applyFilter(), pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::Feature< PointInT, pcl::SHOT352 >::compute(), pcl::compute3DCentroid(), pcl::computeCentroid(), pcl::computeCovarianceMatrix(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature(), pcl::SHOTLocalReferenceFrameEstimation< PointInT, ReferenceFrame >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeFeature(), pcl::SHOTEstimation< PointInT, PointNT, pcl::SHOT352, pcl::ReferenceFrame >::computeFeature(), pcl::SHOTColorEstimation< PointInT, PointNT, pcl::SHOT1344, pcl::ReferenceFrame >::computeFeature(), pcl::NormalEstimation< PointInT, PointNT >::computeFeature(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeatureFull(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeaturePart(), pcl::computeMeanAndCovarianceMatrix(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::fromPCLPointCloud2(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloudRGBA(), pcl::getMaxDistance(), pcl::getMinMax3D(), pcl::getPointCloudDifference(), pcl::getPointsInBox(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::operator<<(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::io::pointCloudTovtkPolyData(), pcl::ColorGradientModality< PointXYZT >::processInputData(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCircle3D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelSphere< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< pcl::RGB >::swap(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::visualization::PCLVisualizer::updatePointCloud(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::io::vtkPolyDataToPointCloud(), and pcl::io::vtkStructuredGridToPointCloud().
std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::PointCloud< PointT >::points |
The point data.
Definition at line 397 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram(), pcl::visualization::PCLPlotter::addFeatureHistogram(), pcl::visualization::PCLVisualizer::addPointCloudIntensityGradients(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPointCloudPrincipalCurvatures(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::visualization::ImageViewer::addRectangle(), pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate(), pcl::recognition::TrimmedICP< pcl::PointXYZ, float >::align(), pcl::Registration< PointSource, PointTarget >::align(), pcl::BilateralFilter< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::SamplingSurfaceNormal< PointT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::RadiusOutlierRemoval< PointT >::applyFilter(), pcl::StatisticalOutlierRemoval< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::PassThrough< PointInT >::applyFilter(), pcl::ModelOutlierRemoval< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< pcl::PointXYZRGBL >::applyFilter(), pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::octree::OctreePointCloudSearch< PointT, pcl::octree::OctreeContainerPointIndices, pcl::octree::OctreeContainerEmpty >::approxNearestSearch(), pcl::UnaryClassifier< PointT >::assignLabels(), pcl::RangeImageBorderExtractor::calculateBorderDirection(), pcl::RangeImageBorderExtractor::calculateMainPrincipalCurvature(), pcl::ESFEstimation< PointInT, PointOutT >::cleanup9(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::Feature< PointInT, pcl::SHOT352 >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateCovariances(), pcl::features::computeApproximateNormals(), pcl::occlusion_reasoning::ZBuffering< ModelT, SceneT >::computeDepthMap(), pcl::ESFEstimation< PointInT, PointOutT >::computeESF(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::computeFeature(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeFeature(), pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeFeature(), pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >::computeFeature(), pcl::GASDEstimation< PointInT, GASDSignature984 >::computeFeature(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimation< PointInT, PointNT, pcl::SHOT352, pcl::ReferenceFrame >::computeFeature(), pcl::SHOTColorEstimation< PointInT, PointNT, pcl::SHOT1344, pcl::ReferenceFrame >::computeFeature(), pcl::NormalEstimation< PointInT, PointNT >::computeFeature(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeaturePart(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeIntensitySpinImage(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradientsSobel(), pcl::MLSResult::computeMLSSurface(), pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computePairFeatures(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computePairFeatures(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computePointMomentInvariants(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computePointPFHSignature(), pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computePointPrincipalCurvatures(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::computePointSPFHSignature(), pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeRGBPairFeatures(), pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeRIFT(), pcl::CRHAlignment< PointT, nbins_ >::computeRollAngle(), pcl::computeRSD(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::visualization::ImageViewer::convertRGBCloudToUChar(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTsdfVectors(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::LineRGBD< PointXYZT, PointRGBT >::createAndAddTemplate(), pcl::visualization::createPolygon(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::registration::TransformationEstimationDQ< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationDualQuaternion< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSymmetricPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLSWeighted< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSVD< PointT, PointT, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, float >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::ProgressiveMorphologicalFilter< PointT >::extract(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::gpu::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::io::PointCloudImageExtractorWithScaling< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromNormalField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromRGBField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromLabelField< PointT >::extractImpl(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::extractLabeledEuclideanClusters(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::occlusion_reasoning::ZBuffering< ModelT, SceneT >::filter(), pcl::occlusion_reasoning::filter(), pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::filterNormalsWithHighCurvature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::filterNormalsWithHighCurvature(), pcl::UnaryClassifier< PointT >::findClusters(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects(), pcl::ApproximateVoxelGrid< PointT >::flush(), pcl::fromPCLPointCloud2(), pcl::PCDWriter::generateHeader(), pcl::getApproximateIndices(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloudRGBA(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getExistingData(), pcl::getFeaturePointCloud(), pcl::Registration< PointSource, PointTarget >::getFitnessScore(), pcl::getMaxDistance(), pcl::getMaxSegment(), pcl::getMeanPointDensity(), pcl::getMinMax3D(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::getPointCloudDifference(), pcl::getPointsInBox(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint(), pcl::isPointIn2DPolygon(), pcl::isXYPointIn2DXYPolygon(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::LineRGBD< PointXYZT, PointRGBT >::loadTemplates(), pcl::TextureMapping< PointInT >::mapMultipleTexturesToMeshUV(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::mismatchVector(), pcl::KdTree< FeatureT >::nearestKSearch(), pcl::search::Search< PointXYZRGB >::nearestKSearch(), pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::OptimizationFunctor::operator()(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::OptimizationFunctor::operator()(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::OptimizationFunctorWithIndices::operator()(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::OptimizationFunctorWithIndices::operator()(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::OptimizationFunctorWithIndices::operator()(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::Poisson< PointNT >::performReconstruction(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloud< pcl::RGB >::PointCloud(), pcl::PointCloudDepthAndRGBtoXYZRGBA(), pcl::PointCloudRGBtoI(), pcl::io::pointCloudTovtkPolyData(), pcl::PointCloudXYZRGBAtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZI(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCircle3D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelSphere< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::UnaryClassifier< PointT >::queryFeatureDistances(), pcl::octree::OctreePointCloudSearch< PointT, pcl::octree::OctreeContainerPointIndices, pcl::octree::OctreeContainerEmpty >::radiusSearch(), pcl::KdTree< FeatureT >::radiusSearch(), pcl::search::Search< PointXYZRGB >::radiusSearch(), pcl::VoxelGridCovariance< PointTarget >::radiusSearch(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::readRange(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::seededHueSegmentation(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segment(), pcl::OrganizedMultiPlaneSegmentation< pcl::PointXYZRGBA, pcl::Normal, pcl::Label >::segmentAndRefine(), pcl::CrfSegmentation< PointT >::segmentPoints(), pcl::MinCutSegmentation< PointT >::setBackgroundPoints(), pcl::PlanarPolygon< PointT >::setContour(), pcl::MinCutSegmentation< PointT >::setForegroundPoints(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), pcl::poisson::Octree< Degree >::setTree(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::shiftCloud(), pcl::TextureMapping< PointInT >::showOcclusions(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), pcl::TextureMapping< PointInT >::sortFacesByCamera(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::spatialGradient(), pcl::PointCloud< pcl::RGB >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram(), pcl::visualization::PCLVisualizer::updatePointCloud(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, pcl::Normal, float >::validateMatch(), pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::validateTransformation(), pcl::ESFEstimation< PointInT, PointOutT >::voxelize9(), pcl::io::vtkPolyDataToPointCloud(), pcl::io::vtkStructuredGridToPointCloud(), pcl::PCDWriter::writeASCII(), pcl::PCDWriter::writeBinary(), and pcl::PCDWriter::writeBinaryCompressed().
Eigen::Quaternionf pcl::PointCloud< PointT >::sensor_orientation_ = Eigen::Quaternionf::Identity () |
Sensor acquisition pose (rotation).
Definition at line 410 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeature(), pcl::copyPointCloud(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::Filter< pcl::PointXYZRGBL >::filter(), pcl::PCDWriter::generateHeader(), pcl::operator<<(), pcl::PCDGrabber< PointT >::operator[](), pcl::ImageGrabber< PointT >::operator[](), pcl::StereoGrabber< PointT >::publish(), pcl::PCDGrabber< PointT >::publish(), pcl::ImageGrabber< PointT >::publish(), pcl::IFSReader::read(), pcl::FileReader::read(), pcl::PLYReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< pcl::RGB >::swap(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().
Eigen::Vector4f pcl::PointCloud< PointT >::sensor_origin_ = Eigen::Vector4f::Zero () |
Sensor acquisition pose (origin/translation).
Definition at line 408 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeature(), pcl::copyPointCloud(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::Filter< pcl::PointXYZRGBL >::filter(), pcl::PCDWriter::generateHeader(), pcl::operator<<(), pcl::PCDGrabber< PointT >::operator[](), pcl::ImageGrabber< PointT >::operator[](), pcl::StereoGrabber< PointT >::publish(), pcl::PCDGrabber< PointT >::publish(), pcl::ImageGrabber< PointT >::publish(), pcl::IFSReader::read(), pcl::FileReader::read(), pcl::PLYReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< pcl::RGB >::swap(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().
std::uint32_t pcl::PointCloud< PointT >::width = 0 |
The point cloud width (if organized as an image-structure).
Definition at line 400 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRGBImage(), pcl::Registration< PointSource, PointTarget >::align(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), pcl::FastBilateralFilter< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::SamplingSurfaceNormal< PointT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< pcl::PointXYZRGBL >::applyFilter(), pcl::VoxelGridCovariance< PointTarget >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections(), pcl::RangeImageBorderExtractor::calculateBorderDirection(), pcl::RangeImageBorderExtractor::calculateMainPrincipalCurvature(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::RangeImageBorderExtractor::changeScoreAccordingToShadowBorderValue(), pcl::RangeImageBorderExtractor::checkIfMaximum(), pcl::RangeImageBorderExtractor::checkPotentialBorder(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::GASDEstimation< PointInT, GASDSignature984 >::compute(), pcl::DisparityMapConverter< PointDEM >::compute(), pcl::Feature< PointInT, pcl::SHOT352 >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeFeature(), pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeFeature(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeatureFull(), pcl::IntegralImageNormalEstimation< pcl::PointXYZRGBA, pcl::Normal >::computeFeaturePart(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointXYZT >::computeMaxColorGradientsSobel(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< pcl::RGB >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::GaussianKernel::convolve(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::common::deleteCols(), pcl::common::deleteRows(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeRoberts(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::Morphology< PointT >::dilationBinary(), pcl::Morphology< PointT >::dilationGray(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::downsample(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::Morphology< PointT >::erosionBinary(), pcl::Morphology< PointT >::erosionGray(), pcl::estimateProjectionMatrix(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::OrganizedEdgeBase< PointT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::io::PointCloudImageExtractorWithScaling< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromNormalField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromRGBField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromLabelField< PointT >::extractImpl(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::occlusion_reasoning::filter(), pcl::fromPCLPointCloud2(), pcl::PCDWriter::generateHeader(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloud(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::Morphology< PointT >::intersectionBinary(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::mismatchVector(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloudDepthAndRGBtoXYZRGBA(), pcl::PointCloudRGBtoI(), pcl::io::pointCloudTovtkStructuredGrid(), pcl::PointCloudXYZRGBAtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZI(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointXYZT >::processInputData(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCircle3D< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelSphere< pcl::PointXYZRGB >::projectPoints(), pcl::SampleConsensusModelCylinder< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< pcl::PointXYZRGB, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode::queryBBIncludes(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointNT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::DisparityMapConverter< PointDEM >::setImage(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::spatialGradient(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< pcl::RGB >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::RangeImageBorderExtractor::updatedScoreAccordingToNeighborValues(), pcl::io::vtkPolyDataToPointCloud(), pcl::io::vtkStructuredGridToPointCloud(), and pcl::PCDWriter::writeASCII().