Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. The affine transformation is used to transform the point before clipping it using the unit cube centered at origin and with an extend of -1 to +1 in each dimension. More...
#include <box_clipper3D.h>
Public Types | |
typedef boost::shared_ptr < const BoxClipper3D< PointT > > | ConstPtr |
typedef boost::shared_ptr < BoxClipper3D< PointT > > | Ptr |
Public Member Functions | |
BoxClipper3D (const Eigen::Affine3f &transformation) | |
Constructor taking an affine transformation matrix, which allows also shearing of the clipping area. | |
BoxClipper3D (const Eigen::Vector3f &rodrigues, const Eigen::Vector3f &translation, const Eigen::Vector3f &box_size) | |
creates a BoxClipper object with a scaled box in general pose | |
virtual bool | clipLineSegment3D (PointT &from, PointT &to) const |
virtual void | clipPlanarPolygon3D (std::vector< PointT > &polygon) const |
virtual void | clipPlanarPolygon3D (const std::vector< PointT > &polygon, std::vector< PointT > &clipped_polygon) const |
virtual bool | clipPoint3D (const PointT &point) const |
interface to clip a single point | |
virtual void | clipPointCloud3D (const pcl::PointCloud< PointT > &cloud_in, std::vector< int > &clipped, const std::vector< int > &indices=std::vector< int >()) const |
interface to clip a point cloud | |
virtual Clipper3D< PointT > * | clone () const |
polymorphic method to clone the underlying clipper with its parameters. | |
void | setTransformation (const Eigen::Affine3f &transformation) |
Set the affine transformation. | |
void | setTransformation (const Eigen::Vector3f &rodrigues, const Eigen::Vector3f &translation, const Eigen::Vector3f &box_size) |
sets the box in general pose given by the orientation position and size | |
virtual | ~BoxClipper3D () throw () |
virtual destructor | |
Protected Member Functions | |
float | getDistance (const PointT &point) const |
void | transformPoint (const PointT &pointIn, PointT &pointOut) const |
Private Attributes | |
Eigen::Affine3f | transformation_ |
the affine transformation that is applied before clipping is done on the unit cube. |
Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. The affine transformation is used to transform the point before clipping it using the unit cube centered at origin and with an extend of -1 to +1 in each dimension.
Definition at line 51 of file box_clipper3D.h.
typedef boost::shared_ptr< const BoxClipper3D<PointT> > pcl::BoxClipper3D< PointT >::ConstPtr |
Reimplemented from pcl::Clipper3D< PointT >.
Definition at line 56 of file box_clipper3D.h.
typedef boost::shared_ptr< BoxClipper3D<PointT> > pcl::BoxClipper3D< PointT >::Ptr |
Reimplemented from pcl::Clipper3D< PointT >.
Definition at line 55 of file box_clipper3D.h.
pcl::BoxClipper3D< PointT >::BoxClipper3D | ( | const Eigen::Affine3f & | transformation | ) |
Constructor taking an affine transformation matrix, which allows also shearing of the clipping area.
[in] | transformation | the 3x3 affine transformation matrix that is used to describe the unit cube |
Definition at line 41 of file box_clipper3D.hpp.
pcl::BoxClipper3D< PointT >::BoxClipper3D | ( | const Eigen::Vector3f & | rodrigues, |
const Eigen::Vector3f & | translation, | ||
const Eigen::Vector3f & | box_size | ||
) |
creates a BoxClipper object with a scaled box in general pose
[in] | rodrigues | the rotation axis and angle given by the vector direction and length respectively |
[in] | translation | the position of the box center |
[in] | box_size | the size of the box for each dimension |
Definition at line 49 of file box_clipper3D.hpp.
pcl::BoxClipper3D< PointT >::~BoxClipper3D | ( | ) | throw () [virtual] |
virtual destructor
Definition at line 56 of file box_clipper3D.hpp.
bool pcl::BoxClipper3D< PointT >::clipLineSegment3D | ( | PointT & | point1, |
PointT & | point2 | ||
) | const [virtual] |
Implements pcl::Clipper3D< PointT >.
Definition at line 133 of file box_clipper3D.hpp.
void pcl::BoxClipper3D< PointT >::clipPlanarPolygon3D | ( | std::vector< PointT > & | polygon | ) | const [virtual] |
Implements pcl::Clipper3D< PointT >.
Definition at line 197 of file box_clipper3D.hpp.
void pcl::BoxClipper3D< PointT >::clipPlanarPolygon3D | ( | const std::vector< PointT > & | polygon, |
std::vector< PointT > & | clipped_polygon | ||
) | const [virtual] |
Implements pcl::Clipper3D< PointT >.
Definition at line 186 of file box_clipper3D.hpp.
bool pcl::BoxClipper3D< PointT >::clipPoint3D | ( | const PointT & | point | ) | const [virtual] |
interface to clip a single point
[in] | point | the point to check against |
Implements pcl::Clipper3D< PointT >.
Definition at line 112 of file box_clipper3D.hpp.
void pcl::BoxClipper3D< PointT >::clipPointCloud3D | ( | const pcl::PointCloud< PointT > & | cloud_in, |
std::vector< int > & | clipped, | ||
const std::vector< int > & | indices = std::vector< int >() |
||
) | const [virtual] |
interface to clip a point cloud
[in] | cloud_in | input point cloud |
[out] | clipped | indices of points that remain after clipping the input cloud |
[in] | indices | the indices of points in the point cloud to be clipped. |
Implements pcl::Clipper3D< PointT >.
Definition at line 206 of file box_clipper3D.hpp.
pcl::Clipper3D< PointT > * pcl::BoxClipper3D< PointT >::clone | ( | ) | const [virtual] |
polymorphic method to clone the underlying clipper with its parameters.
Implements pcl::Clipper3D< PointT >.
Definition at line 78 of file box_clipper3D.hpp.
float pcl::BoxClipper3D< PointT >::getDistance | ( | const PointT & | point | ) | const [protected] |
void pcl::BoxClipper3D< PointT >::setTransformation | ( | const Eigen::Affine3f & | transformation | ) |
Set the affine transformation.
[in] | transformation |
Definition at line 62 of file box_clipper3D.hpp.
void pcl::BoxClipper3D< PointT >::setTransformation | ( | const Eigen::Vector3f & | rodrigues, |
const Eigen::Vector3f & | translation, | ||
const Eigen::Vector3f & | box_size | ||
) |
sets the box in general pose given by the orientation position and size
[in] | rodrigues | the rotation axis and angle given by the vector direction and length respectively |
[in] | translation | the position of the box center |
[in] | box_size | the size of the box for each dimension |
Definition at line 70 of file box_clipper3D.hpp.
void pcl::BoxClipper3D< PointT >::transformPoint | ( | const PointT & | pointIn, |
PointT & | pointOut | ||
) | const [protected] |
Definition at line 85 of file box_clipper3D.hpp.
Eigen::Affine3f pcl::BoxClipper3D< PointT >::transformation_ [private] |
the affine transformation that is applied before clipping is done on the unit cube.
Definition at line 118 of file box_clipper3D.h.