Public Types |
typedef boost::shared_ptr
< const RIFTEstimation
< PointInT, GradientT,
PointOutT > > | ConstPtr |
typedef pcl::PointCloud
< GradientT > | PointCloudGradient |
typedef
PointCloudGradient::ConstPtr | PointCloudGradientConstPtr |
| typedef PointCloudGradient::Ptr | PointCloudGradientPtr |
| typedef pcl::PointCloud< PointInT > | PointCloudIn |
typedef Feature< PointInT,
PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr
< RIFTEstimation< PointInT,
GradientT, PointOutT > > | Ptr |
Public Member Functions |
| void | computeRIFT (const PointCloudIn &cloud, const PointCloudGradient &gradient, int p_idx, float radius, const std::vector< int > &indices, const std::vector< float > &squared_distances, Eigen::MatrixXf &rift_descriptor) |
| | Estimate the Rotation Invariant Feature Transform (RIFT) descriptor for a given point based on its spatial neighborhood of 3D points and the corresponding intensity gradient vector field.
|
| PointCloudGradientConstPtr | getInputGradient () const |
| | Returns a shared pointer to the input gradient data.
|
| int | getNrDistanceBins () const |
| | Returns the number of bins in the distance dimension of the RIFT descriptor.
|
| int | getNrGradientBins () const |
| | Returns the number of bins in the gradient orientation dimension of the RIFT descriptor.
|
| | RIFTEstimation () |
| | Empty constructor.
|
| void | setInputGradient (const PointCloudGradientConstPtr &gradient) |
| | Provide a pointer to the input gradient data.
|
| void | setNrDistanceBins (int nr_distance_bins) |
| | Set the number of bins to use in the distance dimension of the RIFT descriptor.
|
| void | setNrGradientBins (int nr_gradient_bins) |
| | Set the number of bins to use in the gradient orientation dimension of the RIFT descriptor.
|
Protected Member Functions |
| void | computeFeature (PointCloudOut &output) |
| | Estimate the Rotation Invariant Feature Transform (RIFT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface (), the gradient in setInputGradient (), and the spatial locator in setSearchMethod ()
|
Protected Attributes |
| PointCloudGradientConstPtr | gradient_ |
| | The intensity gradient of the input point cloud data.
|
| int | nr_distance_bins_ |
| | The number of distance bins in the descriptor.
|
| int | nr_gradient_bins_ |
| | The number of gradient orientation bins in the descriptor.
|
template<typename PointInT, typename GradientT, typename PointOutT>
class pcl::RIFTEstimation< PointInT, GradientT, PointOutT >
RIFTEstimation estimates the Rotation Invariant Feature Transform descriptors for a given point cloud dataset containing points and intensity. For more information about the RIFT descriptor, see:
Svetlana Lazebnik, Cordelia Schmid, and Jean Ponce. A sparse texture representation using local affine regions. In IEEE Transactions on Pattern Analysis and Machine Intelligence, volume 27, pages 1265-1278, August 2005.
- Author:
- Michael Dixon
Definition at line 60 of file rift.h.
template<typename PointInT , typename GradientT , typename PointOutT >
Estimate the Rotation Invariant Feature Transform (RIFT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface (), the gradient in setInputGradient (), and the spatial locator in setSearchMethod ()
- Parameters:
-
| [out] | output | the resultant point cloud model dataset that contains the RIFT feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 113 of file rift.hpp.