CropBox is a filter that allows the user to filter all the data inside of a given box. More...
#include <crop_box.h>
Public Member Functions | |
CropBox () | |
Empty constructor. | |
Eigen::Vector4f | getMax () const |
Get the value of the maxiomum point of the box, as set by the user. | |
Eigen::Vector4f | getMin () const |
Get the value of the minimum point of the box, as set by the user. | |
Eigen::Vector3f | getRotation () const |
Get the value of the box rotatation parameter, as set by the user. | |
Eigen::Affine3f | getTransform () const |
Get the value of the transformation parameter, as set by the user. | |
Eigen::Vector3f | getTranslation () const |
Get the value of the box translation parameter as set by the user. | |
void | setMax (const Eigen::Vector4f &max_pt) |
Set the maximum point of the box. | |
void | setMin (const Eigen::Vector4f &min_pt) |
Set the minimum point of the box. | |
void | setRotation (const Eigen::Vector3f &rotation) |
Set a rotation value for the box. | |
void | setTransform (const Eigen::Affine3f &transform) |
Set a transformation that should be applied to the cloud before filtering. | |
void | setTranslation (const Eigen::Vector3f &translation) |
Set a translation value for the box. | |
Protected Member Functions | |
void | applyFilter (PointCloud2 &output) |
Sample of point indices into a separate PointCloud. | |
void | applyFilter (std::vector< int > &indices) |
Sample of point indices. | |
Protected Attributes | |
Eigen::Vector4f | max_pt_ |
The maximum point of the box. | |
Eigen::Vector4f | min_pt_ |
The minimum point of the box. | |
Eigen::Vector3f | rotation_ |
The 3D rotation for the box. | |
Eigen::Affine3f | transform_ |
The affine transform applied to the cloud. | |
Eigen::Vector3f | translation_ |
The 3D translation for the box. | |
Private Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
CropBox is a filter that allows the user to filter all the data inside of a given box.
Definition at line 198 of file crop_box.h.
typedef sensor_msgs::PointCloud2 pcl::CropBox< sensor_msgs::PointCloud2 >::PointCloud2 [private] |
Reimplemented from pcl::FilterIndices< sensor_msgs::PointCloud2 >.
Definition at line 203 of file crop_box.h.
typedef PointCloud2::ConstPtr pcl::CropBox< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 205 of file crop_box.h.
typedef PointCloud2::Ptr pcl::CropBox< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 204 of file crop_box.h.
pcl::CropBox< sensor_msgs::PointCloud2 >::CropBox | ( | ) | [inline] |
Empty constructor.
Definition at line 209 of file crop_box.h.
void pcl::CropBox< sensor_msgs::PointCloud2 >::applyFilter | ( | PointCloud2 & | output | ) | [protected, virtual] |
Sample of point indices into a separate PointCloud.
output | the resultant point cloud |
Implements pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 46 of file crop_box.cpp.
void pcl::CropBox< sensor_msgs::PointCloud2 >::applyFilter | ( | std::vector< int > & | indices | ) | [protected, virtual] |
Sample of point indices.
indices | the resultant point cloud indices |
Implements pcl::FilterIndices< sensor_msgs::PointCloud2 >.
Definition at line 118 of file crop_box.cpp.
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.
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.
Definition at line 232 of file crop_box.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::CropBox< sensor_msgs::PointCloud2 >::setMax | ( | const Eigen::Vector4f & | max_pt | ) | [inline] |
Set the maximum point of the box.
[in] | max_pt | the 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.
[in] | min_pt | the minimum point of the box |
Definition at line 223 of file crop_box.h.
void pcl::CropBox< sensor_msgs::PointCloud2 >::setRotation | ( | const Eigen::Vector3f & | rotation | ) | [inline] |
Set a rotation value for the box.
[in] | rotation | the (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.
[in] | transform | an 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.
[in] | translation | the (tx,ty,tz) values that the box should be translated by |
Definition at line 259 of file crop_box.h.
Eigen::Vector4f pcl::CropBox< sensor_msgs::PointCloud2 >::max_pt_ [protected] |
The maximum point of the box.
Definition at line 319 of file crop_box.h.
Eigen::Vector4f pcl::CropBox< sensor_msgs::PointCloud2 >::min_pt_ [protected] |
The minimum point of the box.
Definition at line 317 of file crop_box.h.
Eigen::Vector3f pcl::CropBox< sensor_msgs::PointCloud2 >::rotation_ [protected] |
The 3D rotation for the box.
Definition at line 323 of file crop_box.h.
Eigen::Affine3f pcl::CropBox< sensor_msgs::PointCloud2 >::transform_ [protected] |
The affine transform applied to the cloud.
Definition at line 325 of file crop_box.h.
Eigen::Vector3f pcl::CropBox< sensor_msgs::PointCloud2 >::translation_ [protected] |
The 3D translation for the box.
Definition at line 321 of file crop_box.h.