pcl::RIFTEstimation< PointInT, GradientT, PointOutT > Class Template Reference
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:
More...
#include <rift.h>
List of all members.
Public Types |
typedef pcl::PointCloud
< GradientT > | PointCloudGradient |
typedef
PointCloudGradient::ConstPtr | PointCloudGradientConstPtr |
typedef PointCloudGradient::Ptr | PointCloudGradientPtr |
typedef pcl::PointCloud< PointInT > | PointCloudIn |
typedef Feature< PointInT,
PointOutT >::PointCloudOut | PointCloudOut |
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 () |
| Returns a shared pointer to the input gradient data.
|
int | getNrDistanceBins () |
| Returns the number of bins in the distance dimension of the RIFT descriptor.
|
int | getNrGradientBins () |
| 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 (size_t nr_distance_bins) |
| Set the number of bins to use in the distance dimension of the RIFT descriptor.
|
void | setNrGradientBins (size_t 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 ().
|
Private 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.
|
Detailed Description
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 56 of file rift.h.
Member Typedef Documentation
template<typename PointInT, typename GradientT, typename PointOutT>
template<typename PointInT, typename GradientT, typename PointOutT>
template<typename PointInT, typename GradientT, typename PointOutT>
template<typename PointInT, typename GradientT, typename PointOutT>
template<typename PointInT, typename GradientT, typename PointOutT>
Constructor & Destructor Documentation
template<typename PointInT, typename GradientT, typename PointOutT>
Empty constructor.
Definition at line 76 of file rift.h.
Member Function Documentation
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:
-
| 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.
template<typename PointInT , typename GradientT , typename PointOutT >
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::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 | |
|
) |
| | [inline] |
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.
- Parameters:
-
| cloud | the dataset containing the Cartesian coordinates of the points |
| gradient | the dataset containing the intensity gradient at each point in cloud |
| p_idx | the index of the query point in cloud (i.e. the center of the neighborhood) |
| radius | the radius of the RIFT feature |
| indices | the indices of the points that comprise p_idx's neighborhood in cloud |
| squared_distances | the squared distances from the query point to each point in the neighborhood |
| rift_descriptor | the resultant RIFT descriptor |
Eigen::Map<Eigen::Vector3f> point (& (cloud.points[indices[idx]].x));
Definition at line 45 of file rift.hpp.
template<typename PointInT, typename GradientT, typename PointOutT>
Returns a shared pointer to the input gradient data.
Definition at line 87 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
Returns the number of bins in the distance dimension of the RIFT descriptor.
Definition at line 96 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
Returns the number of bins in the gradient orientation dimension of the RIFT descriptor.
Definition at line 105 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
Provide a pointer to the input gradient data.
- Parameters:
-
| gradient | a pointer to the input gradient data |
Definition at line 84 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::setNrDistanceBins |
( |
size_t |
nr_distance_bins |
) |
[inline] |
Set the number of bins to use in the distance dimension of the RIFT descriptor.
- Parameters:
-
| nr_distance_bins | the number of bins to use in the distance dimension of the RIFT descriptor |
Definition at line 93 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::setNrGradientBins |
( |
size_t |
nr_gradient_bins |
) |
[inline] |
Set the number of bins to use in the gradient orientation dimension of the RIFT descriptor.
- Parameters:
-
| nr_gradient_bins | the number of bins to use in the gradient orientation dimension of the RIFT descriptor |
Definition at line 102 of file rift.h.
Member Data Documentation
template<typename PointInT, typename GradientT, typename PointOutT>
The intensity gradient of the input point cloud data.
Definition at line 133 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
The number of distance bins in the descriptor.
Definition at line 136 of file rift.h.
template<typename PointInT, typename GradientT, typename PointOutT>
The number of gradient orientation bins in the descriptor.
Definition at line 139 of file rift.h.
The documentation for this class was generated from the following files: