Point Cloud Library (PCL) 1.15.1
Loading...
Searching...
No Matches
pcl::PointCloud< PointT > Class Template Reference

PointCloud represents the base class in PCL for storing collections of 3D points. More...

#include <pcl/point_cloud.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
using reverse_iterator = typename VectorType::reverse_iterator
using const_reverse_iterator = typename VectorType::const_reverse_iterator

Public Member Functions

 PointCloud ()=default
 Default constructor.
 PointCloud (const PointCloud< PointT > &pc, const Indices &indices)
 Copy constructor from point cloud subset.
 PointCloud (std::uint32_t width_, std::uint32_t height_, const PointT &value_=PointT())
 Allocate constructor from point cloud subset.
PointCloudoperator+= (const PointCloud &rhs)
 Add a point cloud to the current cloud.
PointCloud operator+ (const PointCloud &rhs)
 Add a point cloud to another cloud.
const PointT & at (int column, int row) const
 Obtain the point given by the (column, row) coordinates.
PointT & at (int column, int row)
 Obtain the point given by the (column, row) coordinates.
const PointT & operator() (std::size_t column, std::size_t row) const
 Obtain the point given by the (column, row) coordinates.
PointT & operator() (std::size_t column, std::size_t row)
 Obtain the point given by the (column, row) coordinates.
bool isOrganized () const
 Return whether a dataset is organized (e.g., arranged in a structured grid).
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.
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.
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap ()
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > getMatrixXfMap () const
iterator begin () noexcept
iterator end () noexcept
const_iterator begin () const noexcept
const_iterator end () const noexcept
const_iterator cbegin () const noexcept
const_iterator cend () const noexcept
reverse_iterator rbegin () noexcept
reverse_iterator rend () noexcept
const_reverse_iterator rbegin () const noexcept
const_reverse_iterator rend () const noexcept
const_reverse_iterator crbegin () const noexcept
const_reverse_iterator crend () const noexcept
std::size_t size () const
index_t max_size () const noexcept
void reserve (std::size_t n)
bool empty () const
PointT * data () noexcept
const PointT * data () const noexcept
void resize (std::size_t count)
 Resizes the container to contain count elements.
void resize (uindex_t new_width, uindex_t new_height)
 Resizes the container to contain new_width * new_height elements.
void resize (index_t count, const PointT &value)
 Resizes the container to contain count elements.
void resize (index_t new_width, index_t new_height, const PointT &value)
 Resizes the container to contain count elements.
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 assign (index_t count, const PointT &value)
 Replaces the points with count copies of value.
void assign (index_t new_width, index_t new_height, const PointT &value)
 Replaces the points with new_width * new_height copies of value.
template<class InputIterator>
void assign (InputIterator first, InputIterator last)
 Replaces the points with copies of those in the range [first, last).
template<class InputIterator>
void assign (InputIterator first, InputIterator last, index_t new_width)
 Replaces the points with copies of those in the range [first, last).
void assign (std::initializer_list< PointT > ilist)
 Replaces the points with the elements from the initializer list ilist.
void assign (std::initializer_list< PointT > ilist, index_t new_width)
 Replaces the points with the elements from the initializer list ilist.
void push_back (const PointT &pt)
 Insert a new point in the cloud, at the end of the container.
void transient_push_back (const PointT &pt)
 Insert a new point in the cloud, at the end of the container.
template<class... Args>
reference emplace_back (Args &&...args)
 Emplace a new point in the cloud, at the end of the container.
template<class... Args>
reference transient_emplace_back (Args &&...args)
 Emplace a new point in the cloud, at the end of the container.
iterator insert (iterator position, const PointT &pt)
 Insert a new point in the cloud, given an iterator.
iterator transient_insert (iterator position, const PointT &pt)
 Insert a new point in the cloud, given an iterator.
void insert (iterator position, std::size_t n, const PointT &pt)
 Insert a new point in the cloud N times, given an iterator.
void transient_insert (iterator position, std::size_t n, const PointT &pt)
 Insert a new point in the cloud N times, given an iterator.
template<class InputIterator>
void insert (iterator position, InputIterator first, InputIterator last)
 Insert a new range of points in the cloud, at a certain position.
template<class InputIterator>
void transient_insert (iterator position, InputIterator first, InputIterator last)
 Insert a new range of points in the cloud, at a certain position.
template<class... Args>
iterator emplace (iterator position, Args &&...args)
 Emplace a new point in the cloud, given an iterator.
template<class... Args>
iterator transient_emplace (iterator position, Args &&...args)
 Emplace a new point in the cloud, given an iterator.
iterator erase (iterator position)
 Erase a point in the cloud.
iterator transient_erase (iterator position)
 Erase a point in the cloud.
iterator erase (iterator first, iterator last)
 Erase a set of points given by a (first, last) iterator pair.
iterator transient_erase (iterator first, iterator last)
 Erase a set of points given by a (first, last) iterator pair.
void swap (PointCloud< PointT > &rhs)
 Swap a point cloud with another cloud.
void clear ()
 Removes all points in a cloud and sets the width and height to 0.
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.

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.
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
 The point data.
std::uint32_t width = 0
 The point cloud width (if organized as an image-structure).
std::uint32_t height = 0
 The point cloud height (if organized as an image-structure).
bool is_dense = true
 True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Eigen::Vector4f sensor_origin_ = Eigen::Vector4f::Zero ()
 Sensor acquisition pose (origin/translation).
Eigen::Quaternionf sensor_orientation_ = Eigen::Quaternionf::Identity ()
 Sensor acquisition pose (rotation).

Detailed Description

template<typename PointT>
class pcl::PointCloud< PointT >

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:

cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
cloud.push_back (pcl::PointXYZ (rand (), rand (), rand ()));
PointCloud represents the base class in PCL for storing collections of 3D points.
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
A point structure representing Euclidean xyz coordinates.

The PointCloud class contains the following elements:

  • width - specifies the width of the point cloud dataset in the number of points. WIDTH has two meanings:
    • it can specify the total number of points in the cloud (equal with POINTS see below) for unorganized datasets;
    • it can specify the width (total number of points in a row) of an organized point cloud dataset. Mandatory.
  • height - specifies the height of the point cloud dataset in the number of points. HEIGHT has two meanings:
    • it can specify the height (total number of rows) of an organized point cloud dataset;
    • it is set to 1 for unorganized datasets (thus used to check whether a dataset is organized or not). Mandatory.
  • points - the data array where all points of type PointT are stored. Mandatory.
  • is_dense - specifies if all the data in points is finite (true), or whether it might contain Inf/NaN values (false). Mandatory.
  • sensor_origin_ - specifies the sensor acquisition pose (origin/translation). Optional.
  • sensor_orientation_ - specifies the sensor acquisition pose (rotation). Optional.
Author
Patrick Mihelich, Radu B. Rusu

Definition at line 173 of file point_cloud.h.

Member Typedef Documentation

◆ CloudVectorType

template<typename PointT>
using pcl::PointCloud< PointT >::CloudVectorType = std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > >

Definition at line 413 of file point_cloud.h.

◆ const_iterator

template<typename PointT>
using pcl::PointCloud< PointT >::const_iterator = typename VectorType::const_iterator

Definition at line 427 of file point_cloud.h.

◆ const_reference

template<typename PointT>
using pcl::PointCloud< PointT >::const_reference = const PointT&

Definition at line 421 of file point_cloud.h.

◆ const_reverse_iterator

template<typename PointT>
using pcl::PointCloud< PointT >::const_reverse_iterator = typename VectorType::const_reverse_iterator

Definition at line 429 of file point_cloud.h.

◆ ConstPtr

template<typename PointT>
using pcl::PointCloud< PointT >::ConstPtr = shared_ptr<const PointCloud<PointT> >

Definition at line 415 of file point_cloud.h.

◆ difference_type

template<typename PointT>
using pcl::PointCloud< PointT >::difference_type = typename VectorType::difference_type

Definition at line 422 of file point_cloud.h.

◆ iterator

template<typename PointT>
using pcl::PointCloud< PointT >::iterator = typename VectorType::iterator

Definition at line 426 of file point_cloud.h.

◆ PointType

template<typename PointT>
using pcl::PointCloud< PointT >::PointType = PointT

Definition at line 411 of file point_cloud.h.

◆ Ptr

template<typename PointT>
using pcl::PointCloud< PointT >::Ptr = shared_ptr<PointCloud<PointT> >

Definition at line 414 of file point_cloud.h.

◆ reference

template<typename PointT>
using pcl::PointCloud< PointT >::reference = PointT&

Definition at line 420 of file point_cloud.h.

◆ reverse_iterator

template<typename PointT>
using pcl::PointCloud< PointT >::reverse_iterator = typename VectorType::reverse_iterator

Definition at line 428 of file point_cloud.h.

◆ size_type

template<typename PointT>
using pcl::PointCloud< PointT >::size_type = typename VectorType::size_type

Definition at line 423 of file point_cloud.h.

◆ value_type

template<typename PointT>
using pcl::PointCloud< PointT >::value_type = PointT

Definition at line 419 of file point_cloud.h.

◆ VectorType

template<typename PointT>
using pcl::PointCloud< PointT >::VectorType = std::vector<PointT, Eigen::aligned_allocator<PointT> >

Definition at line 412 of file point_cloud.h.

Constructor & Destructor Documentation

◆ PointCloud() [1/3]

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( )
default

Default constructor.

Sets is_dense to true, width and height to 0, and the sensor_origin_ and sensor_orientation_ to identity.

◆ PointCloud() [2/3]

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( const PointCloud< PointT > & pc,
const Indices & indices )
inline

Copy constructor from point cloud subset.

Parameters
[in]pcthe cloud to copy into this
[in]indicesthe subset to copy

Definition at line 186 of file point_cloud.h.

◆ PointCloud() [3/3]

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( std::uint32_t width_,
std::uint32_t height_,
const PointT & value_ = PointT () )
inline

Allocate constructor from point cloud subset.

Parameters
[in]width_the cloud width
[in]height_the cloud height
[in]value_default value

Definition at line 202 of file point_cloud.h.

Member Function Documentation

◆ assign() [1/6]

template<typename PointT>
void pcl::PointCloud< PointT >::assign ( index_t count,
const PointT & value )
inline

Replaces the points with count copies of value.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]countnew size of the point cloud
[in]valuevalue each point of the cloud should have

Definition at line 549 of file point_cloud.h.

Referenced by pcl::PointCloud< PointInT >::assign(), pcl::PointCloud< PointInT >::assign(), pcl::transformPointCloud(), pcl::transformPointCloud(), and pcl::transformPointCloudWithNormals().

◆ assign() [2/6]

template<typename PointT>
void pcl::PointCloud< PointT >::assign ( index_t new_width,
index_t new_height,
const PointT & value )
inline

Replaces the points with new_width * new_height copies of value.

Parameters
[in]new_widthnew width of the point cloud
[in]new_heightnew height of the point cloud
[in]valuevalue each point of the cloud should have

Definition at line 563 of file point_cloud.h.

◆ assign() [3/6]

template<typename PointT>
template<class InputIterator>
void pcl::PointCloud< PointT >::assign ( InputIterator first,
InputIterator last )
inline

Replaces the points with copies of those in the range [first, last).

The behavior is undefined if either argument is an iterator into *this

Note
This breaks the organized structure of the cloud by setting the height to 1!

Definition at line 579 of file point_cloud.h.

◆ assign() [4/6]

template<typename PointT>
template<class InputIterator>
void pcl::PointCloud< PointT >::assign ( InputIterator first,
InputIterator last,
index_t new_width )
inline

Replaces the points with copies of those in the range [first, last).

The behavior is undefined if either argument is an iterator into *this

Note
This calculates the height based on size and width provided. This means the assignment happens even if the size is not perfectly divisible by width
Parameters
[in]first,lastthe range from which the points are copied
[in]new_widthnew width of the point cloud

Definition at line 597 of file point_cloud.h.

◆ assign() [5/6]

template<typename PointT>
void pcl::PointCloud< PointT >::assign ( std::initializer_list< PointT > ilist)
inline

Replaces the points with the elements from the initializer list ilist.

Note
This breaks the organized structure of the cloud by setting the height to 1!

Definition at line 624 of file point_cloud.h.

◆ assign() [6/6]

template<typename PointT>
void pcl::PointCloud< PointT >::assign ( std::initializer_list< PointT > ilist,
index_t new_width )
inline

Replaces the points with the elements from the initializer list ilist.

Note
This calculates the height based on size and width provided. This means the assignment happens even if the size is not perfectly divisible by width
Parameters
[in]ilistinitializer list from which the points are copied
[in]new_widthnew width of the point cloud

Definition at line 639 of file point_cloud.h.

◆ at() [1/4]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::at ( int column,
int row )
inline

Obtain the point given by the (column, row) coordinates.

Only works on organized datasets (those that have height != 1).

Parameters
[in]columnthe column coordinate
[in]rowthe row coordinate

Definition at line 277 of file point_cloud.h.

◆ at() [2/4]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::at ( int column,
int row ) const
inline

Obtain the point given by the (column, row) coordinates.

Only works on organized datasets (those that have height != 1).

Parameters
[in]columnthe column coordinate
[in]rowthe row coordinate

Definition at line 263 of file point_cloud.h.

Referenced by pcl::filters::Pyramid< PointT >::compute(), pcl::occlusion_reasoning::filter(), pcl::occlusion_reasoning::filter(), pcl::occlusion_reasoning::getOccludedCloud(), and pcl::PointCloudDepthAndRGBtoXYZRGBA().

◆ at() [3/4]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::at ( std::size_t n)
inline

Definition at line 535 of file point_cloud.h.

◆ at() [4/4]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::at ( std::size_t n) const
inline

Definition at line 534 of file point_cloud.h.

◆ back() [1/2]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::back ( )
inline

Definition at line 539 of file point_cloud.h.

◆ back() [2/2]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::back ( ) const
inline

Definition at line 538 of file point_cloud.h.

◆ begin() [1/2]

template<typename PointT>
const_iterator pcl::PointCloud< PointT >::begin ( ) const
inlinenoexcept

Definition at line 432 of file point_cloud.h.

◆ begin() [2/2]

◆ cbegin()

◆ cend()

◆ clear()

◆ concatenate() [1/2]

template<typename PointT>
bool pcl::PointCloud< PointT >::concatenate ( const pcl::PointCloud< PointT > & cloud1,
const pcl::PointCloud< PointT > & cloud2,
pcl::PointCloud< PointT > & cloud_out )
inlinestatic

Definition at line 249 of file point_cloud.h.

◆ concatenate() [2/2]

template<typename PointT>
bool pcl::PointCloud< PointT >::concatenate ( pcl::PointCloud< PointT > & cloud1,
const pcl::PointCloud< PointT > & cloud2 )
inlinestatic

◆ crbegin()

template<typename PointT>
const_reverse_iterator pcl::PointCloud< PointT >::crbegin ( ) const
inlinenoexcept

Definition at line 440 of file point_cloud.h.

◆ crend()

template<typename PointT>
const_reverse_iterator pcl::PointCloud< PointT >::crend ( ) const
inlinenoexcept

Definition at line 441 of file point_cloud.h.

◆ data() [1/2]

template<typename PointT>
const PointT * pcl::PointCloud< PointT >::data ( ) const
inlinenoexcept

Definition at line 449 of file point_cloud.h.

◆ data() [2/2]

template<typename PointT>
PointT * pcl::PointCloud< PointT >::data ( )
inlinenoexcept

◆ emplace()

template<typename PointT>
template<class... Args>
iterator pcl::PointCloud< PointT >::emplace ( iterator position,
Args &&... args )
inline

Emplace a new point in the cloud, given an iterator.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]positioniterator before which the point will be emplaced
[in]argsthe parameters to forward to the point to construct
Returns
returns the new position iterator

Definition at line 794 of file point_cloud.h.

◆ emplace_back()

template<typename PointT>
template<class... Args>
reference pcl::PointCloud< PointT >::emplace_back ( Args &&... args)
inline

Emplace a new point in the cloud, at the end of the container.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]argsthe parameters to forward to the point to construct
Returns
reference to the emplaced point

Definition at line 687 of file point_cloud.h.

Referenced by pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures().

◆ empty()

◆ end() [1/2]

template<typename PointT>
const_iterator pcl::PointCloud< PointT >::end ( ) const
inlinenoexcept

Definition at line 433 of file point_cloud.h.

◆ end() [2/2]

◆ erase() [1/2]

template<typename PointT>
iterator pcl::PointCloud< PointT >::erase ( iterator first,
iterator last )
inline

Erase a set of points given by a (first, last) iterator pair.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]firstwhere to start erasing points from
[in]lastwhere to stop erasing points from
Returns
returns the new position iterator

Definition at line 848 of file point_cloud.h.

◆ erase() [2/2]

template<typename PointT>
iterator pcl::PointCloud< PointT >::erase ( iterator position)
inline

Erase a point in the cloud.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]positionwhat data point to erase
Returns
returns the new position iterator

Definition at line 821 of file point_cloud.h.

Referenced by pcl::common::deleteCols(), and pcl::common::deleteRows().

◆ front() [1/2]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::front ( )
inline

Definition at line 537 of file point_cloud.h.

◆ front() [2/2]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::front ( ) const
inline

Definition at line 536 of file point_cloud.h.

◆ getMatrixXfMap() [1/4]

template<typename PointT>
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud< PointT >::getMatrixXfMap ( )
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Note
This method is for advanced users only! Use with care!
Attention
PointT types are most of the time aligned, so the offsets are not continuous!

Definition at line 375 of file point_cloud.h.

◆ getMatrixXfMap() [2/4]

template<typename PointT>
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud< PointT >::getMatrixXfMap ( ) const
inline

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Note
This method is for advanced users only! Use with care!
Attention
PointT types are most of the time aligned, so the offsets are not continuous!

Definition at line 387 of file point_cloud.h.

◆ getMatrixXfMap() [3/4]

template<typename PointT>
Eigen::Map< Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud< PointT >::getMatrixXfMap ( int dim,
int stride,
int offset )
inline

Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.

Note
This method is for advanced users only! Use with care!
Attention
Compile time flags used for Eigen might affect the dimension of the Eigen::Map returned. If Eigen is using row major storage, the matrix shape would be (number of Points X elements in a Point) else the matrix shape would be (elements in a Point X number of Points). Essentially,
  • Major direction: number of points in cloud
  • Minor direction: number of point dimensions By default, as of Eigen 3.3, Eigen uses Column major storage
Parameters
[in]dimthe number of dimensions to consider for each point
[in]stridethe number of values in each point (will be the number of values that separate two of the columns)
[in]offsetthe 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)
Note
for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
Attention
PointT types are most of the time aligned, so the offsets are not continuous!

Definition at line 334 of file point_cloud.h.

◆ getMatrixXfMap() [4/4]

template<typename PointT>
const Eigen::Map< const Eigen::MatrixXf, Eigen::Aligned, Eigen::OuterStride<> > pcl::PointCloud< PointT >::getMatrixXfMap ( int dim,
int stride,
int offset ) const
inline

Return an Eigen MatrixXf (assumes float values) mapped to the specified dimensions of the PointCloud.

Note
This method is for advanced users only! Use with care!
Attention
Compile time flags used for Eigen might affect the dimension of the Eigen::Map returned. If Eigen is using row major storage, the matrix shape would be (number of Points X elements in a Point) else the matrix shape would be (elements in a Point X number of Points). Essentially,
  • Major direction: number of points in cloud
  • Minor direction: number of point dimensions By default, as of Eigen 3.3, Eigen uses Column major storage
Parameters
[in]dimthe number of dimensions to consider for each point
[in]stridethe number of values in each point (will be the number of values that separate two of the columns)
[in]offsetthe 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)
Note
for getting only XYZ coordinates out of PointXYZ use dim=3, stride=4 and offset=0 due to the alignment.
Attention
PointT types are most of the time aligned, so the offsets are not continuous!

Definition at line 360 of file point_cloud.h.

◆ insert() [1/3]

template<typename PointT>
iterator pcl::PointCloud< PointT >::insert ( iterator position,
const PointT & pt )
inline

Insert a new point in the cloud, given an iterator.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]positionwhere to insert the point
[in]ptthe point to insert
Returns
returns the new position iterator

Definition at line 714 of file point_cloud.h.

Referenced by pcl::PointCloud< PointInT >::concatenate(), pcl::common::duplicateColumns(), pcl::common::duplicateRows(), pcl::common::expandColumns(), pcl::common::expandRows(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), and pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing().

◆ insert() [2/3]

template<typename PointT>
template<class InputIterator>
void pcl::PointCloud< PointT >::insert ( iterator position,
InputIterator first,
InputIterator last )
inline

Insert a new range of points in the cloud, at a certain position.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]positionwhere to insert the data
[in]firstwhere to start inserting the points from
[in]lastwhere to stop inserting the points from

Definition at line 768 of file point_cloud.h.

◆ insert() [3/3]

template<typename PointT>
void pcl::PointCloud< PointT >::insert ( iterator position,
std::size_t n,
const PointT & pt )
inline

Insert a new point in the cloud N times, given an iterator.

Note
This breaks the organized structure of the cloud by setting the height to 1!
Parameters
[in]positionwhere to insert the point
[in]nthe number of times to insert the point
[in]ptthe point to insert

Definition at line 742 of file point_cloud.h.

◆ isOrganized()

◆ makeShared()

template<typename PointT>
Ptr pcl::PointCloud< PointT >::makeShared ( ) const
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.

Returns
shared pointer to the copy of the cloud

Definition at line 899 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().

◆ max_size()

template<typename PointT>
index_t pcl::PointCloud< PointT >::max_size ( ) const
inlinenoexcept

Definition at line 445 of file point_cloud.h.

◆ operator()() [1/2]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::operator() ( std::size_t column,
std::size_t row )
inline

Obtain the point given by the (column, row) coordinates.

Only works on organized datasets (those that have height != 1).

Parameters
[in]columnthe column coordinate
[in]rowthe row coordinate

Definition at line 302 of file point_cloud.h.

◆ operator()() [2/2]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::operator() ( std::size_t column,
std::size_t row ) const
inline

Obtain the point given by the (column, row) coordinates.

Only works on organized datasets (those that have height != 1).

Parameters
[in]columnthe column coordinate
[in]rowthe row coordinate

Definition at line 291 of file point_cloud.h.

◆ operator+()

template<typename PointT>
PointCloud pcl::PointCloud< PointT >::operator+ ( const PointCloud< PointT > & rhs)
inline

Add a point cloud to another cloud.

Parameters
[in]rhsthe cloud to add to the current cloud
Returns
the new cloud as a concatenation of the current cloud and the new given cloud

Definition at line 226 of file point_cloud.h.

◆ operator+=()

template<typename PointT>
PointCloud & pcl::PointCloud< PointT >::operator+= ( const PointCloud< PointT > & rhs)
inline

Add a point cloud to the current cloud.

Parameters
[in]rhsthe cloud to add to the current cloud
Returns
the new cloud as a concatenation of the current cloud and the new given cloud

Definition at line 215 of file point_cloud.h.

◆ operator[]() [1/2]

template<typename PointT>
PointT & pcl::PointCloud< PointT >::operator[] ( std::size_t n)
inline

Definition at line 533 of file point_cloud.h.

◆ operator[]() [2/2]

template<typename PointT>
const PointT & pcl::PointCloud< PointT >::operator[] ( std::size_t n) const
inline

Definition at line 532 of file point_cloud.h.

◆ push_back()

template<typename PointT>
void pcl::PointCloud< PointT >::push_back ( const PointT & pt)
inline

◆ rbegin() [1/2]

template<typename PointT>
const_reverse_iterator pcl::PointCloud< PointT >::rbegin ( ) const
inlinenoexcept

Definition at line 438 of file point_cloud.h.

◆ rbegin() [2/2]

template<typename PointT>
reverse_iterator pcl::PointCloud< PointT >::rbegin ( )
inlinenoexcept

Definition at line 436 of file point_cloud.h.

◆ rend() [1/2]

template<typename PointT>
const_reverse_iterator pcl::PointCloud< PointT >::rend ( ) const
inlinenoexcept

Definition at line 439 of file point_cloud.h.

◆ rend() [2/2]

template<typename PointT>
reverse_iterator pcl::PointCloud< PointT >::rend ( )
inlinenoexcept

Definition at line 437 of file point_cloud.h.

◆ reserve()

◆ resize() [1/4]

template<typename PointT>
void pcl::PointCloud< PointT >::resize ( index_t count,
const PointT & value )
inline

Resizes the container to contain count elements.

  • If the current size is greater than count, the pointcloud is reduced to its first count elements
  • If the current size is less than count, additional copies of value are appended
    Note
    This potentially breaks the organized structure of the cloud by setting the height to 1 IFF width * height != count!
    Parameters
    [in]countnew size of the point cloud
    [in]valuethe value to initialize the new points with

Definition at line 503 of file point_cloud.h.

◆ resize() [2/4]

template<typename PointT>
void pcl::PointCloud< PointT >::resize ( index_t new_width,
index_t new_height,
const PointT & value )
inline

Resizes the container to contain count elements.

  • If the current size is greater then the requested size, the pointcloud is reduced to its first requested elements
  • If the current size is less then the requested size, additional default-inserted points are appended
    Parameters
    [in]new_widthnew width of the point cloud
    [in]new_heightnew height of the point cloud
    [in]valuethe value to initialize the new points with

Definition at line 524 of file point_cloud.h.

◆ resize() [3/4]

template<typename PointT>
void pcl::PointCloud< PointT >::resize ( std::size_t count)
inline

Resizes the container to contain count elements.

  • If the current size is greater than count, the pointcloud is reduced to its first count elements
  • If the current size is less than count, additional default-inserted points are appended
    Note
    This potentially breaks the organized structure of the cloud by setting the height to 1 IFF width * height != count!
    Parameters
    [in]countnew size of the point cloud

Definition at line 463 of file point_cloud.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::align(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >::computeFeature(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::concatenateFields(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::demeanPointCloud(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), 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::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::fromPCLPointCloud2(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::Morphology< PointT >::intersectionBinary(), pcl::isPointIn2DPolygon(), pcl::SupervoxelClustering< PointT >::makeSupervoxelNormalCloud(), pcl::search::Search< PointInT >::nearestKSearchT(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::Poisson< PointNT >::performReconstruction(), pcl::Poisson< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::search::Search< PointInT >::radiusSearchT(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::validateTransformation(), pcl::io::vtkPolyDataToPointCloud(), and pcl::io::vtkStructuredGridToPointCloud().

◆ resize() [4/4]

template<typename PointT>
void pcl::PointCloud< PointT >::resize ( uindex_t new_width,
uindex_t new_height )
inline

Resizes the container to contain new_width * new_height elements.

  • If the current size is greater than the requested size, the pointcloud is reduced to its first requested elements
  • If the current size is less then the requested size, additional default-inserted points are appended
    Parameters
    [in]new_widthnew width of the point cloud
    [in]new_heightnew height of the point cloud

Definition at line 483 of file point_cloud.h.

◆ size()

template<typename PointT>
std::size_t pcl::PointCloud< PointT >::size ( ) const
inline

Definition at line 444 of file point_cloud.h.

Referenced by pcl::visualization::PCLHistogramVisualizer::addFeatureHistogram(), pcl::visualization::PCLPlotter::addFeatureHistogram(), pcl::visualization::ImageViewer::addMask(), pcl::visualization::PCLVisualizer::addPointCloudIntensityGradients(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPointCloudPrincipalCurvatures(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::visualization::ImageViewer::addRectangle(), pcl::recognition::TrimmedICP< PointT, Scalar >::align(), pcl::applyMorphologicalOperator(), pcl::PointCloud< PointInT >::assign(), pcl::PointCloud< PointInT >::assign(), pcl::PointCloud< PointInT >::assign(), pcl::PointCloud< PointInT >::assign(), pcl::PointCloud< PointInT >::assign(), pcl::UnaryClassifier< PointT >::assignLabels(), pcl::calculatePolygonArea(), pcl::BoxClipper3D< PointT >::clipPointCloud3D(), pcl::PlaneClipper3D< PointT >::clipPointCloud3D(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::features::computeApproximateCovariances(), pcl::features::computeApproximateNormals(), pcl::computeCentroidAndOBB(), pcl::computeCovarianceMatrix(), pcl::computeCovarianceMatrix(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar >::computeCovariances(), pcl::ESFEstimation< PointInT, PointOutT >::computeESF(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::computeMeanAndCovarianceMatrix(), pcl::computeNDCentroid(), pcl::computePointNormal(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< PointInT >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTsdfVectors(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::detail::copyPointCloudMemcpy(), pcl::detail::copyPointCloudMemcpy(), pcl::visualization::createPolygon(), pcl::demeanPointCloud(), pcl::demeanPointCloud(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::PointCloud< PointInT >::emplace(), pcl::PointCloud< PointInT >::emplace_back(), pcl::PointCloud< PointInT >::erase(), pcl::PointCloud< PointInT >::erase(), pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimation3Point< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationDualQuaternion< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationDualQuaternion< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLSWeighted< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneLLSWeighted< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSVD< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSVD< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSymmetricPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::registration::TransformationEstimationSymmetricPointToPlaneLLS< PointSource, PointTarget, Scalar >::estimateRigidTransformation(), pcl::io::PointCloudImageExtractor< PointT >::extract(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::gpu::extractEuclideanClusters(), pcl::extractLabeledEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::occlusion_reasoning::filter(), pcl::occlusion_reasoning::filter(), pcl::occlusion_reasoning::ZBuffering< ModelT, SceneT >::filter(), pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::filterNormalsWithHighCurvature(), pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >::filterNormalsWithHighCurvature(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects(), pcl::PCDWriter::generateHeader(), pcl::getApproximateIndices(), pcl::getApproximateIndices(), pcl::UnaryClassifier< PointT >::getCloudWithLabel(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::getMaxDistance(), pcl::getMaxSegment(), pcl::getMeanPointDensity(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::getPointCloudDifference(), pcl::getPointsInBox(), pcl::PointCloud< PointInT >::insert(), pcl::PointCloud< PointInT >::insert(), pcl::PointCloud< PointInT >::insert(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::Morphology< PointT >::intersectionBinary(), pcl::isPointIn2DPolygon(), pcl::isXYPointIn2DXYPolygon(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::KdTree< PointInT >::nearestKSearch(), pcl::search::Search< PointInT >::nearestKSearchT(), pcl::operator<<(), pcl::operator<<(), pcl::MovingLeastSquares< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloud< PointInT >::PointCloud(), pcl::io::pointCloudTovtkPolyData(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::PointCloud< PointInT >::push_back(), pcl::UnaryClassifier< PointT >::queryFeatureDistances(), pcl::KdTree< PointInT >::radiusSearch(), pcl::search::Search< PointT >::radiusSearch(), pcl::search::Search< PointT >::radiusSearch(), pcl::search::Search< PointInT >::radiusSearchT(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::search::Search< WeightSACPointType >::Search(), pcl::seededHueSegmentation(), pcl::seededHueSegmentation(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::geometry::MeshBase< PolygonMesh< MeshTraitsT >, MeshTraitsT, PolygonMeshTag >::setEdgeDataCloud(), pcl::geometry::MeshBase< PolygonMesh< MeshTraitsT >, MeshTraitsT, PolygonMeshTag >::setFaceDataCloud(), pcl::geometry::MeshBase< PolygonMesh< MeshTraitsT >, MeshTraitsT, PolygonMeshTag >::setHalfEdgeDataCloud(), pcl::search::Search< WeightSACPointType >::setInputCloud(), pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar >::setInputSource(), pcl::poisson::Octree< Degree >::setTree(), pcl::geometry::MeshBase< PolygonMesh< MeshTraitsT >, MeshTraitsT, PolygonMeshTag >::setVertexDataCloud(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::visualization::PCLHistogramVisualizer::updateFeatureHistogram(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::validateTransformation(), pcl::io::vtkPolyDataToPointCloud(), pcl::PCDWriter::writeASCII(), pcl::PCDWriter::writeASCII(), pcl::PCDWriter::writeBinary(), and pcl::PCDWriter::writeBinaryCompressed().

◆ swap()

template<typename PointT>
void pcl::PointCloud< PointT >::swap ( PointCloud< PointT > & rhs)
inline

Swap a point cloud with another cloud.

Parameters
[in,out]rhspoint cloud to swap this with

Definition at line 873 of file point_cloud.h.

Referenced by pcl::applyMorphologicalOperator(), and pcl::MarchingCubes< PointNT >::performReconstruction().

◆ transient_emplace()

template<typename PointT>
template<class... Args>
iterator pcl::PointCloud< PointT >::transient_emplace ( iterator position,
Args &&... args )
inline

Emplace a new point in the cloud, given an iterator.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]positioniterator before which the point will be emplaced
[in]argsthe parameters to forward to the point to construct
Returns
returns the new position iterator

Definition at line 809 of file point_cloud.h.

◆ transient_emplace_back()

template<typename PointT>
template<class... Args>
reference pcl::PointCloud< PointT >::transient_emplace_back ( Args &&... args)
inline

Emplace a new point in the cloud, at the end of the container.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]argsthe parameters to forward to the point to construct
Returns
reference to the emplaced point

Definition at line 701 of file point_cloud.h.

◆ transient_erase() [1/2]

template<typename PointT>
iterator pcl::PointCloud< PointT >::transient_erase ( iterator first,
iterator last )
inline

Erase a set of points given by a (first, last) iterator pair.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]firstwhere to start erasing points from
[in]lastwhere to stop erasing points from
Returns
returns the new position iterator

Definition at line 863 of file point_cloud.h.

◆ transient_erase() [2/2]

template<typename PointT>
iterator pcl::PointCloud< PointT >::transient_erase ( iterator position)
inline

Erase a point in the cloud.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]positionwhat data point to erase
Returns
returns the new position iterator

Definition at line 835 of file point_cloud.h.

◆ transient_insert() [1/3]

template<typename PointT>
iterator pcl::PointCloud< PointT >::transient_insert ( iterator position,
const PointT & pt )
inline

Insert a new point in the cloud, given an iterator.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]positionwhere to insert the point
[in]ptthe point to insert
Returns
returns the new position iterator

Definition at line 729 of file point_cloud.h.

◆ transient_insert() [2/3]

template<typename PointT>
template<class InputIterator>
void pcl::PointCloud< PointT >::transient_insert ( iterator position,
InputIterator first,
InputIterator last )
inline

Insert a new range of points in the cloud, at a certain position.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]positionwhere to insert the data
[in]firstwhere to start inserting the points from
[in]lastwhere to stop inserting the points from

Definition at line 782 of file point_cloud.h.

◆ transient_insert() [3/3]

template<typename PointT>
void pcl::PointCloud< PointT >::transient_insert ( iterator position,
std::size_t n,
const PointT & pt )
inline

Insert a new point in the cloud N times, given an iterator.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]positionwhere to insert the point
[in]nthe number of times to insert the point
[in]ptthe point to insert

Definition at line 756 of file point_cloud.h.

◆ transient_push_back()

template<typename PointT>
void pcl::PointCloud< PointT >::transient_push_back ( const PointT & pt)
inline

Insert a new point in the cloud, at the end of the container.

Note
This assumes the user would correct the width and height later on!
Parameters
[in]ptthe point to insert

Definition at line 676 of file point_cloud.h.

Referenced by pcl::copyPointCloud(), and pcl::copyPointCloud().

Member Data Documentation

◆ header

template<typename PointT>
pcl::PCLHeader pcl::PointCloud< PointT >::header

The point cloud header.

It contains information about the acquisition time.

Definition at line 393 of file point_cloud.h.

Referenced by pcl::Registration< PointSource, PointTarget, Scalar >::align(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::features::computeApproximateNormals(), pcl::PointCloud< PointInT >::concatenate(), pcl::concatenateFields(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::detectKeypoints(), pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >::determinePersistentFeatures(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::extractEuclideanClusters(), pcl::gpu::extractEuclideanClusters(), pcl::extractLabeledEuclideanClusters(), pcl::gpu::extractLabeledEuclideanClusters(), pcl::Filter< PointT >::filter(), pcl::fromPCLPointCloud2(), pcl::operator<<(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::SegmentDifferences< PointT >::segment(), pcl::PointCloud< PointInT >::swap(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), and pcl::transformPointCloudWithNormals().

◆ height

template<typename PointT>
std::uint32_t pcl::PointCloud< PointT >::height = 0

The point cloud height (if organized as an image-structure).

Definition at line 401 of file point_cloud.h.

Referenced by pcl::visualization::ImageViewer::addMask(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRectangle(), pcl::visualization::ImageViewer::addRectangle(), pcl::visualization::ImageViewer::addRGBImage(), pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::Feature< PointInT, ReferenceFrame >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradientsSobel(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< PointInT >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::GaussianKernel::convolve(), pcl::GaussianKernel::convolve(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::common::deleteCols(), pcl::common::deleteRows(), pcl::demeanPointCloud(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::Edge< PointInT, PointInT >::detectEdgeSobel(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::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::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::occlusion_reasoning::filter(), 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, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), pcl::Morphology< PointT >::intersectionBinary(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::common::mirrorColumns(), pcl::common::mirrorRows(), pcl::operator<<(), pcl::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloudDepthAndRGBtoXYZRGBA(), pcl::PointCloudRGBtoI(), pcl::PointCloudRGBtoI(), pcl::PointCloudRGBtoI(), pcl::io::pointCloudTovtkStructuredGrid(), pcl::PointCloudXYZHSVtoXYZRGB(), pcl::PointCloudXYZRGBAtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZI(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::Registration< PointSource, PointTarget, float >::setInputSource(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< PointInT >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::io::vtkPolyDataToPointCloud(), pcl::io::vtkStructuredGridToPointCloud(), pcl::PCDWriter::writeASCII(), and pcl::PCDWriter::writeASCII().

◆ is_dense

template<typename PointT>
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 404 of file point_cloud.h.

Referenced by pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::FilterIndices< PointT >::applyFilter(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::compute3DCentroid(), pcl::compute3DCentroid(), pcl::computeCentroid(), pcl::computeCentroid(), pcl::computeCentroidAndOBB(), pcl::computeCentroidAndOBB(), pcl::computeCovarianceMatrix(), pcl::computeCovarianceMatrix(), pcl::computeCovarianceMatrix(), pcl::computeCovarianceMatrix(), pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature(), pcl::computeMeanAndCovarianceMatrix(), pcl::computeMeanAndCovarianceMatrix(), pcl::PointCloud< PointInT >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::demeanPointCloud(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::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, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::getMaxDistance(), pcl::getMaxDistance(), pcl::getMinMax3D(), pcl::getMinMax3D(), pcl::getMinMax3D(), pcl::getMinMax3D(), pcl::getPointCloudDifference(), pcl::getPointsInBox(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::operator<<(), pcl::operator<<(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::io::pointCloudTovtkPolyData(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< PointInT >::swap(), pcl::toPCLPointCloud2(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::visualization::PCLVisualizer::updatePolygonMesh(), pcl::io::vtkPolyDataToPointCloud(), and pcl::io::vtkStructuredGridToPointCloud().

◆ points

template<typename PointT>
std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::PointCloud< PointT >::points

The point data.

Definition at line 396 of file point_cloud.h.

Referenced by pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::features::computeApproximateCovariances(), pcl::features::computeApproximateNormals(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::MomentInvariantsEstimation< PointInT, PointOutT >::computePointMomentInvariants(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::visualization::createPolygon(), pcl::BriskKeypoint2D< PointInT, PointOutT, IntensityT >::detectKeypoints(), pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects(), pcl::features::ISMVoteList< PointT >::getColoredCloud(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::getMinMax3D(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::UnaryClassifier< PointT >::kmeansClustering(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::MarchingCubes< PointNT >::performReconstruction(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine(), pcl::PlanarPolygon< PointT >::setContour(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::shiftCloud(), pcl::TextureMapping< PointInT >::showOcclusions(), pcl::PointCloud< PointInT >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras(), and pcl::PCDWriter::writeASCII().

◆ sensor_orientation_

template<typename PointT>
Eigen::Quaternionf pcl::PointCloud< PointT >::sensor_orientation_ = Eigen::Quaternionf::Identity ()

Sensor acquisition pose (rotation).

Definition at line 409 of file point_cloud.h.

Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::Filter< PointT >::filter(), pcl::PCDWriter::generateHeader(), pcl::operator<<(), pcl::operator<<(), pcl::ImageGrabber< PointT >::operator[](), pcl::PCDGrabber< PointT >::operator[](), pcl::ImageGrabber< PointT >::publish(), pcl::PCDGrabber< PointT >::publish(), pcl::StereoGrabber< PointT >::publish(), pcl::FileReader::read(), pcl::IFSReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), pcl::PLYReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< PointInT >::swap(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().

◆ sensor_origin_

template<typename PointT>
Eigen::Vector4f pcl::PointCloud< PointT >::sensor_origin_ = Eigen::Vector4f::Zero ()

Sensor acquisition pose (origin/translation).

Definition at line 407 of file point_cloud.h.

Referenced by pcl::visualization::PCLVisualizer::addCorrespondences(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloud(), pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::PCLVisualizer::addPolygonMesh(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::Filter< PointT >::filter(), pcl::PCDWriter::generateHeader(), pcl::operator<<(), pcl::operator<<(), pcl::ImageGrabber< PointT >::operator[](), pcl::PCDGrabber< PointT >::operator[](), pcl::ImageGrabber< PointT >::publish(), pcl::PCDGrabber< PointT >::publish(), pcl::StereoGrabber< PointT >::publish(), pcl::FileReader::read(), pcl::IFSReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::OBJReader::read(), pcl::PCDReader::read(), pcl::PLYReader::read(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::PointCloud< PointInT >::swap(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::FileWriter::write(), and pcl::PLYWriter::write().

◆ width

template<typename PointT>
std::uint32_t pcl::PointCloud< PointT >::width = 0

The point cloud width (if organized as an image-structure).

Definition at line 399 of file point_cloud.h.

Referenced by pcl::visualization::PCLVisualizer::addPointCloudNormals(), pcl::visualization::ImageViewer::addRGBImage(), pcl::LineRGBD< PointXYZT, PointRGBT >::applyProjectiveDepthICPOnDetections(), pcl::Edge< PointInT, PointOutT >::canny(), pcl::BRISK2DEstimation< PointInT, PointOutT, KeypointT, IntensityT >::compute(), pcl::DisparityMapConverter< PointT >::compute(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::Feature< PointInT, ReferenceFrame >::compute(), pcl::filters::Pyramid< PointT >::compute(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::features::computeApproximateNormals(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradients(), pcl::ColorGradientModality< PointInT >::computeMaxColorGradientsSobel(), pcl::LineRGBD< PointXYZT, PointRGBT >::computeTransformedTemplatePoints(), pcl::PointCloud< PointInT >::concatenate(), pcl::concatenateFields(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, false >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::io::OrganizedConversion< PointT, true >::convert(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::UnaryClassifier< PointT >::convertCloud(), pcl::gpu::kinfuLS::StandaloneMarchingCubes< PointT >::convertTrianglesToMesh(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::convolve(), pcl::GaussianKernel::convolve(), pcl::GaussianKernel::convolve(), pcl::GaussianKernel::convolveCols(), pcl::GaussianKernel::convolveRows(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::copyPointCloud(), pcl::common::deleteCols(), pcl::common::deleteRows(), pcl::demeanPointCloud(), pcl::demeanPointCloud(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::derivatives(), pcl::Edge< PointInT, PointOutT >::detectEdgeCanny(), pcl::Edge< PointInT, PointOutT >::detectEdgePrewitt(), pcl::Edge< PointInT, PointOutT >::detectEdgeSobel(), pcl::Edge< PointInT, PointInT >::detectEdgeSobel(), pcl::SmoothedSurfacesKeypoint< PointT, PointNT >::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::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::extractRGBFromPointCloud(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< PointT, GeneratorT >::fill(), pcl::common::CloudGenerator< pcl::PointXY, GeneratorT >::fill(), pcl::occlusion_reasoning::filter(), 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, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::occlusion_reasoning::getOccludedCloud(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes(), pcl::RFFaceDetectorTrainer::getVotes2(), pcl::filters::Convolution< PointIn, PointOut >::initCompute(), pcl::outofcore::OutofcoreOctreeDiskContainer< PointT >::insertRange(), 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::operator<<(), pcl::BilateralUpsampling< PointInT, PointOutT >::performProcessing(), pcl::ConcaveHull< PointInT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::GridProjection< PointNT >::performReconstruction(), pcl::ConvexHull< PointInT >::performReconstruction2D(), pcl::ConvexHull< PointInT >::performReconstruction3D(), pcl::PointCloudDepthAndRGBtoXYZRGBA(), pcl::PointCloudRGBtoI(), pcl::PointCloudRGBtoI(), pcl::PointCloudRGBtoI(), pcl::io::pointCloudTovtkStructuredGrid(), pcl::PointCloudXYZHSVtoXYZRGB(), pcl::PointCloudXYZRGBAtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZHSV(), pcl::PointCloudXYZRGBtoXYZI(), pcl::BilateralUpsampling< PointInT, PointOutT >::process(), pcl::CloudSurfaceProcessing< PointInT, PointOutT >::process(), pcl::MovingLeastSquares< PointInT, PointOutT >::process(), pcl::ColorGradientModality< PointInT >::processInputData(), pcl::PCDGrabber< PointT >::publish(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes(), pcl::io::LZFBayer8ImageReader::read(), pcl::io::LZFDepth16ImageReader::read(), pcl::io::LZFRGB24ImageReader::read(), pcl::io::LZFYUV422ImageReader::read(), pcl::io::LZFBayer8ImageReader::readOMP(), pcl::io::LZFDepth16ImageReader::readOMP(), pcl::io::LZFRGB24ImageReader::readOMP(), pcl::io::LZFYUV422ImageReader::readOMP(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConcaveHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::ConvexHull< PointInT >::reconstruct(), pcl::SurfaceReconstruction< PointInT >::reconstruct(), pcl::removeNaNFromPointCloud(), pcl::removeNaNNormalsFromPointCloud(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::SegmentDifferences< PointT >::segment(), pcl::Registration< PointSource, PointTarget, float >::setInputSource(), pcl::visualization::ImageViewer::showCorrespondences(), pcl::Edge< PointInT, PointOutT >::sobelMagnitudeDirection(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::spatialGradient(), pcl::Morphology< PointT >::subtractionBinary(), pcl::PointCloud< PointInT >::swap(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::swapDimensions(), pcl::toPCLPointCloud2(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::track(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloud(), pcl::transformPointCloudWithNormals(), pcl::transformPointCloudWithNormals(), pcl::Morphology< PointT >::unionBinary(), pcl::io::vtkPolyDataToPointCloud(), pcl::io::vtkStructuredGridToPointCloud(), pcl::PCDWriter::writeASCII(), and pcl::PCDWriter::writeASCII().


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