Point Cloud Library (PCL)  1.14.0-dev
vfh.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_VFH_H_
42 #define PCL_FEATURES_IMPL_VFH_H_
43 
44 #include <pcl/features/vfh.h>
45 #include <pcl/features/pfh_tools.h>
46 #include <pcl/common/common.h>
47 #include <pcl/common/centroid.h>
48 
49 //////////////////////////////////////////////////////////////////////////////////////////////
50 template<typename PointInT, typename PointNT, typename PointOutT> bool
52 {
53  if (input_->size () < 2 || (surface_ && surface_->size () < 2))
54  {
55  PCL_ERROR ("[pcl::VFHEstimation::initCompute] Input dataset must have at least 2 points!\n");
56  return (false);
57  }
58  if (search_radius_ == 0 && k_ == 0)
59  k_ = 1;
61 }
62 
63 //////////////////////////////////////////////////////////////////////////////////////////////
64 template<typename PointInT, typename PointNT, typename PointOutT> void
66 {
67  if (!initCompute ())
68  {
69  output.width = output.height = 0;
70  output.clear ();
71  return;
72  }
73  // Copy the header
74  output.header = input_->header;
75 
76  // Resize the output dataset
77  // Important! We should only allocate precisely how many elements we will need, otherwise
78  // we risk at pre-allocating too much memory which could lead to bad_alloc
79  // (see http://dev.pointclouds.org/issues/657)
80  output.width = output.height = 1;
81  output.is_dense = input_->is_dense;
82  output.resize (1);
83 
84  // Perform the actual feature computation
85  computeFeature (output);
86 
88 }
89 
90 //////////////////////////////////////////////////////////////////////////////////////////////
91 template<typename PointInT, typename PointNT, typename PointOutT> void
93  const Eigen::Vector4f &centroid_n,
94  const pcl::PointCloud<PointInT> &cloud,
95  const pcl::PointCloud<PointNT> &normals,
96  const pcl::Indices &indices)
97 {
98  Eigen::Vector4f pfh_tuple;
99  // Reset the whole thing
100  for (int i = 0; i < 4; ++i)
101  {
102  hist_f_[i].setZero (nr_bins_f_[i]);
103  }
104 
105  // Get the bounding box of the current cluster
106  //Eigen::Vector4f min_pt, max_pt;
107  //pcl::getMinMax3D (cloud, indices, min_pt, max_pt);
108  //double distance_normalization_factor = (std::max)((centroid_p - min_pt).norm (), (centroid_p - max_pt).norm ());
109 
110  //Instead of using the bounding box to normalize the VFH distance component, it is better to use the max_distance
111  //from any point to centroid. VFH is invariant to rotation about the roll axis but the bounding box is not,
112  //resulting in different normalization factors for point clouds that are just rotated about that axis.
113 
114  double distance_normalization_factor = 1.0;
115  if (normalize_distances_)
116  {
117  Eigen::Vector4f max_pt;
118  pcl::getMaxDistance (cloud, indices, centroid_p, max_pt);
119  max_pt[3] = 0;
120  distance_normalization_factor = (centroid_p - max_pt).norm ();
121  }
122 
123  // Factorization constant
124  float hist_incr = 1;
125  if (normalize_bins_)
126  hist_incr = 100.0f / static_cast<float> (indices.size () - 1);
127 
128  float hist_incr_size_component = 0;
129  if (size_component_)
130  hist_incr_size_component = hist_incr;
131 
132  // Iterate over all the points in the neighborhood
133  for (const auto &index : indices)
134  {
135  // Compute the pair P to NNi
136  if (!computePairFeatures (centroid_p, centroid_n, cloud[index].getVector4fMap (),
137  normals[index].getNormalVector4fMap (), pfh_tuple[0], pfh_tuple[1],
138  pfh_tuple[2], pfh_tuple[3]))
139  continue;
140 
141  // Normalize the f1, f2, f3, f4 features and push them in the histogram
142  for (int i = 0; i < 3; ++i)
143  {
144  const int raw_index = static_cast<int> (std::floor (nr_bins_f_[i] * ((pfh_tuple[i] + M_PI) * d_pi_)));
145  const int h_index = std::max(std::min(raw_index, nr_bins_f_[i] - 1), 0);
146  hist_f_[i] (h_index) += hist_incr;
147  }
148 
149  if (hist_incr_size_component)
150  {
151  int h_index;
152  if (normalize_distances_)
153  h_index = static_cast<int> (std::floor (nr_bins_f_[3] * (pfh_tuple[3] / distance_normalization_factor)));
154  else
155  h_index = static_cast<int> (pcl_round (pfh_tuple[3] * 100));
156 
157  h_index = std::max (std::min (h_index, nr_bins_f_[3] - 1), 0);
158  hist_f_[3] (h_index) += hist_incr_size_component;
159  }
160  }
161 }
162 //////////////////////////////////////////////////////////////////////////////////////////////
163 template <typename PointInT, typename PointNT, typename PointOutT> void
165 {
166  // ---[ Step 1a : compute the centroid in XYZ space
167  Eigen::Vector4f xyz_centroid (0, 0, 0, 0);
168 
169  if (use_given_centroid_)
170  xyz_centroid = centroid_to_use_;
171  else
172  compute3DCentroid (*surface_, *indices_, xyz_centroid); // Estimate the XYZ centroid
173 
174  // ---[ Step 1b : compute the centroid in normal space
175  Eigen::Vector4f normal_centroid = Eigen::Vector4f::Zero ();
176 
177  // If the data is dense, we don't need to check for NaN
178  if (use_given_normal_)
179  normal_centroid = normal_to_use_;
180  else
181  {
182  std::size_t cp = 0;
183  if (normals_->is_dense)
184  {
185  for (const auto& index: *indices_)
186  {
187  normal_centroid.noalias () += (*normals_)[index].getNormalVector4fMap ();
188  }
189  cp = indices_->size();
190  }
191  // NaN or Inf values could exist => check for them
192  else
193  {
194  for (const auto& index: *indices_)
195  {
196  if (!std::isfinite ((*normals_)[index].normal[0]) ||
197  !std::isfinite ((*normals_)[index].normal[1]) ||
198  !std::isfinite ((*normals_)[index].normal[2]))
199  continue;
200  normal_centroid.noalias () += (*normals_)[index].getNormalVector4fMap ();
201  cp++;
202  }
203  }
204  normal_centroid /= static_cast<float> (cp);
205  }
206 
207  // Compute the direction of view from the viewpoint to the centroid
208  Eigen::Vector4f viewpoint (vpx_, vpy_, vpz_, 0);
209  Eigen::Vector4f d_vp_p = viewpoint - xyz_centroid;
210  d_vp_p.normalize ();
211 
212  // Estimate the SPFH at nn_indices[0] using the entire cloud
213  computePointSPFHSignature (xyz_centroid, normal_centroid, *surface_, *normals_, *indices_);
214 
215  // ---[ Step 2 : obtain the viewpoint component
216  hist_vp_.setZero (nr_bins_vp_);
217 
218  float hist_incr = 1.0;
219  if (normalize_bins_)
220  hist_incr = 100.0 / static_cast<double> (indices_->size ());
221 
222  for (const auto& index: *indices_)
223  {
224  Eigen::Vector4f normal ((*normals_)[index].normal[0],
225  (*normals_)[index].normal[1],
226  (*normals_)[index].normal[2], 0);
227  // Normalize
228  double alpha = (normal.dot (d_vp_p) + 1.0) * 0.5;
229  auto fi = static_cast<std::size_t> (std::floor (alpha * hist_vp_.size ()));
230  fi = std::max<std::size_t> (0u, fi);
231  fi = std::min<std::size_t> (hist_vp_.size () - 1, fi);
232  // Bin into the histogram
233  hist_vp_ [fi] += hist_incr;
234  }
235 
236  // We only output _1_ signature
237  output.resize (1);
238  output.width = 1;
239  output.height = 1;
240 
241  // Estimate the FPFH at nn_indices[0] using the entire cloud and copy the resultant signature
242  auto outPtr = std::begin (output[0].histogram);
243 
244  for (int i = 0; i < 4; ++i)
245  {
246  outPtr = std::copy (hist_f_[i].data (), hist_f_[i].data () + hist_f_[i].size (), outPtr);
247  }
248  outPtr = std::copy (hist_vp_.data (), hist_vp_.data () + hist_vp_.size (), outPtr);
249 }
250 
251 #define PCL_INSTANTIATE_VFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::VFHEstimation<T,NT,OutT>;
252 
253 #endif // PCL_FEATURES_IMPL_VFH_H_
Define methods for centroid estimation and covariance matrix calculus.
Feature represents the base feature class.
Definition: feature.h:107
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:403
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
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
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
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud data...
Definition: vfh.h:73
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
Definition: vfh.hpp:65
bool initCompute() override
This method should get called before starting the actual computation.
Definition: vfh.hpp:51
void computePointSPFHSignature(const Eigen::Vector4f &centroid_p, const Eigen::Vector4f &centroid_n, const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const pcl::Indices &indices)
Estimate the SPFH (Simple Point Feature Histograms) signatures of the angular (f1,...
Definition: vfh.hpp:92
Define standard C methods and C++ classes that are common to all methods.
void getMaxDistance(const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt)
Get the point at maximum distance from a given point and a given pointcloud.
Definition: common.hpp:197
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
PCL_EXPORTS bool computePairFeatures(const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4)
Compute the 4-tuple representation containing the three angles and one distance between two points re...
int cp(int from, int to)
Returns field copy operation code.
Definition: repacks.hpp:56
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
__inline double pcl_round(double number)
Win32 doesn't seem to have rounding functions.
Definition: pcl_macros.h:239
#define M_PI
Definition: pcl_macros.h:201