RSDEstimation estimates the Radius-based Surface Descriptor (minimal and maximal radius of the local surface's curves) for a given point cloud dataset containing points and normals. More...
#include <rsd.h>
Public Types | |
typedef boost::shared_ptr < const RSDEstimation < PointInT, PointNT, PointOutT > > | ConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudIn | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < RSDEstimation< PointInT, PointNT, PointOutT > > | Ptr |
Public Member Functions | |
boost::shared_ptr< std::vector < Eigen::MatrixXf, Eigen::aligned_allocator < Eigen::MatrixXf > > > | getHistograms () const |
Returns a pointer to the list of full distance-angle histograms for all points. | |
int | getNrSubdivisions () const |
Get the number of subdivisions for the considered distance interval. | |
double | getPlaneRadius () const |
Get the maximum radius, above which everything can be considered planar. | |
bool | getSaveHistograms () const |
Returns whether the full distance-angle histograms are being saved. | |
RSDEstimation () | |
Empty constructor. | |
void | setKSearch (int) |
Disables the setting of the number of k nearest neighbors to use for the feature estimation. | |
void | setNrSubdivisions (int nr_subdiv) |
Set the number of subdivisions for the considered distance interval. | |
void | setPlaneRadius (double plane_radius) |
Set the maximum radius, above which everything can be considered planar. | |
void | setSaveHistograms (bool save) |
Set whether the full distance-angle histograms should be saved. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the estimates the Radius-based Surface Descriptor (RSD) at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () | |
Protected Attributes | |
boost::shared_ptr< std::vector < Eigen::MatrixXf, Eigen::aligned_allocator < Eigen::MatrixXf > > > | histograms_ |
The list of full distance-angle histograms for all points. | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &output) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. | |
Private Attributes | |
int | nr_subdiv_ |
The number of subdivisions for the considered distance interval. | |
double | plane_radius_ |
The maximum radius, above which everything can be considered planar. | |
bool | save_histograms_ |
Signals whether the full distance-angle histograms are being saved. |
RSDEstimation estimates the Radius-based Surface Descriptor (minimal and maximal radius of the local surface's curves) for a given point cloud dataset containing points and normals.
typedef boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > pcl::RSDEstimation< PointInT, PointNT, PointOutT >::ConstPtr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::RSDEstimation< PointInT, PointNT, PointOutT >::PointCloudIn |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::RSDEstimation< PointInT, PointNT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
typedef boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > pcl::RSDEstimation< PointInT, PointNT, PointOutT >::Ptr |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
pcl::RSDEstimation< PointInT, PointNT, PointOutT >::RSDEstimation | ( | ) | [inline] |
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Estimate the estimates the Radius-based Surface Descriptor (RSD) at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
output | the resultant point cloud model dataset that contains the RSD feature estimates (r_min and r_max values) |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen | ( | pcl::PointCloud< Eigen::MatrixXf > & | output | ) | [inline, private, virtual] |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
[out] | output | the output point cloud |
Implements pcl::Feature< PointInT, PointOutT >.
boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > > pcl::RSDEstimation< PointInT, PointNT, PointOutT >::getHistograms | ( | ) | const [inline] |
int pcl::RSDEstimation< PointInT, PointNT, PointOutT >::getNrSubdivisions | ( | ) | const [inline] |
double pcl::RSDEstimation< PointInT, PointNT, PointOutT >::getPlaneRadius | ( | ) | const [inline] |
bool pcl::RSDEstimation< PointInT, PointNT, PointOutT >::getSaveHistograms | ( | ) | const [inline] |
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setKSearch | ( | int | ) | [inline] |
Disables the setting of the number of k nearest neighbors to use for the feature estimation.
Reimplemented from pcl::Feature< PointInT, PointOutT >.
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setNrSubdivisions | ( | int | nr_subdiv | ) | [inline] |
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setPlaneRadius | ( | double | plane_radius | ) | [inline] |
Set the maximum radius, above which everything can be considered planar.
[in] | plane_radius | the new plane radius |
void pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setSaveHistograms | ( | bool | save | ) | [inline] |
boost::shared_ptr<std::vector<Eigen::MatrixXf, Eigen::aligned_allocator<Eigen::MatrixXf> > > pcl::RSDEstimation< PointInT, PointNT, PointOutT >::histograms_ [protected] |
int pcl::RSDEstimation< PointInT, PointNT, PointOutT >::nr_subdiv_ [private] |
double pcl::RSDEstimation< PointInT, PointNT, PointOutT >::plane_radius_ [private] |
bool pcl::RSDEstimation< PointInT, PointNT, PointOutT >::save_histograms_ [private] |