Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes
pcl::ProjectInliers< sensor_msgs::PointCloud2 > Class Template Reference

ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More...

#include <project_inliers.h>

Inheritance diagram for pcl::ProjectInliers< sensor_msgs::PointCloud2 >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getCopyAllData () const
 Get whether all data is being copied (true), or only the projected inliers (false).
bool getCopyAllFields () const
 Get whether all fields are being copied (true), or only XYZ (false).
ModelCoefficientsConstPtr getModelCoefficients () const
 Get a pointer to the model coefficients.
int getModelType () const
 Get the type of SAC model used.
 ProjectInliers ()
 Empty constructor.
void setCopyAllData (bool val)
 Set whether all data will be returned, or only the projected inliers.
void setCopyAllFields (bool val)
 Set whether all fields should be copied, or only the XYZ.
void setModelCoefficients (const ModelCoefficientsConstPtr &model)
 Provide a pointer to the model coefficients.
void setModelType (int model)
 The type of model to use (user given parameter).

Protected Member Functions

void applyFilter (PointCloud2 &output)
 Abstract filter method.

Protected Attributes

bool copy_all_data_
 True if all data will be returned, false if only the projected inliers. Default: false.
bool copy_all_fields_
 True if all fields will be returned, false if only XYZ. Default: true.
ModelCoefficientsConstPtr model_
 A pointer to the vector of model coefficients.
int model_type_
 The type of model to use (user given parameter).

Private Types

typedef sensor_msgs::PointCloud2 PointCloud2
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
typedef PointCloud2::Ptr PointCloud2Ptr
typedef SampleConsensusModel
< PointXYZ >::Ptr 
SampleConsensusModelPtr

Private Member Functions

virtual bool initSACModel (int model_type)

Private Attributes

SampleConsensusModelPtr sacmodel_
 The model that needs to be segmented.

Detailed Description

template<>
class pcl::ProjectInliers< sensor_msgs::PointCloud2 >

ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud.

Note:
setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
Author:
Radu Bogdan Rusu

Definition at line 171 of file project_inliers.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl::ProjectInliers< sensor_msgs::PointCloud2 >::PointCloud2 [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 176 of file project_inliers.h.

typedef PointCloud2::ConstPtr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 178 of file project_inliers.h.

typedef PointCloud2::Ptr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private]

Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 177 of file project_inliers.h.

typedef SampleConsensusModel<PointXYZ>::Ptr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::SampleConsensusModelPtr [private]

Definition at line 180 of file project_inliers.h.


Constructor & Destructor Documentation

pcl::ProjectInliers< sensor_msgs::PointCloud2 >::ProjectInliers ( ) [inline]

Empty constructor.

Definition at line 184 of file project_inliers.h.


Member Function Documentation

void pcl::ProjectInliers< sensor_msgs::PointCloud2 >::applyFilter ( PointCloud2 output) [protected, virtual]

Abstract filter method.

The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.

Parameters:
[out]outputthe resultant filtered point cloud

Implements pcl::Filter< sensor_msgs::PointCloud2 >.

Definition at line 47 of file filters/src/project_inliers.cpp.

bool pcl::ProjectInliers< sensor_msgs::PointCloud2 >::getCopyAllData ( ) const [inline]

Get whether all data is being copied (true), or only the projected inliers (false).

Definition at line 248 of file project_inliers.h.

bool pcl::ProjectInliers< sensor_msgs::PointCloud2 >::getCopyAllFields ( ) const [inline]

Get whether all fields are being copied (true), or only XYZ (false).

Definition at line 232 of file project_inliers.h.

ModelCoefficientsConstPtr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::getModelCoefficients ( ) const [inline]

Get a pointer to the model coefficients.

Definition at line 216 of file project_inliers.h.

int pcl::ProjectInliers< sensor_msgs::PointCloud2 >::getModelType ( ) const [inline]

Get the type of SAC model used.

Definition at line 200 of file project_inliers.h.

bool pcl::ProjectInliers< sensor_msgs::PointCloud2 >::initSACModel ( int  model_type) [private, virtual]

Definition at line 161 of file filters/src/project_inliers.cpp.

void pcl::ProjectInliers< sensor_msgs::PointCloud2 >::setCopyAllData ( bool  val) [inline]

Set whether all data will be returned, or only the projected inliers.

Parameters:
[in]valtrue if all data should be returned, false if only the projected inliers

Definition at line 241 of file project_inliers.h.

void pcl::ProjectInliers< sensor_msgs::PointCloud2 >::setCopyAllFields ( bool  val) [inline]

Set whether all fields should be copied, or only the XYZ.

Parameters:
[in]valtrue if all fields will be returned, false if only XYZ

Definition at line 225 of file project_inliers.h.

void pcl::ProjectInliers< sensor_msgs::PointCloud2 >::setModelCoefficients ( const ModelCoefficientsConstPtr &  model) [inline]

Provide a pointer to the model coefficients.

Parameters:
[in]modela pointer to the model coefficients

Definition at line 209 of file project_inliers.h.

void pcl::ProjectInliers< sensor_msgs::PointCloud2 >::setModelType ( int  model) [inline]

The type of model to use (user given parameter).

Parameters:
[in]modelthe model type (check model_types.h)

Definition at line 193 of file project_inliers.h.


Member Data Documentation

bool pcl::ProjectInliers< sensor_msgs::PointCloud2 >::copy_all_data_ [protected]

True if all data will be returned, false if only the projected inliers. Default: false.

Definition at line 257 of file project_inliers.h.

bool pcl::ProjectInliers< sensor_msgs::PointCloud2 >::copy_all_fields_ [protected]

True if all fields will be returned, false if only XYZ. Default: true.

Definition at line 260 of file project_inliers.h.

ModelCoefficientsConstPtr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::model_ [protected]

A pointer to the vector of model coefficients.

Definition at line 263 of file project_inliers.h.

int pcl::ProjectInliers< sensor_msgs::PointCloud2 >::model_type_ [protected]

The type of model to use (user given parameter).

Definition at line 254 of file project_inliers.h.

SampleConsensusModelPtr pcl::ProjectInliers< sensor_msgs::PointCloud2 >::sacmodel_ [private]

The model that needs to be segmented.

Definition at line 270 of file project_inliers.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:54