UniqueShapeContext implements the Unique Shape Descriptor described here: More...
#include <usc.h>
Public Types | |
typedef boost::shared_ptr < const UniqueShapeContext < PointInT, PointOutT, PointRFT > > | ConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudIn | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < UniqueShapeContext< PointInT, PointOutT, PointRFT > > | Ptr |
Public Member Functions | |
size_t | getAzimuthBins () const |
size_t | getElevationBins () const |
double | getLocalRadius () const |
double | getMinimalRadius () const |
double | getPointDensityRadius () const |
size_t | getRadiusBins () const |
void | setAzimuthBins (size_t bins) |
Set the number of bins along the azimuth. | |
void | setElevationBins (size_t bins) |
Set the number of bins along the elevation. | |
void | setLocalRadius (double radius) |
void | setMinimalRadius (double radius) |
void | setPointDensityRadius (double radius) |
void | setRadiusBins (size_t bins) |
Set the number of bins along the radii. | |
UniqueShapeContext () | |
Constructor. | |
virtual | ~UniqueShapeContext () |
Protected Member Functions | |
virtual void | computeFeature (PointCloudOut &output) |
The actual feature computation. | |
void | computePointDescriptor (size_t index, std::vector< float > &desc) |
virtual bool | initCompute () |
Initialize computation by allocating all the intervals and the volume lookup table. | |
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 | local_radius_ |
Radius to compute local RF. | |
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. | |
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. |
UniqueShapeContext implements the Unique Shape Descriptor described here:
The USC computed feature has the following structure:
typedef boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::ConstPtr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::PointCloudIn |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::Ptr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::UniqueShapeContext | ( | ) | [inline] |
virtual pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::~UniqueShapeContext | ( | ) | [inline, virtual] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
The actual feature computation.
[out] | output | the resultant features |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::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::UniqueShapeContext< PointInT, Eigen::MatrixXf, PointRFT >.
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computePointDescriptor | ( | size_t | index, |
std::vector< float > & | desc | ||
) | [protected] |
Compute 3D shape context feature descriptor
[in] | index | point index in input_ |
[out] | desc | descriptor to compute |
Compute the angle between the neighbour and the z axis (normal) in the interval [0, 180]
Bin (j, k, l)
Compute the Bin(j, k, l) coordinates of current neighbour
Local point density = number of points in a sphere of radius "point_density_radius_" around the current neighbour
point_density is always bigger than 0 because FindPointsWithinRadius returns at least the point itself
Accumulate w into correspondant Bin(j,k,l)
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getAzimuthBins | ( | ) | const [inline] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getElevationBins | ( | ) | const [inline] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getLocalRadius | ( | ) | const [inline] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getMinimalRadius | ( | ) | const [inline] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getPointDensityRadius | ( | ) | const [inline] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getRadiusBins | ( | ) | const [inline] |
bool pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::initCompute | ( | ) | [protected, virtual] |
Initialize computation by allocating all the intervals and the volume lookup table.
Reimplemented from pcl::Feature< PointInT, PointOutT >.
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setAzimuthBins | ( | size_t | bins | ) | [inline] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setElevationBins | ( | size_t | bins | ) | [inline] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setLocalRadius | ( | double | radius | ) | [inline] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setMinimalRadius | ( | double | radius | ) | [inline] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setPointDensityRadius | ( | double | radius | ) | [inline] |
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setRadiusBins | ( | size_t | bins | ) | [inline] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::azimuth_bins_ [protected] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::descriptor_length_ [protected] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::elevation_bins_ [protected] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::local_radius_ [protected] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::min_radius_ [protected] |
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::phi_divisions_ [protected] |
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::point_density_radius_ [protected] |
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::radii_interval_ [protected] |
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::radius_bins_ [protected] |
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::theta_divisions_ [protected] |
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::volume_lut_ [protected] |