Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT > Class Template Reference

IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position and intensity values. The intensity gradient at a given point will be a vector orthogonal to the surface normal and pointing in the direction of the greatest increase in local intensity; the vector's magnitude indicates the rate of intensity change. More...

#include <intensity_gradient.h>

Inheritance diagram for pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Public Member Functions

 IntensityGradientEstimation ()
 Empty constructor.
void setNumberOfThreads (int nr_threads)
 Initialize the scheduler and set the number of threads to use.

Protected Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the intensity gradients for a set of points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().
void computePointIntensityGradient (const pcl::PointCloud< PointInT > &cloud, const std::vector< int > &indices, const Eigen::Vector3f &point, float mean_intensity, const Eigen::Vector3f &normal, Eigen::Vector3f &gradient)
 Estimate the intensity gradient around a given point based on its spatial neighborhood of points.

Protected Attributes

IntensitySelectorT intensity_
 intensity field accessor structure
int threads_
 number of threads to be used, default 1

Private Member Functions

void computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &)
 Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
class pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >

IntensityGradientEstimation estimates the intensity gradient for a point cloud that contains position and intensity values. The intensity gradient at a given point will be a vector orthogonal to the surface normal and pointing in the direction of the greatest increase in local intensity; the vector's magnitude indicates the rate of intensity change.

Author:
Michael Dixon

Definition at line 55 of file intensity_gradient.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::PointCloudOut

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 66 of file intensity_gradient.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::IntensityGradientEstimation ( ) [inline]

Empty constructor.

Definition at line 69 of file intensity_gradient.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT , typename IntensitySelectorT >
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeature ( PointCloudOut output) [protected, virtual]

Estimate the intensity gradients for a set of points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ().

Parameters:
outputthe resultant point cloud that contains the intensity gradient vectors

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 143 of file intensity_gradient.hpp.

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::IntensityGradientEstimation< PointInT, PointNT, Eigen::MatrixXf >.

Definition at line 112 of file intensity_gradient.h.

template<typename PointInT, typename PointNT , typename PointOutT , typename IntensitySelectorT >
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::computePointIntensityGradient ( const pcl::PointCloud< PointInT > &  cloud,
const std::vector< int > &  indices,
const Eigen::Vector3f &  point,
float  mean_intensity,
const Eigen::Vector3f &  normal,
Eigen::Vector3f &  gradient 
) [protected]

Estimate the intensity gradient around a given point based on its spatial neighborhood of points.

Parameters:
clouda point cloud dataset containing XYZI coordinates (Cartesian coordinates + intensity)
indicesthe indices of the neighoring points in the dataset
pointthe 3D Cartesian coordinates of the point at which to estimate the gradient
normalthe 3D surface normal of the given point
gradientthe resultant 3D gradient vector

Definition at line 47 of file intensity_gradient.hpp.

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
void pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::setNumberOfThreads ( int  nr_threads) [inline]

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

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

Definition at line 79 of file intensity_gradient.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
IntensitySelectorT pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::intensity_ [protected]

intensity field accessor structure

Definition at line 116 of file intensity_gradient.h.

template<typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >::threads_ [protected]

number of threads to be used, default 1

Definition at line 118 of file intensity_gradient.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30