ShapeContext3DEstimation implements the 3D shape context descriptor as described in: More...
#include <3dsc.h>
Public Types | |
typedef Feature< PointInT, PointOutT >::PointCloudIn | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
size_t | getAzimuthBins () |
size_t | getElevationBins () |
double | getMinimalRadius () |
double | getPointDensityRadius () |
size_t | getRadiusBins () |
void | setAzimuthBins (size_t bins) |
Set the number of bins along the azimuth to bins. | |
void | setElevationBins (size_t bins) |
Set the number of bins along the elevation to bins. | |
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. | |
void | setRadiusBins (size_t bins) |
Set the number of bins along the radii to bins. | |
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 () |
Boost-based random number generator. | |
void | shiftAlongAzimuth (size_t block_size, std::vector< float > &desc) |
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. | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. |
ShapeContext3DEstimation implements the 3D shape context descriptor as described in:
The 3DSC computed feature has the following structure
The pcl::ShapeContext descriptor is the default PointOutT.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::PointCloudIn |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::ShapeContext3DEstimation | ( | bool | random = false | ) | [inline] |
virtual pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::~ShapeContext3DEstimation | ( | ) | [inline, virtual] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Estimate the actual feature.
[out] | output | the resultant feature |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen | ( | pcl::PointCloud< Eigen::MatrixXf > & | ) | [inline, private, virtual] |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
[out] | output | the output point cloud |
Implements pcl::Feature< PointInT, PointOutT >.
Reimplemented in pcl::ShapeContext3DEstimation< PointInT, PointNT, Eigen::MatrixXf >.
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.
[in] | index | the index of the point to estimate a descriptor for |
[in] | normals | a pointer to the set of normals |
[in] | rf | the reference frame |
[out] | desc | the resultant estimated descriptor |
----- 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)
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getAzimuthBins | ( | ) | [inline] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getElevationBins | ( | ) | [inline] |
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getMinimalRadius | ( | ) | [inline] |
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getPointDensityRadius | ( | ) | [inline] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::getRadiusBins | ( | ) | [inline] |
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 >.
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rnd | ( | ) | [inline, protected] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setAzimuthBins | ( | size_t | bins | ) | [inline] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setElevationBins | ( | size_t | bins | ) | [inline] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setMinimalRadius | ( | double | radius | ) | [inline] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setPointDensityRadius | ( | double | radius | ) | [inline] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::setRadiusBins | ( | size_t | bins | ) | [inline] |
void pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::shiftAlongAzimuth | ( | size_t | block_size, |
std::vector< float > & | desc | ||
) | [protected] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::azimuth_bins_ [protected] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::descriptor_length_ [protected] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::elevation_bins_ [protected] |
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::min_radius_ [protected] |
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::phi_divisions_ [protected] |
double pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::point_density_radius_ [protected] |
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::radii_interval_ [protected] |
size_t pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::radius_bins_ [protected] |
boost::shared_ptr<boost::uniform_01<boost::mt19937> > pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rng_ [protected] |
boost::mt19937 pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::rng_alg_ [protected] |
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::theta_divisions_ [protected] |
std::vector<float> pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >::volume_lut_ [protected] |