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>
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. | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. |
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.
typedef boost::shared_ptr<const RIFTEstimation<PointInT, GradientT, PointOutT> > pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::ConstPtr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef pcl::PointCloud<GradientT> pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::PointCloudGradient |
typedef PointCloudGradient::ConstPtr pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::PointCloudGradientConstPtr |
typedef PointCloudGradient::Ptr pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::PointCloudGradientPtr |
typedef pcl::PointCloud<PointInT> pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::PointCloudIn |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef boost::shared_ptr<RIFTEstimation<PointInT, GradientT, PointOutT> > pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::Ptr |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::RIFTEstimation | ( | ) | [inline] |
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
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 ()
[out] | output | the resultant point cloud model dataset that contains the RIFT feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::RIFTEstimation< PointInT, GradientT, 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::RIFTEstimation< PointInT, GradientT, Eigen::MatrixXf >.
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 | ||
) |
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.
[in] | cloud | the dataset containing the Cartesian coordinates of the points |
[in] | gradient | the dataset containing the intensity gradient at each point in cloud |
[in] | p_idx | the index of the query point in cloud (i.e. the center of the neighborhood) |
[in] | radius | the radius of the RIFT feature |
[in] | indices | the indices of the points that comprise p_idx's neighborhood in cloud |
[in] | squared_distances | the squared distances from the query point to each point in the neighborhood |
[out] | rift_descriptor | the resultant RIFT descriptor |
PointCloudGradientConstPtr pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::getInputGradient | ( | ) | const [inline] |
int pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::getNrDistanceBins | ( | ) | const [inline] |
int pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::getNrGradientBins | ( | ) | const [inline] |
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::setInputGradient | ( | const PointCloudGradientConstPtr & | gradient | ) | [inline] |
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::setNrDistanceBins | ( | int | nr_distance_bins | ) | [inline] |
void pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::setNrGradientBins | ( | int | nr_gradient_bins | ) | [inline] |
PointCloudGradientConstPtr pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::gradient_ [protected] |
int pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::nr_distance_bins_ [protected] |
int pcl::RIFTEstimation< PointInT, GradientT, PointOutT >::nr_gradient_bins_ [protected] |