CRHEstimation estimates the Camera Roll Histogram (CRH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in: More...
#include <crh.h>
Public Types | |
typedef boost::shared_ptr < const CRHEstimation < PointInT, PointNT, PointOutT > > | ConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < CRHEstimation< PointInT, PointNT, PointOutT > > | Ptr |
Public Member Functions | |
CRHEstimation () | |
Constructor. | |
void | getViewPoint (float &vpx, float &vpy, float &vpz) |
Get the viewpoint. | |
void | setCentroid (Eigen::Vector4f ¢roid) |
void | setViewPoint (float vpx, float vpy, float vpz) |
Set the viewpoint. | |
Private Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the CRH histogram at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () | |
Private Attributes | |
Eigen::Vector4f | centroid_ |
Centroid to be used. | |
int | nbins_ |
Number of bins, this should match the Output type. | |
float | vpx_ |
Values describing the viewpoint ("pinhole" camera model assumed). By default, the viewpoint is set to 0,0,0. | |
float | vpy_ |
float | vpz_ |
CRHEstimation estimates the Camera Roll Histogram (CRH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in:
The suggested PointOutT is pcl::Histogram<90>. //dc (real) + 44 complex numbers (real, imaginary) + nyquist (real)
typedef boost::shared_ptr<const CRHEstimation<PointInT, PointNT, PointOutT> > pcl::CRHEstimation< PointInT, PointNT, PointOutT >::ConstPtr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::CRHEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef boost::shared_ptr<CRHEstimation<PointInT, PointNT, PointOutT> > pcl::CRHEstimation< PointInT, PointNT, PointOutT >::Ptr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
pcl::CRHEstimation< PointInT, PointNT, PointOutT >::CRHEstimation | ( | ) | [inline] |
void pcl::CRHEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [private, virtual] |
Estimate the CRH histogram at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface ()
[out] | output | the resultant point cloud with a CRH histogram |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::CRHEstimation< PointInT, PointNT, PointOutT >::getViewPoint | ( | float & | vpx, |
float & | vpy, | ||
float & | vpz | ||
) | [inline] |
void pcl::CRHEstimation< PointInT, PointNT, PointOutT >::setCentroid | ( | Eigen::Vector4f & | centroid | ) | [inline] |
void pcl::CRHEstimation< PointInT, PointNT, PointOutT >::setViewPoint | ( | float | vpx, |
float | vpy, | ||
float | vpz | ||
) | [inline] |
Eigen::Vector4f pcl::CRHEstimation< PointInT, PointNT, PointOutT >::centroid_ [private] |
int pcl::CRHEstimation< PointInT, PointNT, PointOutT >::nbins_ [private] |
float pcl::CRHEstimation< PointInT, PointNT, PointOutT >::vpx_ [private] |
float pcl::CRHEstimation< PointInT, PointNT, PointOutT >::vpy_ [private] |
float pcl::CRHEstimation< PointInT, PointNT, PointOutT >::vpz_ [private] |