Public Types | Public Member Functions | Protected Member Functions | Private Attributes
pcl::PlaneClipper3D< PointT > Class Template Reference

Implementation of a plane clipper in 3D. More...

#include <plane_clipper3D.h>

Inheritance diagram for pcl::PlaneClipper3D< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const PlaneClipper3D< PointT > > 
ConstPtr
typedef boost::shared_ptr
< PlaneClipper3D< PointT > > 
Ptr

Public Member Functions

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.
const Eigen::Vector4f & getPlaneParameters () const
 return the current plane parameters
 PlaneClipper3D (const Eigen::Vector4f &plane_params)
 Constructor taking the homogeneous representation of the plane as a Eigen::Vector4f.
void setPlaneParameters (const Eigen::Vector4f &plane_params)
 Set new plane parameters.
virtual ~PlaneClipper3D () throw ()

Protected Member Functions

float getDistance (const PointT &point) const

Private Attributes

Eigen::Vector4f plane_params_

Detailed Description

template<typename PointT>
class pcl::PlaneClipper3D< PointT >

Implementation of a plane clipper in 3D.

Author:
Suat Gedikli <gedikli@willowgarage.com>

Definition at line 50 of file plane_clipper3D.h.


Member Typedef Documentation

template<typename PointT >
typedef boost::shared_ptr< const PlaneClipper3D<PointT> > pcl::PlaneClipper3D< PointT >::ConstPtr

Reimplemented from pcl::Clipper3D< PointT >.

Definition at line 55 of file plane_clipper3D.h.

template<typename PointT >
typedef boost::shared_ptr< PlaneClipper3D<PointT> > pcl::PlaneClipper3D< PointT >::Ptr

Reimplemented from pcl::Clipper3D< PointT >.

Definition at line 54 of file plane_clipper3D.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::PlaneClipper3D< PointT >::PlaneClipper3D ( const Eigen::Vector4f &  plane_params)

Constructor taking the homogeneous representation of the plane as a Eigen::Vector4f.

Author:
Suat Gedikli <gedikli@willowgarage.com>
Parameters:
[in]plane_paramsplane parameters, need not necessarily be normalized

Definition at line 41 of file plane_clipper3D.hpp.

template<typename PointT >
pcl::PlaneClipper3D< PointT >::~PlaneClipper3D ( ) throw () [virtual]

Definition at line 47 of file plane_clipper3D.hpp.


Member Function Documentation

template<typename PointT >
bool pcl::PlaneClipper3D< PointT >::clipLineSegment3D ( PointT point1,
PointT point2 
) const [virtual]
Attention:
untested code

Implements pcl::Clipper3D< PointT >.

Definition at line 85 of file plane_clipper3D.hpp.

template<typename PointT >
void pcl::PlaneClipper3D< PointT >::clipPlanarPolygon3D ( std::vector< PointT > &  polygon) const [virtual]
Attention:
untested code

Implements pcl::Clipper3D< PointT >.

Definition at line 171 of file plane_clipper3D.hpp.

template<typename PointT >
void pcl::PlaneClipper3D< PointT >::clipPlanarPolygon3D ( const std::vector< PointT > &  polygon,
std::vector< PointT > &  clipped_polygon 
) const [virtual]
Attention:
untested code

Implements pcl::Clipper3D< PointT >.

Definition at line 114 of file plane_clipper3D.hpp.

template<typename PointT >
bool pcl::PlaneClipper3D< PointT >::clipPoint3D ( const PointT point) const [virtual]

interface to clip a single point

Parameters:
[in]pointthe point to check against
Returns:
true, it point still exists, false if its clipped

Implements pcl::Clipper3D< PointT >.

Definition at line 76 of file plane_clipper3D.hpp.

template<typename PointT >
void pcl::PlaneClipper3D< 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

Parameters:
[in]cloud_ininput point cloud
[out]clippedindices of points that remain after clipping the input cloud
[in]indicesthe indices of points in the point cloud to be clipped.
Returns:
list of indices of remaining points after clipping.

Implements pcl::Clipper3D< PointT >.

Definition at line 180 of file plane_clipper3D.hpp.

template<typename PointT >
pcl::Clipper3D< PointT > * pcl::PlaneClipper3D< PointT >::clone ( ) const [virtual]

polymorphic method to clone the underlying clipper with its parameters.

Returns:
the new clipper object from the specific subclass with all its parameters.

Implements pcl::Clipper3D< PointT >.

Definition at line 64 of file plane_clipper3D.hpp.

template<typename PointT >
float pcl::PlaneClipper3D< PointT >::getDistance ( const PointT point) const [protected]

Definition at line 70 of file plane_clipper3D.hpp.

template<typename PointT >
const Eigen::Vector4f & pcl::PlaneClipper3D< PointT >::getPlaneParameters ( ) const

return the current plane parameters

Returns:
the current plane parameters

Definition at line 58 of file plane_clipper3D.hpp.

template<typename PointT >
void pcl::PlaneClipper3D< PointT >::setPlaneParameters ( const Eigen::Vector4f &  plane_params)

Set new plane parameters.

Parameters:
plane_params

Definition at line 52 of file plane_clipper3D.hpp.


Member Data Documentation

template<typename PointT >
Eigen::Vector4f pcl::PlaneClipper3D< PointT >::plane_params_ [private]

Definition at line 101 of file plane_clipper3D.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:00