Public Types | Public Member Functions | Public Attributes | Protected Attributes | Friends
pcl::PointCloud< PointT > Class Template Reference

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

#include <point_cloud.h>

List of all members.

Public Types

typedef std::vector
< PointCloud< PointT >
, Eigen::aligned_allocator
< PointCloud< PointT > > > 
CloudVectorType
typedef VectorType::const_iterator const_iterator
typedef boost::shared_ptr
< const PointCloud< PointT > > 
ConstPtr
typedef VectorType::iterator iterator
typedef PointT PointType
typedef boost::shared_ptr
< PointCloud< PointT > > 
Ptr
typedef std::vector< PointT,
Eigen::aligned_allocator
< PointT > > 
VectorType

Public Member Functions

const PointTat (int column, int row) const
 Obtain the point given by the (column, row) coordinates. Only works on organized datasets (those that have height != 1).
PointTat (int column, int row)
 Obtain the point given by the (column, row) coordinates. Only works on organized datasets (those that have height != 1).
const PointTat (size_t n) const
PointTat (size_t n)
const PointTback () const
PointTback ()
iterator begin ()
const_iterator begin () const
void clear ()
 Removes all points in a cloud and sets the width and height to 0.
bool empty () const
iterator end ()
const_iterator end () const
iterator 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.
const PointTfront () const
PointTfront ()
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 ()
 Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
const Eigen::Map< const
Eigen::MatrixXf,
Eigen::Aligned,
Eigen::OuterStride<> > 
getMatrixXfMap () const
 Return an Eigen MatrixXf (assumes float values) mapped to the PointCloud.
iterator insert (iterator position, const PointT &pt)
 Insert a new point in the cloud, given an iterator.
void insert (iterator position, 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.
bool isOrganized () const
 Return whether a dataset is organized (e.g., arranged in a structured grid).
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. The changes of the returned cloud are not mirrored back to this one.
const PointToperator() (size_t column, size_t row) const
 Obtain the point given by the (column, row) coordinates. Only works on organized datasets (those that have height != 1).
PointToperator() (size_t column, size_t row)
 Obtain the point given by the (column, row) coordinates. Only works on organized datasets (those that have height != 1).
const PointCloud operator+ (const PointCloud &rhs)
 Add a point cloud to another cloud.
PointCloudoperator+= (const PointCloud &rhs)
 Add a point cloud to the current cloud.
const PointToperator[] (size_t n) const
PointToperator[] (size_t n)
 PointCloud ()
 Default constructor. Sets is_dense to true, width and height to 0, and the sensor_origin_ and sensor_orientation_ to identity.
 PointCloud (PointCloud< PointT > &pc)
 Copy constructor (needed by compilers such as Intel C++)
 PointCloud (const PointCloud< PointT > &pc)
 Copy constructor (needed by compilers such as Intel C++)
 PointCloud (const PointCloud< PointT > &pc, const std::vector< int > &indices)
 Copy constructor from point cloud subset.
 PointCloud (uint32_t width_, uint32_t height_, const PointT &value_=PointT())
 Allocate constructor from point cloud subset.
void push_back (const PointT &pt)
 Insert a new point in the cloud, at the end of the container.
void reserve (size_t n)
void resize (size_t n)
 Resize the cloud.
size_t size () const
void swap (PointCloud< PointT > &rhs)
 Swap a point cloud with another cloud.
virtual ~PointCloud ()
 Destructor.

Public Attributes

pcl::PCLHeader header
 The point cloud header. It contains information about the acquisition time.
uint32_t height
 The point cloud height (if organized as an image-structure).
bool is_dense
 True if no points are invalid (e.g., have NaN or Inf values).
std::vector< PointT,
Eigen::aligned_allocator
< PointT > > 
points
 The point data.
Eigen::Quaternionf sensor_orientation_
 Sensor acquisition pose (rotation).
Eigen::Vector4f sensor_origin_
 Sensor acquisition pose (origin/translation).
uint32_t width
 The point cloud width (if organized as an image-structure).

Protected Attributes

boost::shared_ptr< MsgFieldMapmapping_

Friends

boost::shared_ptr< MsgFieldMap > & detail::getMapping (pcl::PointCloud< PointT > &p)

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:

 pcl::PointCloud<pcl::PointXYZ> cloud;
 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 ())); 

The PointCloud class contains the following elements:

Author:
Patrick Mihelich, Radu B. Rusu

Definition at line 172 of file point_cloud.h.


Member Typedef Documentation

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

Definition at line 427 of file point_cloud.h.

template<typename PointT>
typedef VectorType::const_iterator pcl::PointCloud< PointT >::const_iterator

Definition at line 433 of file point_cloud.h.

template<typename PointT>
typedef boost::shared_ptr<const PointCloud<PointT> > pcl::PointCloud< PointT >::ConstPtr

Reimplemented in pcl::RangeImage, pcl::RangeImagePlanar, and pcl::RangeImageSpherical.

Definition at line 429 of file point_cloud.h.

template<typename PointT>
typedef VectorType::iterator pcl::PointCloud< PointT >::iterator

Definition at line 432 of file point_cloud.h.

template<typename PointT>
typedef PointT pcl::PointCloud< PointT >::PointType

Definition at line 425 of file point_cloud.h.

template<typename PointT>
typedef boost::shared_ptr<PointCloud<PointT> > pcl::PointCloud< PointT >::Ptr

Reimplemented in pcl::RangeImage, pcl::RangeImagePlanar, and pcl::RangeImageSpherical.

Definition at line 428 of file point_cloud.h.

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

Definition at line 426 of file point_cloud.h.


Constructor & Destructor Documentation

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

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( PointCloud< PointT > &  pc) [inline]

Copy constructor (needed by compilers such as Intel C++)

Parameters:
[in]pcthe cloud to copy into this

Definition at line 188 of file point_cloud.h.

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( const PointCloud< PointT > &  pc) [inline]

Copy constructor (needed by compilers such as Intel C++)

Parameters:
[in]pcthe cloud to copy into this

Definition at line 199 of file point_cloud.h.

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( const PointCloud< PointT > &  pc,
const std::vector< int > &  indices 
) [inline]

Copy constructor from point cloud subset.

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

Definition at line 211 of file point_cloud.h.

template<typename PointT>
pcl::PointCloud< PointT >::PointCloud ( uint32_t  width_,
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 228 of file point_cloud.h.

template<typename PointT>
virtual pcl::PointCloud< PointT >::~PointCloud ( ) [inline, virtual]

Destructor.

Definition at line 240 of file point_cloud.h.


Member Function Documentation

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 283 of file point_cloud.h.

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 297 of file point_cloud.h.

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

Definition at line 460 of file point_cloud.h.

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

Definition at line 461 of file point_cloud.h.

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

Definition at line 464 of file point_cloud.h.

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

Definition at line 465 of file point_cloud.h.

template<typename PointT>
iterator pcl::PointCloud< PointT >::begin ( ) [inline]

Definition at line 434 of file point_cloud.h.

template<typename PointT>
const_iterator pcl::PointCloud< PointT >::begin ( ) const [inline]

Definition at line 436 of file point_cloud.h.

template<typename PointT>
void pcl::PointCloud< PointT >::clear ( ) [inline]

Removes all points in a cloud and sets the width and height to 0.

Definition at line 567 of file point_cloud.h.

template<typename PointT>
bool pcl::PointCloud< PointT >::empty ( ) const [inline]

Definition at line 442 of file point_cloud.h.

template<typename PointT>
iterator pcl::PointCloud< PointT >::end ( ) [inline]

Definition at line 435 of file point_cloud.h.

template<typename PointT>
const_iterator pcl::PointCloud< PointT >::end ( ) const [inline]

Definition at line 437 of file point_cloud.h.

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 528 of file point_cloud.h.

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 543 of file point_cloud.h.

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

Definition at line 462 of file point_cloud.h.

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

Definition at line 463 of file point_cloud.h.

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:
Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure, that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
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 352 of file point_cloud.h.

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:
Since 1.4.0, Eigen matrices are forced to Row Major to increase the efficiency of the algorithms in PCL This means that the behavior of getMatrixXfMap changed, and is now correctly mapping 1-1 with a PointCloud structure, that is: number of points in a cloud = rows in a matrix, number of point dimensions = columns in a matrix
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 376 of file point_cloud.h.

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

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

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! See getMatrixXfMap for more information.

Definition at line 390 of file point_cloud.h.

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

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

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! See getMatrixXfMap for more information.

Definition at line 401 of file point_cloud.h.

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 486 of file point_cloud.h.

template<typename PointT>
void pcl::PointCloud< PointT >::insert ( iterator  position,
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 501 of file point_cloud.h.

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 515 of file point_cloud.h.

template<typename PointT>
bool pcl::PointCloud< PointT >::isOrganized ( ) const [inline]

Return whether a dataset is organized (e.g., arranged in a structured grid).

Note:
The height value must be different than 1 for a dataset to be organized.

Definition at line 331 of file point_cloud.h.

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 580 of file point_cloud.h.

template<typename PointT>
const PointT& pcl::PointCloud< PointT >::operator() ( size_t  column,
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 311 of file point_cloud.h.

template<typename PointT>
PointT& pcl::PointCloud< PointT >::operator() ( size_t  column,
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 322 of file point_cloud.h.

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

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 247 of file point_cloud.h.

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

Definition at line 458 of file point_cloud.h.

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

Definition at line 459 of file point_cloud.h.

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

Insert 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]ptthe point to insert

Definition at line 472 of file point_cloud.h.

template<typename PointT>
void pcl::PointCloud< PointT >::reserve ( size_t  n) [inline]

Definition at line 441 of file point_cloud.h.

template<typename PointT>
void pcl::PointCloud< PointT >::resize ( size_t  n) [inline]

Resize the cloud.

Parameters:
[in]nthe new cloud size

Definition at line 447 of file point_cloud.h.

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

Definition at line 440 of file point_cloud.h.

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 555 of file point_cloud.h.


Friends And Related Function Documentation

template<typename PointT>
boost::shared_ptr<MsgFieldMap>& detail::getMapping ( pcl::PointCloud< PointT > &  p) [friend]

Member Data Documentation

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
boost::shared_ptr<MsgFieldMap> pcl::PointCloud< PointT >::mapping_ [protected]

Definition at line 584 of file point_cloud.h.

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

The point data.

Definition at line 410 of file point_cloud.h.

template<typename PointT>
Eigen::Quaternionf pcl::PointCloud< PointT >::sensor_orientation_

Sensor acquisition pose (rotation).

Definition at line 423 of file point_cloud.h.

template<typename PointT>
Eigen::Vector4f pcl::PointCloud< PointT >::sensor_origin_

Sensor acquisition pose (origin/translation).

Definition at line 421 of file point_cloud.h.

template<typename PointT>
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.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:02