Point Cloud Library (PCL)  1.14.1-dev
cvfh.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, 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  * $Id$
38  *
39  */
40 
41 #ifndef PCL_FEATURES_IMPL_CVFH_H_
42 #define PCL_FEATURES_IMPL_CVFH_H_
43 
44 #include <pcl/features/cvfh.h>
45 #include <pcl/features/normal_3d.h>
46 #include <pcl/common/centroid.h>
47 
48 //////////////////////////////////////////////////////////////////////////////////////////////
49 template<typename PointInT, typename PointNT, typename PointOutT> void
51 {
53  {
54  output.width = output.height = 0;
55  output.clear ();
56  return;
57  }
58  // Resize the output dataset
59  // Important! We should only allocate precisely how many elements we will need, otherwise
60  // we risk at pre-allocating too much memory which could lead to bad_alloc
61  // (see http://dev.pointclouds.org/issues/657)
62  output.width = output.height = 1;
63  output.resize (1);
64 
65  // Perform the actual feature computation
66  computeFeature (output);
67 
69 }
70 
71 //////////////////////////////////////////////////////////////////////////////////////////////
72 template<typename PointInT, typename PointNT, typename PointOutT> void
75  const pcl::PointCloud<pcl::PointNormal> &normals,
76  float tolerance,
78  std::vector<pcl::PointIndices> &clusters,
79  double eps_angle,
80  unsigned int min_pts_per_cluster,
81  unsigned int max_pts_per_cluster)
82 {
83  if (tree->getInputCloud ()->size () != cloud.size ())
84  {
85  PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point cloud "
86  "dataset (%zu) than the input cloud (%zu)!\n",
87  static_cast<std::size_t>(tree->getInputCloud()->size()),
88  static_cast<std::size_t>(cloud.size()));
89  return;
90  }
91  if (cloud.size () != normals.size ())
92  {
93  PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point "
94  "cloud (%zu) different than normals (%zu)!\n",
95  static_cast<std::size_t>(cloud.size()),
96  static_cast<std::size_t>(normals.size()));
97  return;
98  }
99  // If tree gives sorted results, we can skip the first one because it is the query point itself
100  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
101 
102  // Create a bool vector of processed point indices, and initialize it to false
103  std::vector<bool> processed (cloud.size (), false);
104 
105  pcl::Indices nn_indices;
106  std::vector<float> nn_distances;
107  // Process all points in the indices vector
108  for (std::size_t i = 0; i < cloud.size (); ++i)
109  {
110  if (processed[i])
111  continue;
112  processed[i] = true;
113 
115  r.header = cloud.header;
116  auto& seed_queue = r.indices;
117 
118  seed_queue.push_back (i);
119 
120  // loop has an emplace_back, making it difficult to use modern loops
121  for (std::size_t idx = 0; idx != seed_queue.size (); ++idx)
122  {
123  // Search for seed_queue[index]
124  if (!tree->radiusSearch (seed_queue[idx], tolerance, nn_indices, nn_distances))
125  {
126  continue;
127  }
128 
129  for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
130  {
131  if (processed[nn_indices[j]]) // Has this point been processed before ?
132  continue;
133 
134  //processed[nn_indices[j]] = true;
135  // [-1;1]
136  const double dot_p = normals[seed_queue[idx]].getNormalVector3fMap().dot(
137  normals[nn_indices[j]].getNormalVector3fMap());
138 
139  if (std::acos (dot_p) < eps_angle)
140  {
141  processed[nn_indices[j]] = true;
142  seed_queue.emplace_back (nn_indices[j]);
143  }
144  }
145  }
146 
147  // If this queue is satisfactory, add to the clusters
148  if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
149  {
150  std::sort (r.indices.begin (), r.indices.end ());
151  r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
152 
153  // Might be better to work directly in the cluster somehow
154  clusters.emplace_back (std::move(r)); // Trying to avoid a copy by moving
155  }
156  }
157 }
158 
159 //////////////////////////////////////////////////////////////////////////////////////////////
160 template<typename PointInT, typename PointNT, typename PointOutT> void
162  const pcl::PointCloud<PointNT> & cloud,
163  pcl::Indices &indices_to_use,
164  pcl::Indices &indices_out,
165  pcl::Indices &indices_in,
166  float threshold)
167 {
168  indices_out.resize (cloud.size ());
169  indices_in.resize (cloud.size ());
170 
171  std::size_t in, out;
172  in = out = 0;
173 
174  for (const auto &index : indices_to_use)
175  {
176  if (cloud[index].curvature > threshold)
177  {
178  indices_out[out] = index;
179  out++;
180  }
181  else
182  {
183  indices_in[in] = index;
184  in++;
185  }
186  }
187 
188  indices_out.resize (out);
189  indices_in.resize (in);
190 }
191 
192 //////////////////////////////////////////////////////////////////////////////////////////////
193 template<typename PointInT, typename PointNT, typename PointOutT> void
195 {
196  // Check if input was set
197  if (!normals_)
198  {
199  PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ());
200  output.width = output.height = 0;
201  output.clear ();
202  return;
203  }
204  if (normals_->size () != surface_->size ())
205  {
206  PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ());
207  output.width = output.height = 0;
208  output.clear ();
209  return;
210  }
211 
212  centroids_dominant_orientations_.clear ();
213 
214  // ---[ Step 0: remove normals with high curvature
215  pcl::Indices indices_out;
216  pcl::Indices indices_in;
217  filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_);
218 
220  normals_filtered_cloud->width = indices_in.size ();
221  normals_filtered_cloud->height = 1;
222  normals_filtered_cloud->points.resize (normals_filtered_cloud->width);
223 
224  for (std::size_t i = 0; i < indices_in.size (); ++i)
225  {
226  (*normals_filtered_cloud)[i].x = (*surface_)[indices_in[i]].x;
227  (*normals_filtered_cloud)[i].y = (*surface_)[indices_in[i]].y;
228  (*normals_filtered_cloud)[i].z = (*surface_)[indices_in[i]].z;
229  }
230 
231  std::vector<pcl::PointIndices> clusters;
232 
233  if(normals_filtered_cloud->size() >= min_points_)
234  {
235  //recompute normals and use them for clustering
236  KdTreePtr normals_tree_filtered (new pcl::search::KdTree<pcl::PointNormal> (false));
237  normals_tree_filtered->setInputCloud (normals_filtered_cloud);
238 
239 
241  n3d.setRadiusSearch (radius_normals_);
242  n3d.setSearchMethod (normals_tree_filtered);
243  n3d.setInputCloud (normals_filtered_cloud);
244  n3d.compute (*normals_filtered_cloud);
245 
246  KdTreePtr normals_tree (new pcl::search::KdTree<pcl::PointNormal> (false));
247  normals_tree->setInputCloud (normals_filtered_cloud);
248 
249  extractEuclideanClustersSmooth (*normals_filtered_cloud,
250  *normals_filtered_cloud,
251  cluster_tolerance_,
252  normals_tree,
253  clusters,
254  eps_angle_threshold_,
255  static_cast<unsigned int> (min_points_));
256 
257  }
258 
259  VFHEstimator vfh;
260  vfh.setInputCloud (surface_);
261  vfh.setInputNormals (normals_);
262  vfh.setIndices(indices_);
263  vfh.setSearchMethod (this->tree_);
264  vfh.setUseGivenNormal (true);
265  vfh.setUseGivenCentroid (true);
266  vfh.setNormalizeBins (normalize_bins_);
267  vfh.setNormalizeDistance (true);
268  vfh.setFillSizeComponent (true);
269  output.height = 1;
270 
271  // ---[ Step 1b : check if any dominant cluster was found
272  if (!clusters.empty ())
273  { // ---[ Step 1b.1 : If yes, compute CVFH using the cluster information
274 
275  for (const auto &cluster : clusters) //for each cluster
276  {
277  Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
278  Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
279 
280  for (const auto &index : cluster.indices)
281  {
282  avg_normal += (*normals_filtered_cloud)[index].getNormalVector4fMap ();
283  avg_centroid += (*normals_filtered_cloud)[index].getVector4fMap ();
284  }
285 
286  avg_normal /= static_cast<float> (cluster.indices.size ());
287  avg_centroid /= static_cast<float> (cluster.indices.size ());
288 
289  Eigen::Vector4f centroid_test;
290  pcl::compute3DCentroid (*normals_filtered_cloud, centroid_test);
291  avg_normal.normalize ();
292 
293  Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]);
294  Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
295 
296  //append normal and centroid for the clusters
297  dominant_normals_.push_back (avg_norm);
298  centroids_dominant_orientations_.push_back (avg_dominant_centroid);
299  }
300 
301  //compute modified VFH for all dominant clusters and add them to the list!
302  output.resize (dominant_normals_.size ());
303  output.width = dominant_normals_.size ();
304 
305  for (std::size_t i = 0; i < dominant_normals_.size (); ++i)
306  {
307  //configure VFH computation for CVFH
308  vfh.setNormalToUse (dominant_normals_[i]);
309  vfh.setCentroidToUse (centroids_dominant_orientations_[i]);
311  vfh.compute (vfh_signature);
312  output[i] = vfh_signature[0];
313  }
314  }
315  else
316  { // ---[ Step 1b.1 : If no, compute CVFH using all the object points
317  Eigen::Vector4f avg_centroid;
318  pcl::compute3DCentroid (*surface_, avg_centroid);
319  Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
320  centroids_dominant_orientations_.push_back (cloud_centroid);
321 
322  //configure VFH computation for CVFH using all object points
323  vfh.setCentroidToUse (cloud_centroid);
324  vfh.setUseGivenNormal (false);
325 
327  vfh.compute (vfh_signature);
328 
329  output.resize (1);
330  output.width = 1;
331 
332  output[0] = vfh_signature[0];
333  }
334 }
335 
336 #define PCL_INSTANTIATE_CVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::CVFHEstimation<T,NT,OutT>;
337 
338 #endif // PCL_FEATURES_IMPL_VFH_H_
Define methods for centroid estimation and covariance matrix calculus.
CVFHEstimation estimates the Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given poin...
Definition: cvfh.h:63
typename Feature< PointInT, PointOutT >::PointCloudOut PointCloudOut
Definition: cvfh.h:76
void filterNormalsWithHighCurvature(const pcl::PointCloud< PointNT > &cloud, pcl::Indices &indices_to_use, pcl::Indices &indices_out, pcl::Indices &indices_in, float threshold)
Removes normals with high curvature caused by real edges or noisy data.
Definition: cvfh.hpp:161
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
Definition: cvfh.hpp:50
Feature represents the base feature class.
Definition: feature.h:107
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 setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
Definition: feature.h:164
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:194
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point.
Definition: normal_3d.h:244
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition: normal_3d.h:328
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
reference emplace_back(Args &&...args)
Emplace a new point in the cloud, at the end of the container.
Definition: point_cloud.h:686
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
std::size_t size() const
Definition: point_cloud.h:443
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
virtual bool getSortedResults()
Gets whether the results should be sorted (ascending in the distance) or not Otherwise the results ma...
Definition: search.hpp:68
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:81
virtual PointCloudConstPtr getInputCloud() const
Get a pointer to the input point cloud dataset.
Definition: search.h:124
virtual int radiusSearch(const PointT &point, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const =0
Search for all the nearest neighbors of the query point in a given radius.
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > &centroid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
Definition: centroid.hpp:57
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
::pcl::PCLHeader header
Definition: PointIndices.h:18