Point Cloud Library (PCL)  1.9.1-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 ///////// STATIC /////////
44 template <typename PointInT, typename PointNT, typename PointOutT> int
46  double min_radius_plane,
47  double max_radius_noise,
48  double min_radius_cylinder,
49  double max_min_radius_diff)
50 {
51  if (min_radius > min_radius_plane)
52  return (1); // plane
53  if (max_radius > min_radius_cylinder)
54  return (2); // cylinder (rim)
55  if (min_radius < max_radius_noise)
56  return (0); // noise/corner
57  if (max_radius - min_radius < max_min_radius_diff)
58  return (3); // sphere/corner
59  return (4); // edge
60 }
61 
62 //////////////////////////////////////////////////////////////////////////////////////////////
63 template <typename PointInT, typename PointNT, typename PointOutT> void
65 {
66  // Check if search_radius_ was set
67  if (width_ < 0)
68  {
69  PCL_ERROR ("[pcl::%s::computeFeature] A voxel cell width needs to be set!\n", getClassName ().c_str ());
70  output.width = output.height = 0;
71  output.points.clear ();
72  return;
73  }
74 
75  // Create the voxel grid
76  PointCloudInPtr cloud_downsampled (new PointCloudIn());
78  grid.setLeafSize (width_, width_, width_);
79  grid.setInputCloud (input_);
80  grid.setSaveLeafLayout (true); // TODO maybe avoid this using nearest neighbor search
81  grid.filter (*cloud_downsampled);
82 
83  // Compute RSD
86  rsd.setInputCloud (cloud_downsampled);
87  rsd.setSearchSurface (input_);
88  rsd.setInputNormals (normals_);
89  rsd.setRadiusSearch (std::max (search_radius_, std::sqrt (3.0) * width_ / 2));
90  rsd.compute (*radii);
91 
92  // Save the type of each point
93  int NR_CLASS = 5; // TODO make this nicer
94  std::vector<int> types (radii->points.size ());
95  for (size_t idx = 0; idx < radii->points.size (); ++idx)
96  types[idx] = getSimpleType (radii->points[idx].r_min, radii->points[idx].r_max);
97 
98  // Get the transitions between surface types between neighbors of occupied cells
99  Eigen::MatrixXi transition_matrix = Eigen::MatrixXi::Zero (NR_CLASS + 1, NR_CLASS + 1);
100  for (size_t idx = 0; idx < cloud_downsampled->points.size (); ++idx)
101  {
102  int source_type = types[idx];
103  std::vector<int> neighbors = grid.getNeighborCentroidIndices (cloud_downsampled->points[idx], relative_coordinates_all_);
104  for (const int &neighbor : neighbors)
105  {
106  int neighbor_type;
107  if (neighbor == -1) // empty
108  neighbor_type = NR_CLASS;
109  else
110  neighbor_type = types[neighbor];
111  transition_matrix (source_type, neighbor_type)++;
112  }
113  }
114 
115  // Save feature values
116  output.points.resize (1);
117  output.height = output.width = 1;
118  int nrf = 0;
119  for (int i = 0; i < NR_CLASS + 1; i++)
120  for (int j = i; j < NR_CLASS + 1; j++)
121  output.points[0].histogram[nrf++] = transition_matrix (i, j) + transition_matrix (j, i);
122 }
123 
124 #define PCL_INSTANTIATE_GRSDEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::GRSDEstimation<T,NT,OutT>;
125 
126 #endif /* PCL_FEATURES_IMPL_GRSD_H_ */
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:148
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:411
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
void setSaveLeafLayout(bool save_leaf_layout)
Set to true if leaf layout information needs to be saved for later access.
Definition: voxel_grid.h:279
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:200
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
Definition: filter.h:130
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data...
Definition: voxel_grid.h:177
uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:416
void computeFeature(PointCloudOut &output) override
Estimate the Global Radius-based Surface Descriptor (GRSD) for a set of points given by <setInputClou...
Definition: grsd.hpp:64
uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:414
RSDEstimation estimates the Radius-based Surface Descriptor (minimal and maximal radius of the local ...
Definition: rsd.h:150
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:429
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
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:332
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:192
void setInputNormals(const PointCloudNConstPtr &normals)
Provide a pointer to the input dataset that contains the point normals of the XYZ dataset...
Definition: feature.h:344
typename PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:120
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:222