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>
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. |
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
typedef boost::shared_ptr<const SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::ConstPtr |
Reimplemented from pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >.
Reimplemented in pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::PointCloudIn |
Reimplemented from pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >.
Reimplemented in pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >.
typedef boost::shared_ptr<SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::Ptr |
Reimplemented from pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >.
Reimplemented in pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >.
pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::SHOTColorEstimation | ( | bool | describe_shape = true , |
bool | describe_color = true |
||
) | [inline] |
virtual pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::~SHOTColorEstimation | ( | ) | [inline, virtual] |
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 ()
output | the resultant point cloud model dataset that contains the SHOT feature estimates |
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.
[in] | index | the index of the point in indices_ |
[in] | indices | the k-neighborhood point indices in surface_ |
[in] | sqr_dists | the k-neighborhood point distances in surface_ |
[out] | shot | the resultant SHOT descriptor representing the feature at the query point |
Implements pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, 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.
[in] | indices | the neighborhood point indices |
[in] | sqr_dists | the neighborhood point distances |
[in] | index | the index of the point in indices_ |
[out] | binDistanceShape | the resultant distance shape histogram |
[out] | binDistanceColor | the resultant color shape histogram |
[in] | nr_bins_shape | the number of bins in the shape histogram |
[in] | nr_bins_color | the number of bins in the color histogram |
[out] | shot | the resultant SHOT histogram |
void pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::RGB2CIELAB | ( | unsigned char | R, |
unsigned char | G, | ||
unsigned char | B, | ||
float & | L, | ||
float & | A, | ||
float & | B2 | ||
) | [static] |
bool pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::b_describe_color_ [protected] |
bool pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::b_describe_shape_ [protected] |
int pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::nr_color_bins_ [protected] |
float pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::sRGB_LUT = {- 1} [static] |
float pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >::sXYZ_LUT = {- 1} [static] |