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

SHOTColorEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors. More...

#include <shot.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const SHOTColorEstimation
< PointInT, PointNT, PointOutT,
PointRFT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef boost::shared_ptr
< SHOTColorEstimation
< PointInT, PointNT, PointOutT,
PointRFT > > 
Ptr

Public Member Functions

virtual void computePointSHOT (const int index, const std::vector< int > &indices, const std::vector< float > &sqr_dists, Eigen::VectorXf &shot)
 Estimate the SHOT descriptor for a given point based on its spatial neighborhood of 3D points with normals.
 SHOTColorEstimation (bool describe_shape=true, bool describe_color=true)
 Empty constructor.
virtual ~SHOTColorEstimation ()
 Empty destructor.

Static Public Member Functions

static void RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2)
 Converts RGB triplets to CIELab space.

Static Public Attributes

static float sRGB_LUT [256] = {- 1}
static float sXYZ_LUT [4000] = {- 1}

Protected Member Functions

void computeFeature (pcl::PointCloud< PointOutT > &output)
 Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
void interpolateDoubleChannel (const std::vector< int > &indices, const std::vector< float > &sqr_dists, const int index, std::vector< double > &binDistanceShape, std::vector< double > &binDistanceColor, const int nr_bins_shape, const int nr_bins_color, Eigen::VectorXf &shot)
 Quadrilinear interpolation; used when color and shape descriptions are both activated.

Protected Attributes

bool b_describe_color_
 Compute color descriptor.
bool b_describe_shape_
 Compute shape descriptor.
int nr_color_bins_
 The number of bins in each color histogram.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
class pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >

SHOTColorEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors.

The suggested PointOutT is pcl::SHOT1344

Note:
If you use this code in any academic work, please cite:
Author:
Samuele Salti, Federico Tombari

Definition at line 299 of file shot.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<const SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::ConstPtr
template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::PointCloudIn
template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::Ptr

Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::SHOTColorEstimation ( bool  describe_shape = true,
bool  describe_color = true 
) [inline]

Empty constructor.

Parameters:
[in]describe_shape
[in]describe_color

Definition at line 331 of file shot.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
virtual pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::~SHOTColorEstimation ( ) [inline, virtual]

Empty destructor.

Definition at line 342 of file shot.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
void pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computeFeature ( pcl::PointCloud< PointOutT > &  output) [protected]

Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Parameters:
outputthe resultant point cloud model dataset that contains the SHOT feature estimates

Definition at line 830 of file shot.hpp.

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
void pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::computePointSHOT ( const int  index,
const std::vector< int > &  indices,
const std::vector< float > &  sqr_dists,
Eigen::VectorXf &  shot 
) [virtual]

Estimate the SHOT descriptor for a given point based on its spatial neighborhood of 3D points with normals.

Parameters:
[in]indexthe index of the point in indices_
[in]indicesthe k-neighborhood point indices in surface_
[in]sqr_diststhe k-neighborhood point distances in surface_
[out]shotthe resultant SHOT descriptor representing the feature at the query point

Implements pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >.

Definition at line 646 of file shot.hpp.

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
void pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::interpolateDoubleChannel ( const std::vector< int > &  indices,
const std::vector< float > &  sqr_dists,
const int  index,
std::vector< double > &  binDistanceShape,
std::vector< double > &  binDistanceColor,
const int  nr_bins_shape,
const int  nr_bins_color,
Eigen::VectorXf &  shot 
) [protected]

Quadrilinear interpolation; used when color and shape descriptions are both activated.

Parameters:
[in]indicesthe neighborhood point indices
[in]sqr_diststhe neighborhood point distances
[in]indexthe index of the point in indices_
[out]binDistanceShapethe resultant distance shape histogram
[out]binDistanceColorthe resultant color shape histogram
[in]nr_bins_shapethe number of bins in the shape histogram
[in]nr_bins_colorthe number of bins in the color histogram
[out]shotthe resultant SHOT histogram

Definition at line 430 of file shot.hpp.

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
void pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::RGB2CIELAB ( unsigned char  R,
unsigned char  G,
unsigned char  B,
float &  L,
float &  A,
float &  B2 
) [static]

Converts RGB triplets to CIELab space.

Parameters:
[in]Rthe red channel
[in]Gthe green channel
[in]Bthe blue channel
[out]Lthe lightness
[out]Athe first color-opponent dimension
[out]B2the second color-opponent dimension

Definition at line 97 of file shot.hpp.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
bool pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::b_describe_color_ [protected]

Compute color descriptor.

Definition at line 388 of file shot.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
bool pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::b_describe_shape_ [protected]

Compute shape descriptor.

Definition at line 385 of file shot.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
int pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::nr_color_bins_ [protected]

The number of bins in each color histogram.

Definition at line 391 of file shot.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
float pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::sRGB_LUT = {- 1} [static]

Definition at line 405 of file shot.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
float pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::sXYZ_LUT = {- 1} [static]

Definition at line 406 of file shot.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