Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::filters::Convolution3D< PointIn, PointOut, KernelT > Class Template Reference

#include <convolution_3d.h>

Inheritance diagram for pcl::filters::Convolution3D< PointIn, PointOut, KernelT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< Convolution3D< PointIn,
PointOut, KernelT > > 
ConstPtr
typedef pcl::search::Search
< PointIn > 
KdTree
typedef pcl::search::Search
< PointIn >::Ptr 
KdTreePtr
typedef pcl::PointCloud< PointIn > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef pcl::PointCloud< PointOut > PointCloudOut
typedef boost::shared_ptr
< Convolution3D< PointIn,
PointOut, KernelT > > 
Ptr

Public Member Functions

 Convolution3D ()
 Constructor.
void convolve (PointCloudOut &output)
double getRadiusSearch ()
 Get the sphere radius used for determining the neighbors.
KdTreePtr getSearchMethod ()
 Get a pointer to the search method used.
PointCloudInConstPtr getSearchSurface ()
 Get a pointer to the surface point cloud dataset.
void setKernel (const KernelT &kernel)
 Set convolving kernel.
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
void setRadiusSearch (double radius)
 Set the sphere radius that is to be used for determining the nearest neighbors.
void setSearchMethod (const KdTreePtr &tree)
 Provide a pointer to the search object.
void setSearchSurface (const PointCloudInConstPtr &cloud)
 Provide a pointer to the input dataset that we need to estimate features at every point for.
 ~Convolution3D ()
 Empty destructor.

Protected Member Functions

bool initCompute ()
 initialize computation

Protected Attributes

KernelT kernel_
 convlving kernel
double search_radius_
 The nearest neighbors search radius for each point.
PointCloudInConstPtr surface_
 An input point cloud describing the surface that is to be used for nearest neighbors estimation.
unsigned int threads_
 number of threads
KdTreePtr tree_
 A pointer to the spatial search object.

Detailed Description

template<typename PointIn, typename PointOut, typename KernelT>
class pcl::filters::Convolution3D< PointIn, PointOut, KernelT >

Convolution3D handles the non organized case where width and height are unknown or if you are only interested in convolving based on local neighborhood information. The convolving kernel MUST be a radial symmetric and implement ConvolvingKernel interface.

Definition at line 200 of file convolution_3d.h.


Member Typedef Documentation

template<typename PointIn , typename PointOut , typename KernelT >
typedef boost::shared_ptr<Convolution3D<PointIn, PointOut, KernelT> > pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::ConstPtr

Definition at line 209 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef pcl::search::Search<PointIn> pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::KdTree

Definition at line 205 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef pcl::search::Search<PointIn>::Ptr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::KdTreePtr

Definition at line 206 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef pcl::PointCloud<PointIn> pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::PointCloudIn

Definition at line 203 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef PointCloudIn::ConstPtr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::PointCloudInConstPtr

Definition at line 204 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef pcl::PointCloud<PointOut> pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::PointCloudOut

Definition at line 207 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
typedef boost::shared_ptr<Convolution3D<PointIn, PointOut, KernelT> > pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::Ptr

Definition at line 208 of file convolution_3d.h.


Constructor & Destructor Documentation

template<typename PointInT , typename PointOutT , typename KernelT >
pcl::filters::Convolution3D< PointInT, PointOutT, KernelT >::Convolution3D ( )

Constructor.

Definition at line 171 of file convolution_3d.hpp.

template<typename PointIn , typename PointOut , typename KernelT >
pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::~Convolution3D ( ) [inline]

Empty destructor.

Definition at line 218 of file convolution_3d.h.


Member Function Documentation

template<typename PointInT , typename PointOutT , typename KernelT >
void pcl::filters::Convolution3D< PointInT, PointOutT, KernelT >::convolve ( PointCloudOut output)

Convolve point cloud.

Parameters:
[out]outputthe convolved cloud

Definition at line 226 of file convolution_3d.hpp.

template<typename PointIn , typename PointOut , typename KernelT >
double pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::getRadiusSearch ( ) [inline]

Get the sphere radius used for determining the neighbors.

Definition at line 260 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
KdTreePtr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::getSearchMethod ( ) [inline]

Get a pointer to the search method used.

Definition at line 250 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
PointCloudInConstPtr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::getSearchSurface ( ) [inline]

Get a pointer to the surface point cloud dataset.

Definition at line 240 of file convolution_3d.h.

template<typename PointInT , typename PointOutT , typename KernelT >
bool pcl::filters::Convolution3D< PointInT, PointOutT, KernelT >::initCompute ( ) [protected]

initialize computation

Reimplemented from pcl::PCLBase< PointIn >.

Definition at line 180 of file convolution_3d.hpp.

template<typename PointIn , typename PointOut , typename KernelT >
void pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::setKernel ( const KernelT &  kernel) [inline]

Set convolving kernel.

Parameters:
[in]kernelconvolving element

Definition at line 230 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
void pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::setNumberOfThreads ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 224 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
void pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::setRadiusSearch ( double  radius) [inline]

Set the sphere radius that is to be used for determining the nearest neighbors.

Parameters:
radiusthe sphere radius used as the maximum distance to consider a point a neighbor

Definition at line 256 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
void pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::setSearchMethod ( const KdTreePtr tree) [inline]

Provide a pointer to the search object.

Parameters:
treea pointer to the spatial search object.

Definition at line 246 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
void pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::setSearchSurface ( const PointCloudInConstPtr cloud) [inline]

Provide a pointer to the input dataset that we need to estimate features at every point for.

Parameters:
cloudthe const boost shared pointer to a PointCloud message

Definition at line 236 of file convolution_3d.h.


Member Data Documentation

template<typename PointIn , typename PointOut , typename KernelT >
KernelT pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::kernel_ [protected]

convlving kernel

Definition at line 285 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
double pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::search_radius_ [protected]

The nearest neighbors search radius for each point.

Definition at line 279 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
PointCloudInConstPtr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::surface_ [protected]

An input point cloud describing the surface that is to be used for nearest neighbors estimation.

Definition at line 273 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
unsigned int pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::threads_ [protected]

number of threads

Definition at line 282 of file convolution_3d.h.

template<typename PointIn , typename PointOut , typename KernelT >
KdTreePtr pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 276 of file convolution_3d.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:55