Point Cloud Library (PCL)  1.6.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Public Types | Public Member Functions
pcl::CropBox< sensor_msgs::PointCloud2 > Class Template Reference

CropBox is a filter that allows the user to filter all the data inside of a given box. More...

#include <pcl/filters/crop_box.h>

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

List of all members.

Public Types

typedef PointIndices::Ptr PointIndicesPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr

Public Member Functions

 CropBox ()
 Empty constructor.
void setMin (const Eigen::Vector4f &min_pt)
 Set the minimum point of the box.
Eigen::Vector4f getMin () const
 Get the value of the minimum point of the box, as set by the user.
void setMax (const Eigen::Vector4f &max_pt)
 Set the maximum point of the box.
Eigen::Vector4f getMax () const
 Get the value of the maxiomum point of the box, as set by the user.
void setTranslation (const Eigen::Vector3f &translation)
 Set a translation value for the box.
Eigen::Vector3f getTranslation () const
 Get the value of the box translation parameter as set by the user.
void setRotation (const Eigen::Vector3f &rotation)
 Set a rotation value for the box.
Eigen::Vector3f getRotation () const
 Get the value of the box rotatation parameter, as set by the user.
void setTransform (const Eigen::Affine3f &transform)
 Set a transformation that should be applied to the cloud before filtering.
Eigen::Affine3f getTransform () const
 Get the value of the transformation parameter, as set by the user.
virtual void filter (PointCloud2 &output)
 Calls the filtering method and returns the filtered dataset in output.
void filter (std::vector< int > &indices)
 Calls the filtering method and returns the filtered point cloud indices.
void setNegative (bool negative)
 Set whether the regular conditions for points filtering should apply, or the inverted conditions.
bool getNegative ()
 Get whether the regular conditions for points filtering should apply, or the inverted conditions.
void setKeepOrganized (bool keep_organized)
 Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure.
bool getKeepOrganized ()
 Get whether the filtered points should be kept and set to the value given through setUserFilterValue (default = NaN), or removed from the PointCloud, thus potentially breaking its organized structure.
void setUserFilterValue (float value)
 Provide a value that the filtered points should be set to instead of removing them.
IndicesConstPtr const getRemovedIndices ()
 Get the point indices being removed.
void setInputCloud (const PointCloud2ConstPtr &cloud)
 Provide a pointer to the input dataset.
PointCloud2ConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset.
void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used.

Detailed Description

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

CropBox is a filter that allows the user to filter all the data inside of a given box.

Author:
Justin Rosen

Definition at line 198 of file crop_box.h.


Member Typedef Documentation

Definition at line 280 of file pcl_base.h.

Definition at line 279 of file pcl_base.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 209 of file crop_box.h.


Member Function Documentation

virtual void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter ( PointCloud2 output) [inline, virtual, inherited]

Calls the filtering method and returns the filtered dataset in output.

Parameters:
[out]outputthe resultant filtered point cloud dataset

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

Definition at line 228 of file filter_indices.h.

void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter ( std::vector< int > &  indices) [inherited]

Calls the filtering method and returns the filtered point cloud indices.

Parameters:
[out]indicesthe resultant filtered point cloud indices
IndicesPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getIndices ( ) [inline, inherited]

Get a pointer to the vector of indices used.

Definition at line 329 of file pcl_base.h.

Get a pointer to the input point cloud dataset.

Definition at line 303 of file pcl_base.h.

Get whether the filtered points should be kept and set to the value given through setUserFilterValue (default = NaN), or removed from the PointCloud, thus potentially breaking its organized structure.

Returns:
The value of the internal keep_organized_ parameter; false = remove points (default), true = redefine points, keep structure.

Definition at line 272 of file filter_indices.h.

Eigen::Vector4f pcl::CropBox< sensor_msgs::PointCloud2 >::getMax ( ) const [inline]

Get the value of the maxiomum point of the box, as set by the user.

Returns:
the value of the internal max_pt parameter.

Definition at line 250 of file crop_box.h.

Eigen::Vector4f pcl::CropBox< sensor_msgs::PointCloud2 >::getMin ( ) const [inline]

Get the value of the minimum point of the box, as set by the user.

Returns:
the value of the internal min_pt parameter.

Definition at line 232 of file crop_box.h.

bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::getNegative ( ) [inline, inherited]

Get whether the regular conditions for points filtering should apply, or the inverted conditions.

Returns:
The value of the internal negative_ parameter; false = normal filter behavior (default), true = inverted behavior.

Definition at line 252 of file filter_indices.h.

Get the point indices being removed.

Returns:
The value of the internal negative_ parameter; false = normal filter behavior (default), true = inverted behavior.

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

Definition at line 291 of file filter_indices.h.

Eigen::Vector3f pcl::CropBox< sensor_msgs::PointCloud2 >::getRotation ( ) const [inline]

Get the value of the box rotatation parameter, as set by the user.

Definition at line 282 of file crop_box.h.

Eigen::Affine3f pcl::CropBox< sensor_msgs::PointCloud2 >::getTransform ( ) const [inline]

Get the value of the transformation parameter, as set by the user.

Definition at line 298 of file crop_box.h.

Eigen::Vector3f pcl::CropBox< sensor_msgs::PointCloud2 >::getTranslation ( ) const [inline]

Get the value of the box translation parameter as set by the user.

Definition at line 266 of file crop_box.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const IndicesPtr indices) [inline, inherited]

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

Parameters:
indicesa pointer to the vector of indices that represents the input data.

Definition at line 309 of file pcl_base.h.

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices ( const PointIndicesConstPtr indices) [inline, inherited]

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

Parameters:
indicesa pointer to the vector of indices that represents the input data.

Definition at line 320 of file pcl_base.h.

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message
void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setKeepOrganized ( bool  keep_organized) [inline, inherited]

Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure.

Parameters:
[in]keep_organizedfalse = remove points (default), true = redefine points, keep structure.

Definition at line 262 of file filter_indices.h.

void pcl::CropBox< sensor_msgs::PointCloud2 >::setMax ( const Eigen::Vector4f &  max_pt) [inline]

Set the maximum point of the box.

Parameters:
[in]max_ptthe maximum point of the box

Definition at line 241 of file crop_box.h.

void pcl::CropBox< sensor_msgs::PointCloud2 >::setMin ( const Eigen::Vector4f &  min_pt) [inline]

Set the minimum point of the box.

Parameters:
[in]min_ptthe minimum point of the box

Definition at line 223 of file crop_box.h.

void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setNegative ( bool  negative) [inline, inherited]

Set whether the regular conditions for points filtering should apply, or the inverted conditions.

Parameters:
[in]negativefalse = normal filter behavior (default), true = inverted behavior.

Definition at line 243 of file filter_indices.h.

void pcl::CropBox< sensor_msgs::PointCloud2 >::setRotation ( const Eigen::Vector3f &  rotation) [inline]

Set a rotation value for the box.

Parameters:
[in]rotationthe (rx,ry,rz) values that the box should be rotated by

Definition at line 275 of file crop_box.h.

void pcl::CropBox< sensor_msgs::PointCloud2 >::setTransform ( const Eigen::Affine3f &  transform) [inline]

Set a transformation that should be applied to the cloud before filtering.

Parameters:
[in]transforman affine transformation that needs to be applied to the cloud before filtering

Definition at line 291 of file crop_box.h.

void pcl::CropBox< sensor_msgs::PointCloud2 >::setTranslation ( const Eigen::Vector3f &  translation) [inline]

Set a translation value for the box.

Parameters:
[in]translationthe (tx,ty,tz) values that the box should be translated by

Definition at line 259 of file crop_box.h.

void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setUserFilterValue ( float  value) [inline, inherited]

Provide a value that the filtered points should be set to instead of removing them.

Used in conjunction with setKeepOrganized ().

Parameters:
[in]valuethe user given value that the filtered point dimensions should be set to (default = NaN).

Definition at line 282 of file filter_indices.h.


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