Point Cloud Library (PCL)  1.14.0-dev
grsd.hpp
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 #ifndef PCL_FEATURES_IMPL_GRSD_H_
40 #define PCL_FEATURES_IMPL_GRSD_H_
41 
42 #include <pcl/features/grsd.h>
43 #include <pcl/features/rsd.h> // for RSDEstimation
44 ///////// STATIC /////////
45 template <typename PointInT, typename PointNT, typename PointOutT> int
47  double min_radius_plane,
48  double max_radius_noise,
49  double min_radius_cylinder,
50  double max_min_radius_diff)
51 {
52  if (min_radius > min_radius_plane)
53  return (1); // plane
54  if (max_radius > min_radius_cylinder)
55  return (2); // cylinder (rim)
56  if (min_radius < max_radius_noise)
57  return (0); // noise/corner
58  if (max_radius - min_radius < max_min_radius_diff)
59  return (3); // sphere/corner
60  return (4); // edge
61 }
62 
63 //////////////////////////////////////////////////////////////////////////////////////////////
64 template <typename PointInT, typename PointNT, typename PointOutT> void
66 {
67  // Check if search_radius_ was set
68  if (width_ <= 0.0)
69  {
70  PCL_ERROR ("[pcl::%s::computeFeature] A voxel cell width needs to be set!\n", getClassName ().c_str ());
71  output.width = output.height = 0;
72  output.clear ();
73  return;
74  }
75 
76  // Create the voxel grid
77  PointCloudInPtr cloud_downsampled (new PointCloudIn());
79  grid.setLeafSize (width_, width_, width_);
80  grid.setInputCloud (input_);
81  grid.setSaveLeafLayout (true); // TODO maybe avoid this using nearest neighbor search
82  grid.filter (*cloud_downsampled);
83 
84  // Compute RSD
87  rsd.setInputCloud (cloud_downsampled);
88  rsd.setSearchSurface (input_);
89  rsd.setInputNormals (normals_);
90  rsd.setRadiusSearch (search_radius_);
91  if (rsd_nr_subdiv_ != 0) // if not set, use default from RSDEstimation
92  rsd.setNrSubdivisions (rsd_nr_subdiv_);
93  if (rsd_plane_radius_ != 0.0)
94  rsd.setPlaneRadius (rsd_plane_radius_);
95  rsd.compute (*radii);
96 
97  // Save the type of each point
98  int NR_CLASS = 5; // TODO make this nicer
99  std::vector<int> types (radii->size ());
100  std::transform(radii->points.cbegin (), radii->points.cend (), types.begin (),
101  [](const auto& point) {
102  // GCC 5.4 can't find unqualified getSimpleType
103  return GRSDEstimation<PointInT, PointNT, PointOutT>::getSimpleType(point.r_min, point.r_max); });
104 
105  // Get the transitions between surface types between neighbors of occupied cells
106  Eigen::MatrixXi transition_matrix = Eigen::MatrixXi::Zero (NR_CLASS + 1, NR_CLASS + 1);
107  for (std::size_t idx = 0; idx < cloud_downsampled->size (); ++idx)
108  {
109  const int source_type = types[idx];
110  std::vector<int> neighbors = grid.getNeighborCentroidIndices ((*cloud_downsampled)[idx], relative_coordinates_all_);
111  for (const int &neighbor : neighbors)
112  {
113  int neighbor_type = NR_CLASS;
114  if (neighbor != -1) // not empty
115  neighbor_type = types[neighbor];
116  transition_matrix (source_type, neighbor_type)++;
117  }
118  }
119 
120  // Save feature values
121  output.resize (1);
122  output.height = output.width = 1;
123  int nrf = 0;
124  for (int i = 0; i < NR_CLASS + 1; i++)
125  for (int j = i; j < NR_CLASS + 1; j++)
126  output[0].histogram[nrf++] = transition_matrix (i, j) + transition_matrix (j, i);
127 }
128 
129 #define PCL_INSTANTIATE_GRSDEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::GRSDEstimation<T,NT,OutT>;
130 
131 #endif /* PCL_FEATURES_IMPL_GRSD_H_ */
void setInputNormals(const PointCloudNConstPtr &normals)
Provide a pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition: feature.h:339
typename PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:121
void setSearchSurface(const PointCloudInConstPtr &cloud)
Provide a pointer to a dataset to add additional information to estimate the features for every point...
Definition: feature.h:146
void setRadiusSearch(double radius)
Set the sphere radius that is to be used for determining the nearest neighbors used for the feature e...
Definition: feature.h:198
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:194
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
Definition: filter.h:121
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
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:885
std::size_t size() const
Definition: point_cloud.h:443
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:395
RSDEstimation estimates the Radius-based Surface Descriptor (minimal and maximal radius of the local ...
Definition: rsd.h:133
void setNrSubdivisions(int nr_subdiv)
Set the number of subdivisions for the considered distance interval.
Definition: rsd.h:160
void setPlaneRadius(double plane_radius)
Set the maximum radius, above which everything can be considered planar.
Definition: rsd.h:174
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition: voxel_grid.h:210
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:247
void setSaveLeafLayout(bool save_leaf_layout)
Set to true if leaf layout information needs to be saved for later access.
Definition: voxel_grid.h:304
std::vector< int > getNeighborCentroidIndices(const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) const
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinate...
Definition: voxel_grid.h:357