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

Surface normal estimation on dense data using a least-squares estimation based on a first-order Taylor approximation. More...

#include <linear_least_squares_normal.h>

Inheritance diagram for pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
LinearLeastSquaresNormalEstimation
< PointInT, PointOutT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< LinearLeastSquaresNormalEstimation
< PointInT, PointOutT > > 
Ptr

Public Member Functions

void computePointNormal (const int pos_x, const int pos_y, PointOutT &normal)
 Computes the normal at the specified position.
 LinearLeastSquaresNormalEstimation ()
 Constructor.
void setDepthDependentSmoothing (bool use_depth_dependent_smoothing)
 Set whether to use depth depending smoothing or not.
virtual void setInputCloud (const typename PointCloudIn::ConstPtr &cloud)
 Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method)
void setMaxDepthChangeFactor (float max_depth_change_factor)
 The depth change threshold for computing object borders.
void setNormalSmoothingSize (float normal_smoothing_size)
 Set the normal smoothing size.
virtual ~LinearLeastSquaresNormalEstimation ()
 Destructor.

Protected Member Functions

void computeFeature (PointCloudOut &output)
 Computes the normal for the complete cloud.

Private Attributes

float max_depth_change_factor_
 Threshold for detecting depth discontinuities.
float normal_smoothing_size_
bool use_depth_dependent_smoothing_
 Smooth data based on depth (true/false).

Detailed Description

template<typename PointInT, typename PointOutT>
class pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >

Surface normal estimation on dense data using a least-squares estimation based on a first-order Taylor approximation.

Author:
Stefan Holzer, Cedric Cagniart

Definition at line 52 of file linear_least_squares_normal.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT>
typedef boost::shared_ptr<const LinearLeastSquaresNormalEstimation<PointInT, PointOutT> > pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::ConstPtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 56 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::PointCloudIn

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 57 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::PointCloudOut

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 58 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
typedef boost::shared_ptr<LinearLeastSquaresNormalEstimation<PointInT, PointOutT> > pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::Ptr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 55 of file linear_least_squares_normal.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT>
pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::LinearLeastSquaresNormalEstimation ( ) [inline]

Constructor.

Definition at line 65 of file linear_least_squares_normal.h.

template<typename PointInT , typename PointOutT >
pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::~LinearLeastSquaresNormalEstimation ( ) [virtual]

Destructor.

Definition at line 47 of file linear_least_squares_normal.hpp.


Member Function Documentation

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

Computes the normal for the complete cloud.

Parameters:
[out]outputthe resultant normals

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 155 of file linear_least_squares_normal.hpp.

template<typename PointInT , typename PointOutT >
void pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::computePointNormal ( const int  pos_x,
const int  pos_y,
PointOutT normal 
)

Computes the normal at the specified position.

Parameters:
[in]pos_xx position (pixel)
[in]pos_yy position (pixel)
[out]normalthe output estimated normal

Definition at line 53 of file linear_least_squares_normal.hpp.

template<typename PointInT, typename PointOutT>
void pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::setDepthDependentSmoothing ( bool  use_depth_dependent_smoothing) [inline]

Set whether to use depth depending smoothing or not.

Parameters:
[in]use_depth_dependent_smoothingdecides whether the smoothing is depth dependent

Definition at line 100 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
virtual void pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::setInputCloud ( const typename PointCloudIn::ConstPtr cloud) [inline, virtual]

Provide a pointer to the input dataset (overwrites the PCLBase::setInputCloud method)

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Definition at line 119 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
void pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::setMaxDepthChangeFactor ( float  max_depth_change_factor) [inline]

The depth change threshold for computing object borders.

Parameters:
[in]max_depth_change_factorthe depth change threshold for computing object borders based on depth changes

Definition at line 110 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
void pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::setNormalSmoothingSize ( float  normal_smoothing_size) [inline]

Set the normal smoothing size.

Parameters:
[in]normal_smoothing_sizefactor which influences the size of the area used to smooth normals (depth dependent if useDepthDependentSmoothing is true)

Definition at line 91 of file linear_least_squares_normal.h.


Member Data Documentation

template<typename PointInT, typename PointOutT>
float pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::max_depth_change_factor_ [private]

Threshold for detecting depth discontinuities.

Definition at line 140 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
float pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::normal_smoothing_size_ [private]

Definition at line 143 of file linear_least_squares_normal.h.

template<typename PointInT, typename PointOutT>
bool pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >::use_depth_dependent_smoothing_ [private]

Smooth data based on depth (true/false).

the threshold used to detect depth discontinuities

Definition at line 137 of file linear_least_squares_normal.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:13