Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT > Class Template Reference

UniqueShapeContext implements the Unique Shape Descriptor described here: More...

#include <usc.h>

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

List of all members.

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.

Detailed Description

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
class pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >

UniqueShapeContext implements the Unique Shape Descriptor described here:

The USC computed feature has the following structure:

Author:
Alessandro Franchi, Federico Tombari, Samuele Salti (original code)
Nizar Sallem (port to PCL)

Definition at line 66 of file usc.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::ConstPtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 84 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::PointCloudIn

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 82 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::PointCloudOut

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 81 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::Ptr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 83 of file usc.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::UniqueShapeContext ( ) [inline]

Constructor.

Definition at line 88 of file usc.h.

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

Definition at line 97 of file usc.h.


Member Function Documentation

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

The actual feature computation.

Parameters:
[out]outputthe resultant features

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 242 of file usc.hpp.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::UniqueShapeContext< PointInT, Eigen::MatrixXf, PointRFT >.

Definition at line 215 of file usc.h.

template<typename PointInT , typename PointOutT , typename PointRFT >
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::computePointDescriptor ( size_t  index,
std::vector< float > &  desc 
) [protected]

Compute 3D shape context feature descriptor

Parameters:
[in]indexpoint index in input_
[out]descdescriptor 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)

Definition at line 143 of file usc.hpp.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getAzimuthBins ( ) const [inline]
Returns:
The number of bins along the azimuth.

Definition at line 107 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getElevationBins ( ) const [inline]
Returns:
The number of bins along the elevation

Definition at line 117 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getLocalRadius ( ) const [inline]
Returns:
The local RF radius.

Definition at line 158 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getMinimalRadius ( ) const [inline]
Returns:
The minimal sphere radius.

Definition at line 137 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getPointDensityRadius ( ) const [inline]
Returns:
The point density search radius.

Definition at line 148 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::getRadiusBins ( ) const [inline]
Returns:
The number of bins along the radii direction.

Definition at line 127 of file usc.h.

template<typename PointInT , typename PointOutT , typename PointRFT >
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 >.

Definition at line 51 of file usc.hpp.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setAzimuthBins ( size_t  bins) [inline]

Set the number of bins along the azimuth.

Parameters:
[in]binsthe number of bins along the azimuth

Definition at line 103 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setElevationBins ( size_t  bins) [inline]

Set the number of bins along the elevation.

Parameters:
[in]binsthe number of bins along the elevation

Definition at line 113 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setLocalRadius ( double  radius) [inline]

Set the local RF radius value

Parameters:
[in]radiusthe desired local RF radius

Definition at line 154 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::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 133 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::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 144 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
void pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::setRadiusBins ( size_t  bins) [inline]

Set the number of bins along the radii.

Parameters:
[in]binsthe number of bins along the radii

Definition at line 123 of file usc.h.


Member Data Documentation

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::azimuth_bins_ [protected]

Bins along the azimuth dimension.

Definition at line 191 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::descriptor_length_ [protected]

Descriptor length.

Definition at line 206 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::elevation_bins_ [protected]

Bins along the elevation dimension.

Definition at line 194 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::local_radius_ [protected]

Radius to compute local RF.

Definition at line 209 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::min_radius_ [protected]

Minimal radius value.

Definition at line 200 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::phi_divisions_ [protected]

Phi divisions interval.

Definition at line 185 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
double pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::point_density_radius_ [protected]

Point density radius.

Definition at line 203 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::radii_interval_ [protected]

values of the radii interval.

Definition at line 179 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
size_t pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::radius_bins_ [protected]

Bins along the radius dimension.

Definition at line 197 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::theta_divisions_ [protected]

Theta divisions interval.

Definition at line 182 of file usc.h.

template<typename PointInT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
std::vector<float> pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::volume_lut_ [protected]

Volumes look up table.

Definition at line 188 of file usc.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:18