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

#include <convolution.h>

List of all members.

Public Types

enum  BORDERS_POLICY { BORDERS_POLICY_IGNORE = -1, BORDERS_POLICY_MIRROR = 0, BORDERS_POLICY_DUPLICATE = 1 }
 The borders policy available. More...
typedef boost::shared_ptr
< const Convolution< PointIn,
PointOut > > 
ConstPtr
typedef pcl::PointCloud< PointIn > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud< PointOut > PointCloudOut
typedef boost::shared_ptr
< Convolution< PointIn,
PointOut > > 
Ptr

Public Member Functions

 Convolution ()
 Constructor.
void convolve (const Eigen::ArrayXf &h_kernel, const Eigen::ArrayXf &v_kernel, PointCloudOut &output)
void convolve (PointCloudOut &output)
void convolveCols (PointCloudOut &output)
void convolveRows (PointCloudOut &output)
int getBordersPolicy ()
 Get the borders policy.
const float & getDistanceThreshold () const
void setBordersPolicy (int policy)
 Set the borders policy.
void setDistanceThreshold (const float &threshold)
void setInputCloud (const PointCloudInConstPtr &cloud)
 Provide a pointer to the input dataset.
void setKernel (const Eigen::ArrayXf &kernel)
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
 ~Convolution ()
 Empty destructor.

Protected Member Functions

void convolve_cols (PointCloudOut &output)
 convolve cols and ignore borders
void convolve_cols_duplicate (PointCloudOut &output)
 convolve cols and duplicate borders
void convolve_cols_mirror (PointCloudOut &output)
 convolve cols and mirror borders
void convolve_rows (PointCloudOut &output)
 convolve rows and ignore borders
void convolve_rows_duplicate (PointCloudOut &output)
 convolve rows and duplicate borders
void convolve_rows_mirror (PointCloudOut &output)
 convolve rows and mirror borders
void initCompute (PointCloudOut &output)
void makeInfinite (PointOut &p)
template<>
void makeInfinite (pcl::RGB &p)

Protected Attributes

unsigned int threads_
 The number of threads the scheduler should use.

Private Member Functions

PointOut convolveOneColDense (int i, int j)
template<>
pcl::PointXYZRGB convolveOneColDense (int i, int j)
template<>
pcl::RGB convolveOneColDense (int i, int j)
PointOut convolveOneColNonDense (int i, int j)
template<>
pcl::PointXYZRGB convolveOneColNonDense (int i, int j)
template<>
pcl::RGB convolveOneColNonDense (int i, int j)
PointOut convolveOneRowDense (int i, int j)
template<>
pcl::PointXYZRGB convolveOneRowDense (int i, int j)
template<>
pcl::RGB convolveOneRowDense (int i, int j)
PointOut convolveOneRowNonDense (int i, int j)
template<>
pcl::PointXYZRGB convolveOneRowNonDense (int i, int j)
template<>
pcl::RGB convolveOneRowNonDense (int i, int j)

Private Attributes

int borders_policy_
 Border policy.
float distance_threshold_
 Threshold distance between adjacent points.
int half_width_
 half kernel size
PointCloudInConstPtr input_
 Pointer to the input cloud.
Eigen::ArrayXf kernel_
 convolution kernel
int kernel_width_
 kernel size - 1

Detailed Description

template<typename PointIn, typename PointOut>
class pcl::filters::Convolution< PointIn, PointOut >

Convolution is a mathematical operation on two functions f and g, producing a third function that is typically viewed as a modified version of one of the original functions. see http://en.wikipedia.org/wiki/Convolution.

The class provides rows, column and separate convolving operations of a point cloud. Columns and separate convolution is only allowed on organised point clouds.

When convolving, computing the rows and cols elements at 1/2 kernel width distance from the borders is not defined. We allow for 3 policies:

Author:
Nizar Sallem

Definition at line 77 of file convolution.h.


Member Typedef Documentation

template<typename PointIn, typename PointOut>
typedef boost::shared_ptr< const Convolution<PointIn, PointOut> > pcl::filters::Convolution< PointIn, PointOut >::ConstPtr

Definition at line 85 of file convolution.h.

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

Definition at line 80 of file convolution.h.

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

Definition at line 82 of file convolution.h.

template<typename PointIn, typename PointOut>
typedef PointCloudIn::Ptr pcl::filters::Convolution< PointIn, PointOut >::PointCloudInPtr

Definition at line 81 of file convolution.h.

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

Definition at line 83 of file convolution.h.

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

Definition at line 84 of file convolution.h.


Member Enumeration Documentation

template<typename PointIn, typename PointOut>
enum pcl::filters::Convolution::BORDERS_POLICY

The borders policy available.

Enumerator:
BORDERS_POLICY_IGNORE 
BORDERS_POLICY_MIRROR 
BORDERS_POLICY_DUPLICATE 

Definition at line 89 of file convolution.h.


Constructor & Destructor Documentation

template<typename PointIn , typename PointOut >
pcl::filters::Convolution< PointIn, PointOut >::Convolution ( )

Constructor.

Definition at line 47 of file convolution.hpp.

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

Empty destructor.

Definition at line 98 of file convolution.h.


Member Function Documentation

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::convolve ( const Eigen::ArrayXf &  h_kernel,
const Eigen::ArrayXf &  v_kernel,
PointCloudOut output 
) [inline]

Convolve point cloud with an horizontal kernel along rows then vertical kernel along columns : convolve separately.

Parameters:
[in]h_kernelkernel for convolving rows
[in]v_kernelkernel for convolving columns
[out]outputthe convolved cloud
Note:
if output doesn't fit in input i.e. output.rows () < input.rows () or output.cols () < input.cols () then output is resized to input sizes.
template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::convolve ( PointCloudOut output) [inline]

Convolve point cloud with same kernel along rows and columns separately.

Parameters:
[out]outputthe convolved cloud
Note:
if output doesn't fit in input i.e. output.rows () < input.rows () or output.cols () < input.cols () then output is resized to input sizes.
template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_cols ( PointCloudOut output) [protected]

convolve cols and ignore borders

Definition at line 539 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_cols_duplicate ( PointCloudOut output) [protected]

convolve cols and duplicate borders

Definition at line 583 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_cols_mirror ( PointCloudOut output) [protected]

convolve cols and mirror borders

Definition at line 628 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_rows ( PointCloudOut output) [protected]

convolve rows and ignore borders

Definition at line 405 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_rows_duplicate ( PointCloudOut output) [protected]

convolve rows and duplicate borders

Definition at line 449 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolve_rows_mirror ( PointCloudOut output) [protected]

convolve rows and mirror borders

Definition at line 494 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolveCols ( PointCloudOut output) [inline]

Convolve a float image columns by a given kernel.

Parameters:
[in]kernelconvolution kernel
[out]outputthe convolved image
Note:
if output doesn't fit in input i.e. output.rows () < input.rows () or output.cols () < input.cols () then output is resized to input sizes.

Definition at line 109 of file convolution.hpp.

template<typename PointIn , typename PointOut >
PointOut pcl::filters::Convolution< PointIn, PointOut >::convolveOneColDense ( int  i,
int  j 
) [inline, private]
Returns:
the result of convolution of point at (, )
Note:
no test on finity is performed

Definition at line 177 of file convolution.hpp.

Definition at line 263 of file convolution.hpp.

template<>
pcl::RGB pcl::filters::Convolution< pcl::RGB, pcl::RGB >::convolveOneColDense ( int  i,
int  j 
) [private]

Definition at line 368 of file convolution.hpp.

template<typename PointIn , typename PointOut >
PointOut pcl::filters::Convolution< PointIn, PointOut >::convolveOneColNonDense ( int  i,
int  j 
) [inline, private]
Returns:
the result of convolution of point at (, )
Note:
only finite points within distance_threshold_ are accounted

Definition at line 213 of file convolution.hpp.

Definition at line 317 of file convolution.hpp.

template<>
pcl::RGB pcl::filters::Convolution< pcl::RGB, pcl::RGB >::convolveOneColNonDense ( int  i,
int  j 
) [private]

Definition at line 391 of file convolution.hpp.

template<typename PointIn , typename PointOut >
PointOut pcl::filters::Convolution< PointIn, PointOut >::convolveOneRowDense ( int  i,
int  j 
) [inline, private]
Returns:
the result of convolution of point at (, )
Note:
no test on finity is performed

Definition at line 167 of file convolution.hpp.

Definition at line 243 of file convolution.hpp.

template<>
pcl::RGB pcl::filters::Convolution< pcl::RGB, pcl::RGB >::convolveOneRowDense ( int  i,
int  j 
) [private]

Definition at line 351 of file convolution.hpp.

template<typename PointIn , typename PointOut >
PointOut pcl::filters::Convolution< PointIn, PointOut >::convolveOneRowNonDense ( int  i,
int  j 
) [inline, private]
Returns:
the result of convolution of point at (, )
Note:
only finite points within distance_threshold_ are accounted

Definition at line 187 of file convolution.hpp.

Definition at line 283 of file convolution.hpp.

template<>
pcl::RGB pcl::filters::Convolution< pcl::RGB, pcl::RGB >::convolveOneRowNonDense ( int  i,
int  j 
) [private]

Definition at line 385 of file convolution.hpp.

template<typename PointIn , typename PointOut >
void pcl::filters::Convolution< PointIn, PointOut >::convolveRows ( PointCloudOut output) [inline]

Convolve a float image rows by a given kernel.

Parameters:
[in]kernelconvolution kernel
[out]outputthe convolved cloud
Note:
if output doesn't fit in input i.e. output.rows () < input.rows () or output.cols () < input.cols () then output is resized to input sizes.

Definition at line 89 of file convolution.hpp.

template<typename PointIn, typename PointOut>
int pcl::filters::Convolution< PointIn, PointOut >::getBordersPolicy ( ) [inline]

Get the borders policy.

Definition at line 115 of file convolution.h.

template<typename PointIn, typename PointOut>
const float& pcl::filters::Convolution< PointIn, PointOut >::getDistanceThreshold ( ) const [inline]
Returns:
the distance threshold

Definition at line 127 of file convolution.h.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::initCompute ( PointCloudOut output) [protected]

init compute is an internal method called before computation

Parameters:
[in]kernelconvolution kernel to be used
Exceptions:
pcl::InitFailedException

Definition at line 58 of file convolution.hpp.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::makeInfinite ( PointOut &  p) [inline, protected]

Definition at line 231 of file convolution.h.

template<>
void pcl::filters::Convolution< pcl::RGB, pcl::RGB >::makeInfinite ( pcl::RGB p) [protected]

Definition at line 397 of file convolution.hpp.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::setBordersPolicy ( int  policy) [inline]

Set the borders policy.

Definition at line 112 of file convolution.h.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::setDistanceThreshold ( const float &  threshold) [inline]
Remarks:
this is critical so please read it carefully. In 3D the next point in (u,v) coordinate can be really far so a distance threshold is used to keep us from ghost points. The value you set here is strongly related to the sensor. A good value for kinect data is 0.001 is std::numeric<float>::infinity ()
Parameters:
[in]thresholdmaximum allowed distance between 2 juxtaposed points

Definition at line 124 of file convolution.h.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::setInputCloud ( const PointCloudInConstPtr cloud) [inline]

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message
Remarks:
Will perform a deep copy

Definition at line 104 of file convolution.h.

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

Set convolving kernel

Parameters:
[in]kernelconvolving element

Definition at line 109 of file convolution.h.

template<typename PointIn, typename PointOut>
void pcl::filters::Convolution< PointIn, PointOut >::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 132 of file convolution.h.


Member Data Documentation

template<typename PointIn, typename PointOut>
int pcl::filters::Convolution< PointIn, PointOut >::borders_policy_ [private]

Border policy.

Definition at line 215 of file convolution.h.

template<typename PointIn, typename PointOut>
float pcl::filters::Convolution< PointIn, PointOut >::distance_threshold_ [private]

Threshold distance between adjacent points.

Definition at line 217 of file convolution.h.

template<typename PointIn, typename PointOut>
int pcl::filters::Convolution< PointIn, PointOut >::half_width_ [private]

half kernel size

Definition at line 223 of file convolution.h.

template<typename PointIn, typename PointOut>
PointCloudInConstPtr pcl::filters::Convolution< PointIn, PointOut >::input_ [private]

Pointer to the input cloud.

Definition at line 219 of file convolution.h.

template<typename PointIn, typename PointOut>
Eigen::ArrayXf pcl::filters::Convolution< PointIn, PointOut >::kernel_ [private]

convolution kernel

Definition at line 221 of file convolution.h.

template<typename PointIn, typename PointOut>
int pcl::filters::Convolution< PointIn, PointOut >::kernel_width_ [private]

kernel size - 1

Definition at line 225 of file convolution.h.

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

The number of threads the scheduler should use.

Definition at line 228 of file convolution.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:53