Point Cloud Library (PCL)  1.14.1-dev
grsd.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2009-2014, Willow Garage, Inc.
6  * Copyright (c) 2014-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  */
38 
39 #pragma once
40 
41 #include <pcl/features/feature.h>
42 #include <pcl/filters/voxel_grid.h>
43 
44 namespace pcl
45 {
46  /** \brief @b GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud dataset
47  * containing points and normals.
48  *
49  * @note If you use this code in any academic work, please cite (first for the ray-casting and second for the additive version):
50  *
51  * <ul>
52  * <li> Z.C. Marton, D. Pangercic, N. Blodow, Michael Beetz.
53  * Combined 2D-3D Categorization and Classification for Multimodal Perception Systems.
54  * In The International Journal of Robotics Research, Sage Publications
55  * pages 1378--1402, Volume 30, Number 11, September 2011.
56  * </li>
57  * <li> A. Kanezaki, Z.C. Marton, D. Pangercic, T. Harada, Y. Kuniyoshi, M. Beetz.
58  * Voxelized Shape and Color Histograms for RGB-D
59  * 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)
60  * San Francisco, California, September 25-30, 2011.
61  * </li>
62  * </ul>
63  *
64  * @note The code is stateful as we do not expect this class to be multicore parallelized. Please look at
65  * \ref FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
66  * \author Zoltan Csaba Marton
67  * \ingroup features
68  * \tparam PointOutT Suggested type is `pcl::GRSDSignature21`
69  */
70 
71  template <typename PointInT, typename PointNT, typename PointOutT>
72  class GRSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
73  {
74  public:
83  //using Feature<PointInT, PointOutT>::computeFeature;
84 
88 
89  /** \brief Constructor. */
91  : relative_coordinates_all_(getAllNeighborCellIndices())
92  {
93  feature_name_ = "GRSDEstimation";
94  };
95 
96  /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature
97  * estimation. Same value will be used for the internal voxel grid leaf size.
98  * \param[in] radius the sphere radius used as the maximum distance to consider a point a neighbor
99  */
100  inline void
101  setRadiusSearch (double radius) { width_ = search_radius_ = radius; }
102 
103  /** \brief Get the sphere radius used for determining the neighbors.
104  * \return the sphere radius used as the maximum distance to consider a point a neighbor
105  */
106  inline double
107  getRadiusSearch () const { return (search_radius_); }
108 
109  /** \brief Set the number of subdivisions for the considered distance interval.
110  * This function configures the underlying RSDEstimation. For more info, see
111  * there. If this function is not called, the default from RSDEstimation is used.
112  * \param[in] nr_subdiv the number of subdivisions
113  */
114  inline void
115  setNrSubdivisions (int nr_subdiv) { rsd_nr_subdiv_ = nr_subdiv; }
116 
117  /** \brief Set the maximum radius, above which everything can be considered planar.
118  * This function configures the underlying RSDEstimation. For more info, see
119  * there. If this function is not called, the default from RSDEstimation is used.
120  * \param[in] plane_radius the new plane radius
121  */
122  inline void
123  setPlaneRadius (double plane_radius) { rsd_plane_radius_ = plane_radius; }
124 
125  /** \brief Get the type of the local surface based on the min and max radius computed.
126  * \return the integer that represents the type of the local surface with values as
127  * Plane (1), Cylinder (2), Noise or corner (0), Sphere (3) and Edge (4)
128  */
129  static inline int
130  getSimpleType (float min_radius, float max_radius,
131  double min_radius_plane = 0.100,
132  double max_radius_noise = 0.015,
133  double min_radius_cylinder = 0.175,
134  double max_min_radius_diff = 0.050);
135 
136  protected:
137 
138  /** \brief Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by
139  * <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
140  * setSearchMethod ()
141  * \param output the resultant point cloud that contains the GRSD feature
142  */
143  void
144  computeFeature (PointCloudOut &output) override;
145 
146  private:
147 
148  /** \brief Defines if an additive feature is computed or ray-casting is used to get a more descriptive feature. */
149  bool additive_ = true;
150 
151  /** \brief Defines the voxel size to be used. */
152  double width_ = 0.0;
153 
154  /** \brief For the underlying RSDEstimation. The number of subdivisions for the considered distance interval. */
155  int rsd_nr_subdiv_ = 0;
156 
157  /** \brief For the underlying RSDEstimation. The maximum radius, above which everything can be considered planar. */
158  double rsd_plane_radius_ = 0.0;
159 
160  /** \brief Pre-computed the relative cell indices of all the 26 neighbors. */
161  Eigen::MatrixXi relative_coordinates_all_;
162 
163  };
164 
165 }
166 
167 #ifdef PCL_NO_PRECOMPILE
168 #include <pcl/features/impl/grsd.hpp>
169 #endif
Feature represents the base feature class.
Definition: feature.h:107
typename PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:121
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:237
std::string feature_name_
The feature name.
Definition: feature.h:220
GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud da...
Definition: grsd.h:73
static int getSimpleType(float min_radius, float max_radius, double min_radius_plane=0.100, double max_radius_noise=0.015, double min_radius_cylinder=0.175, double max_min_radius_diff=0.050)
Get the type of the local surface based on the min and max radius computed.
Definition: grsd.hpp:46
void computeFeature(PointCloudOut &output) override
Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by <setInputClou...
Definition: grsd.hpp:65
void setPlaneRadius(double plane_radius)
Set the maximum radius, above which everything can be considered planar.
Definition: grsd.h:123
void setRadiusSearch(double radius)
Set the sphere radius that is to be used for determining the nearest neighbors used for the feature e...
Definition: grsd.h:101
double getRadiusSearch() const
Get the sphere radius used for determining the neighbors.
Definition: grsd.h:107
void setNrSubdivisions(int nr_subdiv)
Set the number of subdivisions for the considered distance interval.
Definition: grsd.h:115
typename Feature< PointInT, PointOutT >::PointCloudOut PointCloudOut
Definition: grsd.h:85
GRSDEstimation()
Constructor.
Definition: grsd.h:90
Eigen::MatrixXi getAllNeighborCellIndices()
Get the relative cell indices of all the 26 neighbors.
Definition: voxel_grid.h:153