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 ()
 Get whether all data is being copied (true), or only the projected inliers (false).
bool getCopyAllFields ()
 Get whether all fields are being copied (true), or only XYZ (false).
ModelCoefficientsConstPtr getModelCoefficients ()
 Get a pointer to the model coefficients.
int getModelType ()
 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 151 of file project_inliers.h.


Member Typedef Documentation

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

Definition at line 156 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 158 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 157 of file project_inliers.h.

Definition at line 160 of file project_inliers.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 165 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}.

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

Definition at line 45 of file project_inliers.cpp.

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

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

Definition at line 202 of file project_inliers.h.

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

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

Definition at line 195 of file project_inliers.h.

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

Get a pointer to the model coefficients.

Definition at line 188 of file project_inliers.h.

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

Get the type of SAC model used.

Definition at line 178 of file project_inliers.h.

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

Definition at line 135 of file 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:
val true if all data should be returned, false if only the projected inliers

Definition at line 200 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:
val true if all fields will be returned, false if only XYZ

Definition at line 193 of file project_inliers.h.

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

Provide a pointer to the model coefficients.

Parameters:
model a pointer to the model coefficients

Definition at line 184 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:
model the model type (check model_types.h)

Definition at line 174 of file project_inliers.h.


Member Data Documentation

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

Definition at line 208 of file project_inliers.h.

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

Definition at line 211 of file project_inliers.h.

A pointer to the vector of model coefficients.

Definition at line 214 of file project_inliers.h.

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

Definition at line 205 of file project_inliers.h.

The model that needs to be segmented.

Definition at line 220 of file project_inliers.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:20 2013