|
using | PointCloudOut = typename Feature< PointInT, PointOutT >::PointCloudOut |
|
using | PointCloudIn = typename Feature< PointInT, PointOutT >::PointCloudIn |
|
using | PointCloudInPtr = typename Feature< PointInT, PointOutT >::PointCloudInPtr |
|
using | PointCloudN = pcl::PointCloud< PointNT > |
|
using | PointCloudNPtr = typename PointCloudN::Ptr |
|
using | PointCloudNConstPtr = typename PointCloudN::ConstPtr |
|
using | Ptr = shared_ptr< FeatureFromNormals< PointInT, PointNT, PointOutT > > |
|
using | ConstPtr = shared_ptr< const FeatureFromNormals< PointInT, PointNT, PointOutT > > |
|
using | BaseClass = PCLBase< PointInT > |
|
using | Ptr = shared_ptr< Feature< PointInT, PointOutT > > |
|
using | ConstPtr = shared_ptr< const Feature< PointInT, PointOutT > > |
|
using | KdTree = pcl::search::Search< PointInT > |
|
using | KdTreePtr = typename KdTree::Ptr |
|
using | PointCloudIn = pcl::PointCloud< PointInT > |
|
using | PointCloudInPtr = typename PointCloudIn::Ptr |
|
using | PointCloudInConstPtr = typename PointCloudIn::ConstPtr |
|
using | PointCloudOut = pcl::PointCloud< PointOutT > |
|
using | SearchMethod = std::function< int(std::size_t, double, pcl::Indices &, std::vector< float > &)> |
|
using | SearchMethodSurface = std::function< int(const PointCloudIn &cloud, std::size_t index, double, pcl::Indices &, std::vector< float > &)> |
|
using | PointCloud = pcl::PointCloud< PointInT > |
|
using | PointCloudPtr = typename PointCloud::Ptr |
|
using | PointCloudConstPtr = typename PointCloud::ConstPtr |
|
using | PointIndicesPtr = PointIndices::Ptr |
|
using | PointIndicesConstPtr = PointIndices::ConstPtr |
|
|
void | computeFeature (PointCloudOut &output) override |
| Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () More...
|
|
virtual bool | initCompute () |
| This method should get called before starting the actual computation. More...
|
|
const std::string & | getClassName () const |
| Get a string representation of the name of this class. More...
|
|
virtual bool | deinitCompute () |
| This method should get called after ending the actual computation. More...
|
|
int | searchForNeighbors (std::size_t index, double parameter, pcl::Indices &indices, std::vector< float > &distances) const |
| Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface. More...
|
|
int | searchForNeighbors (const PointCloudIn &cloud, std::size_t index, double parameter, pcl::Indices &indices, std::vector< float > &distances) const |
| Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface. More...
|
|
bool | initCompute () |
| This method should get called before starting the actual computation. More...
|
|
bool | deinitCompute () |
| This method should get called after finishing the actual computation. More...
|
|
template<typename PointInT, typename PointNT, typename PointOutT>
class pcl::GRSDEstimation< PointInT, PointNT, PointOutT >
GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud dataset containing points and normals.
- Note
- If you use this code in any academic work, please cite (first for the ray-casting and second for the additive version):
-
Z.C. Marton, D. Pangercic, N. Blodow, Michael Beetz. Combined 2D-3D Categorization and Classification for Multimodal Perception Systems. In The International Journal of Robotics Research, Sage Publications pages 1378–1402, Volume 30, Number 11, September 2011.
-
A. Kanezaki, Z.C. Marton, D. Pangercic, T. Harada, Y. Kuniyoshi, M. Beetz. Voxelized Shape and Color Histograms for RGB-D In the Workshop on Active Semantic Perception and Object Search in the Real World, in conjunction with the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) San Francisco, California, September 25-30, 2011.
- Note
- The code is stateful as we do not expect this class to be multicore parallelized. Please look at FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
- Author
- Zoltan Csaba Marton
- Template Parameters
-
Definition at line 72 of file grsd.h.
template<typename PointInT , typename PointNT , typename PointOutT >
Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
- Parameters
-
output | the resultant point cloud that contains the GRSD feature |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 65 of file grsd.hpp.
References pcl::PointCloud< PointT >::clear(), pcl::Feature< PointInT, PointOutT >::compute(), pcl::Filter< PointT >::filter(), pcl::VoxelGrid< PointT >::getNeighborCentroidIndices(), pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::points, pcl::PointCloud< PointT >::resize(), pcl::PCLBase< PointT >::setInputCloud(), pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::setInputNormals(), pcl::VoxelGrid< PointT >::setLeafSize(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setNrSubdivisions(), pcl::RSDEstimation< PointInT, PointNT, PointOutT >::setPlaneRadius(), pcl::Feature< PointInT, PointOutT >::setRadiusSearch(), pcl::VoxelGrid< PointT >::setSaveLeafLayout(), pcl::Feature< PointInT, PointOutT >::setSearchSurface(), pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.
template<typename PointInT , typename PointNT , typename PointOutT >
Set the number of subdivisions for the considered distance interval.
This function configures the underlying RSDEstimation. For more info, see there. If this function is not called, the default from RSDEstimation is used.
- Parameters
-
[in] | nr_subdiv | the number of subdivisions |
Definition at line 115 of file grsd.h.
template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::setPlaneRadius |
( |
double |
plane_radius | ) |
|
|
inline |
Set the maximum radius, above which everything can be considered planar.
This function configures the underlying RSDEstimation. For more info, see there. If this function is not called, the default from RSDEstimation is used.
- Parameters
-
[in] | plane_radius | the new plane radius |
Definition at line 123 of file grsd.h.
template<typename PointInT , typename PointNT , typename PointOutT >
Set the sphere radius that is to be used for determining the nearest neighbors used for the feature estimation.
Same value will be used for the internal voxel grid leaf size.
- Parameters
-
[in] | radius | the sphere radius used as the maximum distance to consider a point a neighbor |
Definition at line 101 of file grsd.h.
References pcl::Feature< PointInT, PointOutT >::search_radius_.