Point Cloud Library (PCL)  1.9.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/features/rsd.h>
43 #include <pcl/filters/voxel_grid.h>
44 #include <pcl/kdtree/kdtree_flann.h>
45 
46 namespace pcl
47 {
48  /** \brief @b GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud dataset
49  * containing points and normals.
50  *
51  * @note If you use this code in any academic work, please cite (first for the ray-casting and second for the additive version):
52  *
53  * <ul>
54  * <li> Z.C. Marton, D. Pangercic, N. Blodow, Michael Beetz.
55  * Combined 2D-3D Categorization and Classification for Multimodal Perception Systems.
56  * In The International Journal of Robotics Research, Sage Publications
57  * pages 1378--1402, Volume 30, Number 11, September 2011.
58  * </li>
59  * <li> A. Kanezaki, Z.C. Marton, D. Pangercic, T. Harada, Y. Kuniyoshi, M. Beetz.
60  * Voxelized Shape and Color Histograms for RGB-D
61  * 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)
62  * San Francisco, California, September 25-30, 2011.
63  * </li>
64  * </ul>
65  *
66  * @note The code is stateful as we do not expect this class to be multicore parallelized. Please look at
67  * \ref FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
68  * \author Zoltan Csaba Marton
69  * \ingroup features
70  */
71 
72  template <typename PointInT, typename PointNT, typename PointOutT>
73  class GRSDEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
74  {
75  public:
84  //using Feature<PointInT, PointOutT>::computeFeature;
85 
89 
90  /** \brief Constructor. */
91  GRSDEstimation () : additive_ (true)
92  {
93  feature_name_ = "GRSDEstimation";
94  relative_coordinates_all_ = getAllNeighborCellIndices ();
95  };
96 
97  /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature
98  * estimation. Same value will be used for the internal voxel grid leaf size.
99  * \param[in] radius the sphere radius used as the maximum distance to consider a point a neighbor
100  */
101  inline void
102  setRadiusSearch (double radius) { width_ = search_radius_ = radius; }
103 
104  /** \brief Get the sphere radius used for determining the neighbors.
105  * \return the sphere radius used as the maximum distance to consider a point a neighbor
106  */
107  inline double
108  getRadiusSearch () const { return (search_radius_); }
109 
110  /** \brief Get the type of the local surface based on the min and max radius computed.
111  * \return the integer that represents the type of the local surface with values as
112  * Plane (1), Cylinder (2), Noise or corner (0), Sphere (3) and Edge (4)
113  */
114  static inline int
115  getSimpleType (float min_radius, float max_radius,
116  double min_radius_plane = 0.100,
117  double max_radius_noise = 0.015,
118  double min_radius_cylinder = 0.175,
119  double max_min_radius_diff = 0.050);
120 
121  protected:
122 
123  /** \brief Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by
124  * <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
125  * setSearchMethod ()
126  * \param output the resultant point cloud that contains the GRSD feature
127  */
128  void
129  computeFeature (PointCloudOut &output) override;
130 
131  private:
132 
133  /** \brief Defines if an additive feature is computed or ray-casting is used to get a more descriptive feature. */
134  bool additive_;
135 
136  /** \brief Defines the voxel size to be used. */
137  double width_;
138 
139  /** \brief Pre-computed the relative cell indices of all the 26 neighbors. */
140  Eigen::MatrixXi relative_coordinates_all_;
141 
142  };
143 
144 }
145 
146 #ifdef PCL_NO_PRECOMPILE
147 #include <pcl/features/impl/grsd.hpp>
148 #endif
GRSDEstimation()
Constructor.
Definition: grsd.h:91
std::string feature_name_
The feature name.
Definition: feature.h:221
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:44
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:45
GRSDEstimation estimates the Global Radius-based Surface Descriptor (GRSD) for a given point cloud da...
Definition: grsd.h:73
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
Feature< PointInT, PointOutT >::PointCloudInPtr PointCloudInPtr
Definition: grsd.h:88
double getRadiusSearch() const
Get the sphere radius used for determining the neighbors.
Definition: grsd.h:108
PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:119
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:102
Feature< PointInT, PointOutT >::PointCloudIn PointCloudIn
Definition: grsd.h:87
Eigen::MatrixXi getAllNeighborCellIndices()
Get the relative cell indices of all the 26 neighbors.
Definition: voxel_grid.h:121
Feature represents the base feature class.
Definition: feature.h:104
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:238
Feature< PointInT, PointOutT >::PointCloudOut PointCloudOut
Definition: grsd.h:86