Point Cloud Library (PCL)
1.8.1-dev
|
PointCloud represents the base class in PCL for storing collections of 3D points. More...
#include <pcl/common/projection_matrix.h>
Public Types | |
typedef PointT | PointType |
typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | VectorType |
typedef std::vector < PointCloud< PointT > , Eigen::aligned_allocator < PointCloud< PointT > > > | CloudVectorType |
typedef boost::shared_ptr < PointCloud< PointT > > | Ptr |
typedef boost::shared_ptr < const PointCloud< PointT > > | ConstPtr |
typedef PointT | value_type |
typedef PointT & | reference |
typedef const PointT & | const_reference |
typedef VectorType::difference_type | difference_type |
typedef VectorType::size_type | size_type |
typedef VectorType::iterator | iterator |
typedef VectorType::const_iterator | const_iterator |
Public Member Functions | |
PointCloud () | |
Default constructor. More... | |
PointCloud (PointCloud< PointT > &pc) | |
Copy constructor (needed by compilers such as Intel C++) More... | |
PointCloud (const PointCloud< PointT > &pc) | |
Copy constructor (needed by compilers such as Intel C++) More... | |
PointCloud (const PointCloud< PointT > &pc, const std::vector< int > &indices) | |
Copy constructor from point cloud subset. More... | |
PointCloud (uint32_t width_, uint32_t height_, const PointT &value_=PointT()) | |
Allocate constructor from point cloud subset. More... | |
virtual | ~PointCloud () |
Destructor. More... | |
PointCloud & | operator+= (const PointCloud &rhs) |
Add a point cloud to the current cloud. More... | |
const 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() (size_t column, size_t row) const |
Obtain the point given by the (column, row) coordinates. More... | |
PointT & | operator() (size_t column, 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 |
size_t | size () const |
void | reserve (size_t n) |
bool | empty () const |
void | resize (size_t n) |
Resize the cloud. More... | |
const PointT & | operator[] (size_t n) const |
PointT & | operator[] (size_t n) |
const PointT & | at (size_t n) const |
PointT & | at (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... | |
iterator | insert (iterator position, const PointT &pt) |
Insert a new point in the cloud, given an iterator. More... | |
void | insert (iterator position, 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... | |
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... | |
Public Attributes | |
pcl::PCLHeader | header |
The point cloud header. More... | |
std::vector< PointT, Eigen::aligned_allocator < PointT > > | points |
The point data. More... | |
uint32_t | width |
The point cloud width (if organized as an image-structure). More... | |
uint32_t | height |
The point cloud height (if organized as an image-structure). More... | |
bool | is_dense |
True if no points are invalid (e.g., have NaN or Inf values). More... | |
Eigen::Vector4f | sensor_origin_ |
Sensor acquisition pose (origin/translation). More... | |
Eigen::Quaternionf | sensor_orientation_ |
Sensor acquisition pose (rotation). More... | |
Protected Attributes | |
boost::shared_ptr< MsgFieldMap > | mapping_ |
Friends | |
boost::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 53 of file projection_matrix.h.
typedef std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > > pcl::PointCloud< PointT >::CloudVectorType |
Definition at line 427 of file point_cloud.h.
typedef VectorType::const_iterator pcl::PointCloud< PointT >::const_iterator |
Definition at line 441 of file point_cloud.h.
typedef const PointT& pcl::PointCloud< PointT >::const_reference |
Definition at line 435 of file point_cloud.h.
typedef boost::shared_ptr<const PointCloud<PointT> > pcl::PointCloud< PointT >::ConstPtr |
Definition at line 429 of file point_cloud.h.
typedef VectorType::difference_type pcl::PointCloud< PointT >::difference_type |
Definition at line 436 of file point_cloud.h.
typedef VectorType::iterator pcl::PointCloud< PointT >::iterator |
Definition at line 440 of file point_cloud.h.
typedef PointT pcl::PointCloud< PointT >::PointType |
Definition at line 425 of file point_cloud.h.
typedef boost::shared_ptr<PointCloud<PointT> > pcl::PointCloud< PointT >::Ptr |
Definition at line 428 of file point_cloud.h.
typedef PointT& pcl::PointCloud< PointT >::reference |
Definition at line 434 of file point_cloud.h.
typedef VectorType::size_type pcl::PointCloud< PointT >::size_type |
Definition at line 437 of file point_cloud.h.
typedef PointT pcl::PointCloud< PointT >::value_type |
Definition at line 433 of file point_cloud.h.
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::PointCloud< PointT >::VectorType |
Definition at line 426 of file point_cloud.h.
|
inline |
Default constructor.
Sets is_dense to true, width and height to 0, and the sensor_origin_ and sensor_orientation_ to identity.
Definition at line 179 of file point_cloud.h.
|
inline |
Copy constructor (needed by compilers such as Intel C++)
[in] | pc | the cloud to copy into this |
Definition at line 188 of file point_cloud.h.
|
inline |
Copy constructor (needed by compilers such as Intel C++)
[in] | pc | the cloud to copy into this |
Definition at line 199 of file point_cloud.h.
|
inline |
Copy constructor from point cloud subset.
[in] | pc | the cloud to copy into this |
[in] | indices | the subset to copy |
Definition at line 211 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 228 of file point_cloud.h.
|
inlinevirtual |
Destructor.
Definition at line 240 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 283 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 |
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 297 of file point_cloud.h.
|
inline |
Definition at line 468 of file point_cloud.h.
|
inline |
Definition at line 469 of file point_cloud.h.
|
inline |
Definition at line 472 of file point_cloud.h.
Referenced by pcl::VoxelGridCovariance< PointT >::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 473 of file point_cloud.h.
|
inline |
Definition at line 442 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::RangeImage::doZBuffer(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud(), pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::refineCorners(), pcl::LCCPSegmentation< PointT >::relabelCloud(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation().
|
inline |
Definition at line 444 of file point_cloud.h.
|
inline |
Removes all points in a cloud and sets the width and height to 0.
Definition at line 575 of file point_cloud.h.
Referenced by pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::approximatePolygon2D(), pcl::DisparityMapConverter< PointT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::gpu::extractEuclideanClusters(), pcl::VoxelGridCovariance< PointT >::getDisplayCloud(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), and pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi().
|
inline |
Definition at line 450 of file point_cloud.h.
Referenced by pcl::compute3DCentroid(), pcl::computeNDCentroid(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::PCDWriter::writeASCII(), and pcl::PCDWriter::writeBinary().
|
inline |
Definition at line 443 of file point_cloud.h.
Referenced by pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances(), pcl::common::deleteRows(), pcl::RangeImage::doZBuffer(), pcl::common::duplicateRows(), pcl::common::expandRows(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::SupervoxelClustering< PointT >::getLabeledVoxelCloud(), pcl::common::mirrorRows(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::refineCorners(), pcl::LCCPSegmentation< PointT >::relabelCloud(), and pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation().
|
inline |
Definition at line 445 of file point_cloud.h.
|
inline |
Erase a point in the cloud.
[in] | position | what data point to erase |
Definition at line 536 of file point_cloud.h.
Referenced by pcl::common::deleteCols(), and pcl::common::deleteRows().
|
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 551 of file point_cloud.h.
|
inline |
Definition at line 470 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 |
Definition at line 471 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 352 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 376 of file point_cloud.h.
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition at line 390 of file point_cloud.h.
|
inline |
Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
Definition at line 401 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 494 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 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 509 of file point_cloud.h.
|
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 523 of file point_cloud.h.
|
inline |
Return whether a dataset is organized (e.g., arranged in a structured grid).
Definition at line 331 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 588 of file point_cloud.h.
Referenced by pcl::Edge< PointInT, PointOutT >::canny(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::estimateFeatures(), pcl::PCA< PointT >::PCA(), 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 311 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 322 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 272 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 247 of file point_cloud.h.
|
inline |
Definition at line 466 of file point_cloud.h.
|
inline |
Definition at line 467 of file point_cloud.h.
|
inline |
Insert a new point in the cloud, at the end of the container.
[in] | pt | the point to insert |
Definition at line 480 of file point_cloud.h.
Referenced by pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::addData(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::approximatePolygon2D(), pcl::MovingLeastSquares< PointInT, PointOutT >::computeMLSPointNormal(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::MarchingCubes< PointNT >::createSurface(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::gpu::extractEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::VoxelGridCovariance< PointT >::getDisplayCloud(), pcl::MovingLeastSquares< PointInT, PointOutT >::performUpsampling(), pcl::PCA< PointT >::project(), pcl::PCA< PointT >::reconstruct(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), and pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track().
|
inline |
Definition at line 449 of file point_cloud.h.
Referenced by pcl::approximatePolygon2D(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::computeTracking(), pcl::TSDFVolume< VoxelT, WeightT >::convertToTsdfCloud(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), and pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack().
|
inline |
Resize the cloud.
[in] | n | the new cloud size |
Definition at line 455 of file point_cloud.h.
Referenced by pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::cleanUp(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::kernel< PointT >::derivativeXBackwardKernel(), pcl::kernel< PointT >::derivativeXCentralKernel(), pcl::kernel< PointT >::derivativeXForwardKernel(), pcl::kernel< PointT >::derivativeYBackwardKernel(), pcl::kernel< PointT >::derivativeYCentralKernel(), pcl::kernel< PointT >::derivativeYForwardKernel(), 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::kernel< PointT >::gaussianKernel(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::Morphology< PointT >::intersectionBinary(), pcl::kernel< PointT >::loGKernel(), pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud(), pcl::search::Search< PointXYZRGB >::nearestKSearchT(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::Poisson< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::kernel< PointT >::prewittKernelX(), pcl::kernel< PointT >::prewittKernelY(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::PCA< PointT >::project(), 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::PCA< PointT >::reconstruct(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseNoble(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::kernel< PointT >::robertsKernelX(), pcl::kernel< PointT >::robertsKernelY(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), pcl::kernel< PointT >::sobelKernelX(), pcl::kernel< PointT >::sobelKernelY(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::structuringElementCircular(), pcl::Morphology< PointT >::structuringElementRectangle(), pcl::Morphology< PointT >::subtractionBinary(), pcl::Morphology< PointT >::unionBinary(), and pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::validateTransformation().
|
inline |
Definition at line 448 of file point_cloud.h.
Referenced by pcl::visualization::ImageViewer::addMask(), pcl::visualization::ImageViewer::addPlanarPolygon(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::LineRGBD< PointXYZT, PointRGBT >::addTemplate(), pcl::recognition::TrimmedICP< pcl::pcl::PointXYZ, float >::align(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::approximatePolygon(), pcl::approximatePolygon2D(), pcl::calculatePolygonArea(), pcl::PlaneClipper3D< PointT >::clipPointCloud3D(), pcl::BoxClipper3D< PointT >::clipPointCloud3D(), pcl::compute3DCentroid(), pcl::computeCentroid(), pcl::computeCovarianceMatrix(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeCovariances(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::computeFeature(), pcl::computeMeanAndCovarianceMatrix(), pcl::computeNDCentroid(), 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::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, 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::kernel< PointT >::gaussianKernel(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints(), pcl::getMeanPointDensity(), pcl::Morphology< PointT >::intersectionBinary(), pcl::LineRGBD< PointXYZT, PointRGBT >::loadTemplates(), pcl::kernel< PointT >::loGKernel(), pcl::search::Search< PointT >::nearestKSearch(), pcl::search::FlannSearch< PointT, FlannDistance >::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< ModelT >::PointCloud(), pcl::io::pointCloudTovtkPolyData(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::PCA< PointT >::project(), pcl::search::FlannSearch< PointT, FlannDistance >::radiusSearch(), pcl::search::Search< PointT >::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::PCA< PointT >::reconstruct(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::refineCorners(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi(), 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::SupervoxelClustering< PointT >::setInputCloud(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::setInputSource(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), pcl::geometry::MeshBase< QuadMesh< MeshTraitsT >, MeshTraitsT, QuadMeshTag >::setVertexDataCloud(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::structuringElementRectangle(), pcl::Morphology< PointT >::subtractionBinary(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::transformCloud(), pcl::Morphology< PointT >::unionBinary(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), and pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation().
|
inline |
Swap a point cloud with another cloud.
[in,out] | rhs | point cloud to swap this with |
Definition at line 563 of file point_cloud.h.
|
friend |
pcl::PCLHeader pcl::PointCloud< PointT >::header |
The point cloud header.
It contains information about the acquisition time.
Definition at line 407 of file point_cloud.h.
Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::align(), pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::ESFEstimation< PointInT, PointOutT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::features::computeApproximateNormals(), pcl::concatenateFields(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::extractEuclideanClusters(), pcl::extractLabeledEuclideanClusters(), pcl::Filter< pcl::PointXYZRGBL >::filter(), pcl::fromPCLPointCloud2(), pcl::getPointCloudDifference(), pcl::PointCloud< ModelT >::operator+=(), 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< PointT >::projectPoints(), pcl::SampleConsensusModelCircle3D< PointT >::projectPoints(), pcl::SampleConsensusModelSphere< PointT >::projectPoints(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< PointT, PointNT >::projectPoints(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::SegmentDifferences< PointT >::segment(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), and pcl::transformPointCloudWithNormals().
uint32_t pcl::PointCloud< PointT >::height |
The point cloud height (if organized as an image-structure).
Definition at line 415 of file point_cloud.h.
Referenced by pcl::visualization::ImageViewer::addMask(), pcl::visualization::ImageViewer::addPlanarPolygon(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRectangle(), pcl::visualization::ImageViewer::addRGBImage(), pcl::Registration< PointSource, PointTarget, Scalar >::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::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::ESFEstimation< PointInT, PointOutT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::ESFEstimation< PointInT, PointOutT >::computeFeature(), 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< PointInT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradientsSobel(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), 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::kernel< PointT >::derivativeXBackwardKernel(), pcl::kernel< PointT >::derivativeXCentralKernel(), pcl::kernel< PointT >::derivativeXForwardKernel(), pcl::kernel< PointT >::derivativeYBackwardKernel(), pcl::kernel< PointT >::derivativeYCentralKernel(), pcl::kernel< PointT >::derivativeYForwardKernel(), 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::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::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::kernel< PointT >::gaussianKernel(), pcl::PCDWriter::generateHeader(), pcl::gpu::DataSource::generateSurface(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::getPointCloudDifference(), 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::kernel< PointT >::loGKernel(), 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::kernel< PointT >::prewittKernelX(), pcl::kernel< PointT >::prewittKernelY(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< PointT >::projectPoints(), pcl::SampleConsensusModelCircle3D< PointT >::projectPoints(), pcl::SampleConsensusModelSphere< PointT >::projectPoints(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< PointT, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::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< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseCurvature(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseNoble(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::kernel< PointT >::robertsKernelX(), pcl::kernel< PointT >::robertsKernelY(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::kernel< PointT >::sobelKernelX(), pcl::kernel< PointT >::sobelKernelY(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::structuringElementCircular(), pcl::Morphology< PointT >::structuringElementRectangle(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< ModelT >::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 if no points are invalid (e.g., have NaN or Inf values).
Definition at line 418 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::Registration< PointSource, PointTarget, Scalar >::align(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::RandomSample< PointT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::RadiusOutlierRemoval< PointT >::applyFilter(), pcl::StatisticalOutlierRemoval< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::PassThrough< PointT >::applyFilter(), pcl::ModelOutlierRemoval< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::ESFEstimation< PointInT, PointOutT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::compute3DCentroid(), pcl::computeCentroid(), pcl::computeCovarianceMatrix(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature(), pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >::computeFeature(), pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature(), pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeFeature(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computeFeature(), pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::NormalEstimation< PointInT, PointOutT >::computeFeature(), pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computeFeatureFull(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computeFeaturePart(), pcl::computeMeanAndCovarianceMatrix(), 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::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::AgastKeypoint2D< PointInT, PointOutT >::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::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::getMaxDistance(), pcl::getMinMax3D(), pcl::getPointCloudDifference(), pcl::getPointsInBox(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::search::FlannSearch< PointT, FlannDistance >::nearestKSearch(), pcl::PointCloud< ModelT >::operator+=(), pcl::operator<<(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::io::pointCloudTovtkPolyData(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::PCA< PointT >::project(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< PointT >::projectPoints(), pcl::SampleConsensusModelCircle3D< PointT >::projectPoints(), pcl::SampleConsensusModelSphere< PointT >::projectPoints(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< PointT, PointNT >::projectPoints(), pcl::search::FlannSearch< PointT, FlannDistance >::radiusSearch(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::PCA< PointT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::PointCloud< ModelT >::swap(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::visualization::PCLVisualizer::updatePointCloud(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::io::vtkPolyDataToPointCloud(), and pcl::io::vtkStructuredGridToPointCloud().
|
protected |
Definition at line 592 of file point_cloud.h.
Referenced by pcl::detail::getMapping().
std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::PointCloud< PointT >::points |
The point data.
Definition at line 410 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::pcl::PointXYZ, float >::align(), pcl::Registration< PointSource, PointTarget, Scalar >::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< PointT >::applyFilter(), pcl::ModelOutlierRemoval< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::approxNearestSearch(), pcl::UnaryClassifier< PointT >::assignLabels(), pcl::RangeImageBorderExtractor::calculateBorderDirection(), pcl::RangeImageBorderExtractor::calculateMainPrincipalCurvature(), pcl::ESFEstimation< PointInT, PointOutT >::cleanup9(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::ESFEstimation< PointInT, PointOutT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::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::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature(), pcl::ESFEstimation< PointInT, PointOutT >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computeFeature(), pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::computeFeature(), pcl::GRSDEstimation< PointInT, PointNT, 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::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computeFeature(), pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::NormalEstimation< PointInT, PointOutT >::computeFeature(), pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computeFeaturePart(), pcl::IntensitySpinEstimation< PointInT, PointOutT >::computeIntensitySpinImage(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradientsSobel(), 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::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeRGBPairFeatures(), pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeRIFT(), pcl::CRHAlignment< PointT, nbins_ >::computeRollAngle(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), 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::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::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::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLSWeighted< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSVD< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::extractEuclideanClusters(), pcl::io::PointCloudImageExtractorWithScaling< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromNormalField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromRGBField< PointT >::extractImpl(), pcl::io::PointCloudImageExtractorFromLabelField< PointT >::extractImpl(), 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::gpu::DataSource::findKNNeghbors(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects(), pcl::gpu::DataSource::findRadiusNeghbors(), pcl::ApproximateVoxelGrid< PointT >::flush(), pcl::fromPCLPointCloud2(), pcl::gpu::DataSource::generateColor(), pcl::PCDWriter::generateHeader(), pcl::gpu::DataSource::generateIndices(), pcl::gpu::DataSource::generateSurface(), pcl::getApproximateIndices(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::kinfuLS::WorldModel< PointT >::getExistingData(), pcl::getFeaturePointCloud(), pcl::Registration< PointSource, PointTarget, Scalar >::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< PointT >::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::PointCloud< ModelT >::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< ModelT >::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< PointT >::projectPoints(), pcl::SampleConsensusModelCircle3D< PointT >::projectPoints(), pcl::SampleConsensusModelSphere< PointT >::projectPoints(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< PointT, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::UnaryClassifier< PointT >::queryFeatureDistances(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::radiusSearch(), pcl::KdTree< FeatureT >::radiusSearch(), pcl::search::Search< PointT >::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::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::refineCorners(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseCurvature(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi(), pcl::seededHueSegmentation(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine(), pcl::CrfSegmentation< PointT >::segmentPoints(), pcl::PlanarPolygon< PointT >::setContour(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::setPointsToTrack(), 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< ModelT >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), 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, NormalT, Scalar >::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_ |
Sensor acquisition pose (rotation).
Definition at line 423 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< PointInT, PointOutT >::computeFeature(), pcl::copyPointCloud(), 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::PCDReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::PointCloud< ModelT >::swap(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().
Eigen::Vector4f pcl::PointCloud< PointT >::sensor_origin_ |
Sensor acquisition pose (origin/translation).
Definition at line 421 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< PointInT, PointOutT >::computeFeature(), pcl::copyPointCloud(), 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::PCDReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::PointCloud< ModelT >::swap(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().
uint32_t pcl::PointCloud< PointT >::width |
The point cloud width (if organized as an image-structure).
Definition at line 413 of file point_cloud.h.
Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRGBImage(), pcl::Registration< PointSource, PointTarget, Scalar >::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::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::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::ESFEstimation< PointInT, PointOutT >::compute(), pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::VFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::ESFEstimation< PointInT, PointOutT >::computeFeature(), 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< PointInT, PointOutT >::computeFeatureFull(), pcl::IntegralImageNormalEstimation< PointInT, PointOutT >::computeFeaturePart(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradientsSobel(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::computeRFAndShapeDistribution(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), 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::kernel< PointT >::derivativeXBackwardKernel(), pcl::kernel< PointT >::derivativeXCentralKernel(), pcl::kernel< PointT >::derivativeXForwardKernel(), pcl::kernel< PointT >::derivativeYBackwardKernel(), pcl::kernel< PointT >::derivativeYCentralKernel(), pcl::kernel< PointT >::derivativeYForwardKernel(), 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::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::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::kernel< PointT >::gaussianKernel(), pcl::PCDWriter::generateHeader(), pcl::gpu::DataSource::generateSurface(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::getPointCloudDifference(), 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::kernel< PointT >::loGKernel(), 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::kernel< PointT >::prewittKernelX(), pcl::kernel< PointT >::prewittKernelY(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::SampleConsensusModelLine< PointT >::projectPoints(), pcl::SampleConsensusModelStick< PointT >::projectPoints(), pcl::SampleConsensusModelCircle2D< PointT >::projectPoints(), pcl::SampleConsensusModelCircle3D< PointT >::projectPoints(), pcl::SampleConsensusModelSphere< PointT >::projectPoints(), pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPoints(), pcl::SampleConsensusModelPlane< PointT >::projectPoints(), pcl::SampleConsensusModelCone< PointT, PointNT >::projectPoints(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::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< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseCurvature(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseHarris(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseHarris(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseLowe(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseLowe(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseNoble(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseNoble(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >::responseTomasi(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::responseTomasi(), pcl::kernel< PointT >::robertsKernelX(), pcl::kernel< PointT >::robertsKernelY(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::DisparityMapConverter< PointT >::setImage(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::kernel< PointT >::sobelKernelX(), pcl::kernel< PointT >::sobelKernelY(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::spatialGradient(), pcl::Morphology< PointT >::structuringElementCircular(), pcl::Morphology< PointT >::structuringElementRectangle(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< ModelT >::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().