Point Cloud Library (PCL)
1.14.1-dev
|
PCL base class. More...
#include <pcl/pcl_base.h>
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 PointT & | operator[] (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... | |
PCL base class.
Implements methods that are used by most PCL algorithms.
Definition at line 69 of file pcl_base.h.
using pcl::PCLBase< PointT >::PointCloud = pcl::PointCloud<PointT> |
Definition at line 72 of file pcl_base.h.
using pcl::PCLBase< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
Definition at line 74 of file pcl_base.h.
using pcl::PCLBase< PointT >::PointCloudPtr = typename PointCloud::Ptr |
Definition at line 73 of file pcl_base.h.
using pcl::PCLBase< PointT >::PointIndicesConstPtr = PointIndices::ConstPtr |
Definition at line 77 of file pcl_base.h.
using pcl::PCLBase< PointT >::PointIndicesPtr = PointIndices::Ptr |
Definition at line 76 of file pcl_base.h.
pcl::PCLBase< PointT >::PCLBase |
Empty constructor.
Definition at line 46 of file pcl_base.hpp.
pcl::PCLBase< PointT >::PCLBase | ( | const PCLBase< PointT > & | base | ) |
Copy constructor.
Definition at line 55 of file pcl_base.hpp.
|
virtualdefault |
Destructor.
|
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().
|
inline |
Get a pointer to the vector of indices used.
Definition at line 129 of file pcl_base.h.
References pcl::PCLBase< PointT >::indices_.
|
inline |
Get a pointer to the vector of indices used.
Definition at line 133 of file pcl_base.h.
References pcl::PCLBase< PointT >::indices_.
|
inline |
Get a pointer to the input point cloud dataset.
Definition at line 96 of file pcl_base.h.
References pcl::PCLBase< PointT >::input_.
|
protected |
This method should get called before starting the actual computation.
Internally, initCompute() does the following:
Definition at line 138 of file pcl_base.hpp.
Referenced by pcl::FilterIndices< PointT >::filter(), and pcl::Filter< PointT >::filter().
|
inline |
Override PointCloud operator[] to shorten code.
[in] | pos | position in indices_ vector |
Definition at line 140 of file pcl_base.h.
References pcl::PCLBase< PointT >::indices_, and pcl::PCLBase< PointT >::input_.
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
[in] | indices | a 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.
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
[in] | indices | a pointer to the indices that represent the input data. |
Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.
Definition at line 72 of file pcl_base.hpp.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), 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::PCA< PointT >::setIndices(), pcl::MomentOfInertiaEstimation< PointT >::setIndices(), and pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
[in] | indices | a 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.
|
virtual |
Set the indices for the points laying within an interest region of the point cloud.
[in] | row_start | the offset on rows |
[in] | col_start | the offset on columns |
[in] | nb_rows | the number of rows to be considered row_start included |
[in] | nb_cols | the 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.
|
virtual |
Provide a pointer to the input dataset.
[in] | cloud | the 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().
|
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.
|
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[]().
|
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[]().
|
protected |
Set to true if point indices are used.
Definition at line 153 of file pcl_base.h.
Referenced by pcl::ExtractIndices< PointT >::ExtractIndices().