#include <gaussian.h>
Public Member Functions | |
void | compute (float sigma, Eigen::VectorXf &kernel, unsigned kernel_width=MAX_KERNEL_WIDTH) const |
void | compute (float sigma, Eigen::VectorXf &kernel, Eigen::VectorXf &derivative, unsigned kernel_width=MAX_KERNEL_WIDTH) const |
void | computeGradients (const pcl::PointCloud< float > &input, const Eigen::VectorXf &gaussian_kernel, const Eigen::VectorXf &gaussian_kernel_derivative, pcl::PointCloud< float > &grad_x, pcl::PointCloud< float > &grad_y) const |
template<typename PointT > | |
void | computeGradients (const pcl::PointCloud< PointT > &input, boost::function< float(const PointT &p)> field_accessor, const Eigen::VectorXf &gaussian_kernel, const Eigen::VectorXf &gaussian_kernel_derivative, pcl::PointCloud< float > &grad_x, pcl::PointCloud< float > &grad_y) const |
void | convolve (const pcl::PointCloud< float > &input, const Eigen::VectorXf &horiz_kernel, const Eigen::VectorXf &vert_kernel, pcl::PointCloud< float > &output) const |
template<typename PointT > | |
void | convolve (const pcl::PointCloud< PointT > &input, boost::function< float(const PointT &p)> field_accessor, const Eigen::VectorXf &horiz_kernel, const Eigen::VectorXf &vert_kernel, pcl::PointCloud< float > &output) const |
void | convolveCols (const pcl::PointCloud< float > &input, const Eigen::VectorXf &kernel, pcl::PointCloud< float > &output) const |
template<typename PointT > | |
void | convolveCols (const pcl::PointCloud< PointT > &input, boost::function< float(const PointT &p)> field_accessor, const Eigen::VectorXf &kernel, pcl::PointCloud< float > &output) const |
void | convolveRows (const pcl::PointCloud< float > &input, const Eigen::VectorXf &kernel, pcl::PointCloud< float > &output) const |
template<typename PointT > | |
void | convolveRows (const pcl::PointCloud< PointT > &input, boost::function< float(const PointT &p)> field_accessor, const Eigen::VectorXf &kernel, pcl::PointCloud< float > &output) const |
GaussianKernel () | |
void | smooth (const pcl::PointCloud< float > &input, const Eigen::VectorXf &gaussian_kernel, pcl::PointCloud< float > &output) const |
template<typename PointT > | |
void | smooth (const pcl::PointCloud< PointT > &input, boost::function< float(const PointT &p)> field_accessor, const Eigen::VectorXf &gaussian_kernel, pcl::PointCloud< float > &output) const |
Static Public Attributes | |
static const unsigned | MAX_KERNEL_WIDTH = 71 |
Class GaussianKernel assembles all the method for computing, convolving, smoothing, gradients computing an image using a gaussian kernel. The image is stored in point cloud elements intensity member or rgb or...
Definition at line 57 of file gaussian.h.
pcl::GaussianKernel::GaussianKernel | ( | ) | [inline] |
Definition at line 61 of file gaussian.h.
void pcl::GaussianKernel::compute | ( | float | sigma, |
Eigen::VectorXf & | kernel, | ||
unsigned | kernel_width = MAX_KERNEL_WIDTH |
||
) | const |
Computes the gaussian kernel and dervative assiociated to sigma. The kernel and derivative width are adjusted according.
[in] | sigma | |
[out] | kernel | the computed gaussian kernel |
[in] | kernel_width | the desired kernel width upper bond |
pcl::KernelWidthTooSmallException |
Definition at line 41 of file gaussian.cpp.
void pcl::GaussianKernel::compute | ( | float | sigma, |
Eigen::VectorXf & | kernel, | ||
Eigen::VectorXf & | derivative, | ||
unsigned | kernel_width = MAX_KERNEL_WIDTH |
||
) | const |
Computes the gaussian kernel and dervative assiociated to sigma. The kernel and derivative width are adjusted according.
[in] | sigma | |
[out] | kernel | the computed gaussian kernel |
[out] | derivative | the computed kernel derivative |
[in] | kernel_width | the desired kernel width upper bond |
pcl::KernelWidthTooSmallException |
Definition at line 76 of file gaussian.cpp.
void pcl::GaussianKernel::computeGradients | ( | const pcl::PointCloud< float > & | input, |
const Eigen::VectorXf & | gaussian_kernel, | ||
const Eigen::VectorXf & | gaussian_kernel_derivative, | ||
pcl::PointCloud< float > & | grad_x, | ||
pcl::PointCloud< float > & | grad_y | ||
) | const [inline] |
Computes float image gradients using a gaussian kernel and gaussian kernel derivative.
[in] | input | image to compute gardients for |
[in] | gaussian_kernel | the gaussian kernel to be used |
[in] | gaussian_kernel_derivative | the associated derivative |
[out] | grad_x | gradient along X direction |
[out] | grad_y | gradient along Y direction |
Definition at line 197 of file gaussian.h.
void pcl::GaussianKernel::computeGradients | ( | const pcl::PointCloud< PointT > & | input, |
boost::function< float(const PointT &p)> | field_accessor, | ||
const Eigen::VectorXf & | gaussian_kernel, | ||
const Eigen::VectorXf & | gaussian_kernel_derivative, | ||
pcl::PointCloud< float > & | grad_x, | ||
pcl::PointCloud< float > & | grad_y | ||
) | const [inline] |
Computes float image gradients using a gaussian kernel and gaussian kernel derivative.
[in] | input | image to compute gardients for |
[in] | field_accessor | a field accessor |
[in] | gaussian_kernel | the gaussian kernel to be used |
[in] | gaussian_kernel_derivative | the associated derivative |
[out] | grad_x | gradient along X direction |
[out] | grad_y | gradient along Y direction |
Definition at line 219 of file gaussian.h.
void pcl::GaussianKernel::convolve | ( | const pcl::PointCloud< float > & | input, |
const Eigen::VectorXf & | horiz_kernel, | ||
const Eigen::VectorXf & | vert_kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const [inline] |
Convolve a float image in the 2 directions
[in] | horiz_kernel | kernel for convolving rows |
[in] | vert_kernel | kernel for convolving columns |
[in] | input | image to convolve |
[out] | output | the convolved image |
Definition at line 151 of file gaussian.h.
void pcl::GaussianKernel::convolve | ( | const pcl::PointCloud< PointT > & | input, |
boost::function< float(const PointT &p)> | field_accessor, | ||
const Eigen::VectorXf & | horiz_kernel, | ||
const Eigen::VectorXf & | vert_kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const [inline] |
Convolve a float image in the 2 directions
[in] | input | image to convolve |
[in] | field_accessor | a field accessor |
[in] | horiz_kernel | kernel for convolving rows |
[in] | vert_kernel | kernel for convolving columns |
[out] | output | the convolved image |
Definition at line 173 of file gaussian.h.
void pcl::GaussianKernel::convolveCols | ( | const pcl::PointCloud< float > & | input, |
const Eigen::VectorXf & | kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const |
Convolve a float image columns by a given kernel.
[in] | input | the image to convolve |
[in] | kernel | convolution kernel |
[out] | output | the convolved image |
Definition at line 179 of file gaussian.cpp.
void pcl::GaussianKernel::convolveCols | ( | const pcl::PointCloud< PointT > & | input, |
boost::function< float(const PointT &p)> | field_accessor, | ||
const Eigen::VectorXf & | kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const |
Convolve a float image columns by a given kernel.
[in] | input | the image to convolve |
[in] | field_accessor | a field accessor |
[in] | kernel | convolution kernel |
[out] | output | the convolved image |
Definition at line 79 of file gaussian.hpp.
void pcl::GaussianKernel::convolveRows | ( | const pcl::PointCloud< float > & | input, |
const Eigen::VectorXf & | kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const |
Convolve a float image rows by a given kernel.
[in] | kernel | convolution kernel |
[in] | input | the image to convolve |
[out] | output | the convolved image |
Definition at line 134 of file gaussian.cpp.
void pcl::GaussianKernel::convolveRows | ( | const pcl::PointCloud< PointT > & | input, |
boost::function< float(const PointT &p)> | field_accessor, | ||
const Eigen::VectorXf & | kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const |
Convolve a float image rows by a given kernel.
[in] | input | the image to convolve |
[in] | field_accessor | a field accessor |
[in] | kernel | convolution kernel |
[out] | output | the convolved image |
Definition at line 46 of file gaussian.hpp.
void pcl::GaussianKernel::smooth | ( | const pcl::PointCloud< float > & | input, |
const Eigen::VectorXf & | gaussian_kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const [inline] |
Smooth image using a gaussian kernel.
[in] | input | image |
[in] | gaussian_kernel | the gaussian kernel to be used |
[out] | output | the smoothed image |
Definition at line 238 of file gaussian.h.
void pcl::GaussianKernel::smooth | ( | const pcl::PointCloud< PointT > & | input, |
boost::function< float(const PointT &p)> | field_accessor, | ||
const Eigen::VectorXf & | gaussian_kernel, | ||
pcl::PointCloud< float > & | output | ||
) | const [inline] |
Smooth image using a gaussian kernel.
[in] | input | image |
[in] | field_accessor | a field accessor |
[in] | gaussian_kernel | the gaussian kernel to be used |
[out] | output | the smoothed image |
Definition at line 254 of file gaussian.h.
const unsigned pcl::GaussianKernel::MAX_KERNEL_WIDTH = 71 [static] |
Definition at line 63 of file gaussian.h.