Public Types | Public Member Functions | Private Member Functions | Private Attributes
pcl::filters::Pyramid< PointT > Class Template Reference

#include <pyramid.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const Pyramid< PointT > > 
ConstPtr
typedef PointCloud< PointT >
::ConstPtr 
PointCloudConstPtr
typedef PointCloud< PointT >::Ptr PointCloudPtr
typedef boost::shared_ptr
< Pyramid< PointT > > 
Ptr

Public Member Functions

void compute (std::vector< PointCloudPtr > &output)
 compute the pyramid levels.
template<>
void compute (std::vector< Pyramid< pcl::PointXYZRGB >::PointCloudPtr > &output)
template<>
void compute (std::vector< Pyramid< pcl::PointXYZRGBA >::PointCloudPtr > &output)
template<>
void compute (std::vector< Pyramid< pcl::RGB >::PointCloudPtr > &output)
const std::stringgetClassName () const
float getDistanceThreshold () const
PointCloudConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset.
int getNumberOfLevels () const
 Pyramid (int levels=4)
void setDistanceThreshold (float threshold)
void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
void setLargeSmoothingKernel (bool large)
 Choose a larger smoothing kernel for enhanced smoothing.
void setNumberOfLevels (int levels)
 Set the number of pyramid levels.
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.

Private Member Functions

bool initCompute ()
 init computation
void nullify (PointT &p) const
 nullify a point
template<>
void nullify (pcl::RGB &p)

Private Attributes

PointCloudConstPtr input_
 The input point cloud dataset.
Eigen::MatrixXf kernel_
 smoothing kernel
bool large_
 use large smoothing kernel
int levels_
 number of pyramid levels
std::string name_
 filter name
unsigned int threads_
 number of threads
float threshold_
 Threshold distance between adjacent points.

Detailed Description

template<typename PointT>
class pcl::filters::Pyramid< PointT >

Pyramid constructs a multi-scale representation of an organised point cloud. It is an iterative smoothing subsampling algorithm. The subsampling is fixed to 2. Two smoothing kernels may be used:

Author:
Nizar Sallem

Definition at line 62 of file pyramid.h.


Member Typedef Documentation

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

Definition at line 68 of file pyramid.h.

template<typename PointT>
typedef PointCloud<PointT>::ConstPtr pcl::filters::Pyramid< PointT >::PointCloudConstPtr

Definition at line 66 of file pyramid.h.

template<typename PointT>
typedef PointCloud<PointT>::Ptr pcl::filters::Pyramid< PointT >::PointCloudPtr

Definition at line 65 of file pyramid.h.

template<typename PointT>
typedef boost::shared_ptr< Pyramid<PointT> > pcl::filters::Pyramid< PointT >::Ptr

Definition at line 67 of file pyramid.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::filters::Pyramid< PointT >::Pyramid ( int  levels = 4) [inline]

Definition at line 70 of file pyramid.h.


Member Function Documentation

template<typename PointT >
void pcl::filters::Pyramid< PointT >::compute ( std::vector< PointCloudPtr > &  output)

compute the pyramid levels.

Parameters:
[out]outputthe constructed pyramid. It is resized to the number of levels.
Remarks:
input_ is copied to output[0] for consistency reasons.

Definition at line 90 of file pyramid.hpp.

template<>
void pcl::filters::Pyramid< pcl::PointXYZRGB >::compute ( std::vector< Pyramid< pcl::PointXYZRGB >::PointCloudPtr > &  output)

Definition at line 197 of file pyramid.hpp.

template<>
void pcl::filters::Pyramid< pcl::PointXYZRGBA >::compute ( std::vector< Pyramid< pcl::PointXYZRGBA >::PointCloudPtr > &  output)

Definition at line 320 of file pyramid.hpp.

template<>
void pcl::filters::Pyramid< pcl::RGB >::compute ( std::vector< Pyramid< pcl::RGB >::PointCloudPtr > &  output)

Definition at line 453 of file pyramid.hpp.

template<typename PointT>
const std::string& pcl::filters::Pyramid< PointT >::getClassName ( ) const [inline]

Definition at line 131 of file pyramid.h.

template<typename PointT>
float pcl::filters::Pyramid< PointT >::getDistanceThreshold ( ) const [inline]
Returns:
the distance threshold

Definition at line 121 of file pyramid.h.

template<typename PointT>
PointCloudConstPtr const pcl::filters::Pyramid< PointT >::getInputCloud ( ) [inline]

Get a pointer to the input point cloud dataset.

Definition at line 87 of file pyramid.h.

template<typename PointT>
int pcl::filters::Pyramid< PointT >::getNumberOfLevels ( ) const [inline]
Returns:
the number of pyramid levels

Definition at line 97 of file pyramid.h.

template<typename PointT >
bool pcl::filters::Pyramid< PointT >::initCompute ( ) [private]

init computation

Definition at line 44 of file pyramid.hpp.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::nullify ( PointT p) const [inline, private]

nullify a point

Parameters:
[in]out]p point to nullify

Definition at line 143 of file pyramid.h.

template<>
void pcl::filters::Pyramid< pcl::RGB >::nullify ( pcl::RGB p) [private]

Definition at line 447 of file pyramid.hpp.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::setDistanceThreshold ( float  threshold) [inline]

Only points such us distance (center,point) < threshold are accounted for to prevent ghost points. Default value is 0.01, to disable set to std::numeric<float>::infinity ().

Parameters:
[in]thresholdmaximum allowed distance between center and neighbor.

Definition at line 117 of file pyramid.h.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::setInputCloud ( const PointCloudConstPtr cloud) [inline]

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message

Definition at line 83 of file pyramid.h.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::setLargeSmoothingKernel ( bool  large) [inline]

Choose a larger smoothing kernel for enhanced smoothing.

Parameters:
largeif true large smoothng kernel will be used.

Definition at line 109 of file pyramid.h.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::setNumberOfLevels ( int  levels) [inline]

Set the number of pyramid levels.

Parameters:
levelsdesired number of pyramid levels

Definition at line 93 of file pyramid.h.

template<typename PointT>
void pcl::filters::Pyramid< PointT >::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 103 of file pyramid.h.


Member Data Documentation

template<typename PointT>
PointCloudConstPtr pcl::filters::Pyramid< PointT >::input_ [private]

The input point cloud dataset.

Definition at line 149 of file pyramid.h.

template<typename PointT>
Eigen::MatrixXf pcl::filters::Pyramid< PointT >::kernel_ [private]

smoothing kernel

Definition at line 157 of file pyramid.h.

template<typename PointT>
bool pcl::filters::Pyramid< PointT >::large_ [private]

use large smoothing kernel

Definition at line 153 of file pyramid.h.

template<typename PointT>
int pcl::filters::Pyramid< PointT >::levels_ [private]

number of pyramid levels

Definition at line 151 of file pyramid.h.

template<typename PointT>
std::string pcl::filters::Pyramid< PointT >::name_ [private]

filter name

Definition at line 155 of file pyramid.h.

template<typename PointT>
unsigned int pcl::filters::Pyramid< PointT >::threads_ [private]

number of threads

Definition at line 161 of file pyramid.h.

template<typename PointT>
float pcl::filters::Pyramid< PointT >::threshold_ [private]

Threshold distance between adjacent points.

Definition at line 159 of file pyramid.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