Point Cloud Library (PCL)  1.14.1-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::PCLBase< PointT > Class Template Reference

PCL base class. More...

#include <pcl/pcl_base.h>

+ Inheritance diagram for pcl::PCLBase< PointT >:
+ Collaboration diagram for pcl::PCLBase< PointT >:

Public Types

using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointIndicesPtr = PointIndices::Ptr
 
using PointIndicesConstPtr = PointIndices::ConstPtr
 

Public Member Functions

 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()=default
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointToperator[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Member Functions

bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Protected Attributes

PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

Detailed Description

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

PCL base class.

Implements methods that are used by most PCL algorithms.

Definition at line 69 of file pcl_base.h.

Member Typedef Documentation

◆ PointCloud

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

Definition at line 72 of file pcl_base.h.

◆ PointCloudConstPtr

template<typename PointT >
using pcl::PCLBase< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 74 of file pcl_base.h.

◆ PointCloudPtr

template<typename PointT >
using pcl::PCLBase< PointT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 73 of file pcl_base.h.

◆ PointIndicesConstPtr

template<typename PointT >
using pcl::PCLBase< PointT >::PointIndicesConstPtr = PointIndices::ConstPtr

Definition at line 77 of file pcl_base.h.

◆ PointIndicesPtr

template<typename PointT >
using pcl::PCLBase< PointT >::PointIndicesPtr = PointIndices::Ptr

Definition at line 76 of file pcl_base.h.

Constructor & Destructor Documentation

◆ PCLBase() [1/2]

template<typename PointT >
pcl::PCLBase< PointT >::PCLBase

Empty constructor.

Definition at line 46 of file pcl_base.hpp.

◆ PCLBase() [2/2]

template<typename PointT >
pcl::PCLBase< PointT >::PCLBase ( const PCLBase< PointT > &  base)

Copy constructor.

Definition at line 55 of file pcl_base.hpp.

◆ ~PCLBase()

template<typename PointT >
virtual pcl::PCLBase< PointT >::~PCLBase ( )
virtualdefault

Destructor.

Member Function Documentation

◆ deinitCompute()

template<typename PointT >
bool pcl::PCLBase< PointT >::deinitCompute
protected

This method should get called after finishing the actual computation.

Definition at line 175 of file pcl_base.hpp.

Referenced by pcl::FilterIndices< PointT >::filter(), and pcl::Filter< PointT >::filter().

◆ getIndices() [1/2]

template<typename PointT >
IndicesPtr pcl::PCLBase< PointT >::getIndices ( )
inline

Get a pointer to the vector of indices used.

Definition at line 129 of file pcl_base.h.

References pcl::PCLBase< PointT >::indices_.

◆ getIndices() [2/2]

template<typename PointT >
IndicesConstPtr const pcl::PCLBase< PointT >::getIndices ( ) const
inline

Get a pointer to the vector of indices used.

Definition at line 133 of file pcl_base.h.

References pcl::PCLBase< PointT >::indices_.

◆ getInputCloud()

template<typename PointT >
PointCloudConstPtr const pcl::PCLBase< PointT >::getInputCloud ( ) const
inline

Get a pointer to the input point cloud dataset.

Definition at line 96 of file pcl_base.h.

References pcl::PCLBase< PointT >::input_.

◆ initCompute()

template<typename PointT >
bool pcl::PCLBase< PointT >::initCompute
protected

This method should get called before starting the actual computation.

Internally, initCompute() does the following:

  • checks if an input dataset is given, and returns false otherwise
  • checks whether a set of input indices has been given. Returns true if yes.
  • if no input indices have been given, a fake set is created, which will be used until:
    • either a new set is given via setIndices(), or
    • a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices

Definition at line 138 of file pcl_base.hpp.

Referenced by pcl::FilterIndices< PointT >::filter(), and pcl::Filter< PointT >::filter().

◆ operator[]()

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

Override PointCloud operator[] to shorten code.

Note
this method can be called instead of (*input_)[(*indices_)[pos]] or (*input_)[(*indices_)[pos]]
Parameters
[in]posposition in indices_ vector

Definition at line 140 of file pcl_base.h.

References pcl::PCLBase< PointT >::indices_, and pcl::PCLBase< PointT >::input_.

◆ setIndices() [1/4]

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const IndicesConstPtr indices)
virtual

Provide a pointer to the vector of indices that represents the input data.

Parameters
[in]indicesa pointer to the indices that represent the input data.

Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.

Definition at line 81 of file pcl_base.hpp.

◆ setIndices() [2/4]

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const IndicesPtr indices)
virtual

◆ setIndices() [3/4]

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const PointIndicesConstPtr indices)
virtual

Provide a pointer to the vector of indices that represents the input data.

Parameters
[in]indicesa pointer to the indices that represent the input data.

Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.

Definition at line 90 of file pcl_base.hpp.

◆ setIndices() [4/4]

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( std::size_t  row_start,
std::size_t  col_start,
std::size_t  nb_rows,
std::size_t  nb_cols 
)
virtual

Set the indices for the points laying within an interest region of the point cloud.

Note
you shouldn't call this method on unorganized point clouds!
Parameters
[in]row_startthe offset on rows
[in]col_startthe offset on columns
[in]nb_rowsthe number of rows to be considered row_start included
[in]nb_colsthe number of columns to be considered col_start included

Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.

Definition at line 99 of file pcl_base.hpp.

◆ setInputCloud()

template<typename PointT >
void pcl::PCLBase< PointT >::setInputCloud ( const PointCloudConstPtr cloud)
virtual

Provide a pointer to the input dataset.

Parameters
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented in pcl::MinCutSegmentation< PointT >, pcl::GrabCut< PointT >, pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >, pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.

Definition at line 65 of file pcl_base.hpp.

Referenced by pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::UnaryClassifier< PointT >::computeFPFH(), pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::computeRf(), pcl::CrfSegmentation< PointT >::createVoxelGrid(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints(), pcl::kinfuLS::WorldModel< PointT >::getExistingData(), pcl::NormalDistributionsTransform< PointSource, PointTarget, Scalar >::init(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::initCompute(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::PCA< PointT >::setInputCloud(), pcl::MomentOfInertiaEstimation< PointT >::setInputCloud(), pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setInputCloud(), pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setInputSource(), pcl::Registration< PointSource, PointTarget, Scalar >::setInputSource(), pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud(), pcl::kinfuLS::WorldModel< PointT >::setSliceAsNans(), and pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().

Member Data Documentation

◆ fake_indices_

template<typename PointT >
bool pcl::PCLBase< PointT >::fake_indices_
protected

If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.

Definition at line 156 of file pcl_base.h.

◆ indices_

template<typename PointT >
IndicesPtr pcl::PCLBase< PointT >::indices_
protected

A pointer to the vector of point indices to use.

Definition at line 150 of file pcl_base.h.

Referenced by pcl::PCLBase< PointT >::getIndices(), and pcl::PCLBase< PointT >::operator[]().

◆ input_

template<typename PointT >
PointCloudConstPtr pcl::PCLBase< PointT >::input_
protected

The input point cloud dataset.

Definition at line 147 of file pcl_base.h.

Referenced by pcl::Filter< PointT >::filter(), pcl::PCLBase< PointT >::getInputCloud(), and pcl::PCLBase< PointT >::operator[]().

◆ use_indices_

template<typename PointT >
bool pcl::PCLBase< PointT >::use_indices_
protected

Set to true if point indices are used.

Definition at line 153 of file pcl_base.h.

Referenced by pcl::ExtractIndices< PointT >::ExtractIndices().


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