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

ShapeContext3DEstimation implements the 3D shape context descriptor as described in: More...

#include <3dsc.h>

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

List of all members.

Public Types

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

Public Member Functions

size_t getAzimuthBins ()
size_t getElevationBins ()
double getMinimalRadius ()
double getPointDensityRadius ()
size_t getRadiusBins ()
void setMinimalRadius (double radius)
 The minimal radius value for the search sphere (rmin) in the original paper.
void setPointDensityRadius (double radius)
 This radius is used to compute local point density density = number of points within this radius.
 ShapeContext3DEstimation (bool random=false)
 Constructor.
virtual ~ShapeContext3DEstimation ()

Protected Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the actual feature.
bool computePoint (size_t index, const pcl::PointCloud< PointNT > &normals, float rf[9], std::vector< float > &desc)
 Estimate a descriptor for a given point.
bool initCompute ()
 Initialize computation by allocating all the intervals and the volume lookup table.
double rnd ()
 Shift computed descriptor "L" times along the azimuthal direction.

Protected Attributes

size_t azimuth_bins_
 Bins along the azimuth dimension.
size_t descriptor_length_
 Descriptor length.
size_t elevation_bins_
 Bins along the elevation dimension.
double min_radius_
 Minimal radius value.
std::vector< float > phi_divisions_
 Phi divisions interval.
double point_density_radius_
 Point density radius.
std::vector< float > radii_interval_
 Values of the radii interval.
size_t radius_bins_
 Bins along the radius dimension.
boost::shared_ptr
< boost::uniform_01
< boost::mt19937 > > 
rng_
 Boost-based random number generator distribution.
boost::mt19937 rng_alg_
 Boost-based random number generator algorithm.
std::vector< float > theta_divisions_
 Theta divisions interval.
std::vector< float > volume_lut_
 Volumes look up table.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
class pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >

ShapeContext3DEstimation implements the 3D shape context descriptor as described in:

The suggested PointOutT is pcl::ShapeContext1980

Attention:
The convention for a 3D shape context descriptor is:
  • if a query point's nearest neighbors cannot be estimated, the feature descriptor will be set to NaN (not a number), and the RF to 0
  • it is impossible to estimate a 3D shape context descriptor for a point that doesn't have finite 3D coordinates. Therefore, any point that contains NaN data on x, y, or z, will have its boundary feature property set to NaN.
Author:
Alessandro Franchi, Samuele Salti, Federico Tombari (original code)
Nizar Sallem (port to PCL)

Definition at line 72 of file 3dsc.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
typedef boost::shared_ptr<const ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::ConstPtr

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

Definition at line 76 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::PointCloudIn

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

Definition at line 89 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

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

Definition at line 88 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
typedef boost::shared_ptr<ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::Ptr

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

Definition at line 75 of file 3dsc.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::ShapeContext3DEstimation ( bool  random = false) [inline]

Constructor.

Parameters:
[in]randomIf true the random seed is set to current time, else it is set to 12345 prior to computing the descriptor (used to select X axis)

Definition at line 95 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
virtual pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::~ShapeContext3DEstimation ( ) [inline, virtual]

Definition at line 119 of file 3dsc.h.


Member Function Documentation

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

Estimate the actual feature.

Parameters:
[out]outputthe resultant feature

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 279 of file 3dsc.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computePoint ( size_t  index,
const pcl::PointCloud< PointNT > &  normals,
float  rf[9],
std::vector< float > &  desc 
) [protected]

Estimate a descriptor for a given point.

Parameters:
[in]indexthe index of the point to estimate a descriptor for
[in]normalsa pointer to the set of normals
[in]rfthe reference frame
[out]descthe resultant estimated descriptor
Returns:
true if the descriptor was computed successfully, false if there was an error (e.g. the nearest neighbor didn't return any neighbors)

----- Compute current neighbour polar coordinates ----- Get distance between the neighbour and the origin

Project point into the tangent plane

Normalize to compute the dot product

Compute the angle between the projection and the x axis in the interval [0,360]

Compute the angle between the neighbour and the z axis (normal) in the interval [0, 180]

Accumulate w into correspondant Bin(j,k,l)

Definition at line 130 of file 3dsc.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getAzimuthBins ( ) [inline]
Returns:
the number of bins along the azimuth

Definition at line 126 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getElevationBins ( ) [inline]
Returns:
The number of bins along the elevation

Definition at line 133 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getMinimalRadius ( ) [inline]
Returns:
The minimal sphere radius

Definition at line 150 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getPointDensityRadius ( ) [inline]
Returns:
The point density search radius

Definition at line 161 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getRadiusBins ( ) [inline]
Returns:
The number of bins along the radii direction

Definition at line 140 of file 3dsc.h.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::initCompute ( ) [protected, virtual]

Initialize computation by allocating all the intervals and the volume lookup table.

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

Definition at line 50 of file 3dsc.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rnd ( ) [inline, protected]

Shift computed descriptor "L" times along the azimuthal direction.

Parameters:
[in]block_sizethe size of each azimuthal block
[in]descat input desc == original descriptor and on output it contains shifted descriptor resized descriptor_length_ * azimuth_bins_Boost-based random number generator.

Definition at line 231 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setMinimalRadius ( double  radius) [inline]

The minimal radius value for the search sphere (rmin) in the original paper.

Parameters:
[in]radiusthe desired minimal radius

Definition at line 146 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setPointDensityRadius ( double  radius) [inline]

This radius is used to compute local point density density = number of points within this radius.

Parameters:
[in]radiusvalue of the point density search radius

Definition at line 157 of file 3dsc.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::azimuth_bins_ [protected]

Bins along the azimuth dimension.

Definition at line 198 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::descriptor_length_ [protected]

Descriptor length.

Definition at line 213 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::elevation_bins_ [protected]

Bins along the elevation dimension.

Definition at line 201 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::min_radius_ [protected]

Minimal radius value.

Definition at line 207 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::phi_divisions_ [protected]

Phi divisions interval.

Definition at line 192 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::point_density_radius_ [protected]

Point density radius.

Definition at line 210 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::radii_interval_ [protected]

Values of the radii interval.

Definition at line 186 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::radius_bins_ [protected]

Bins along the radius dimension.

Definition at line 204 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
boost::shared_ptr<boost::uniform_01<boost::mt19937> > pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rng_ [protected]

Boost-based random number generator distribution.

Definition at line 219 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
boost::mt19937 pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rng_alg_ [protected]

Boost-based random number generator algorithm.

Definition at line 216 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::theta_divisions_ [protected]

Theta divisions interval.

Definition at line 189 of file 3dsc.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::volume_lut_ [protected]

Volumes look up table.

Definition at line 195 of file 3dsc.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:35