Point Cloud Library (PCL)  1.15.1-dev
boundary.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 #pragma once
42 
43 #include <pcl/features/boundary.h>
44 #include <pcl/common/point_tests.h> // for pcl::isFinite
45 
46 #include <cfloat>
47 
48 #ifdef _OPENMP
49 #include <omp.h>
50 #endif
51 
52 template <typename PointInT, typename PointNT, typename PointOutT>
53 void
55  unsigned int nr_threads)
56 {
57 #ifdef _OPENMP
58  if (nr_threads == 0)
59  threads_ = omp_get_num_procs();
60  else
61  threads_ = nr_threads;
62  PCL_DEBUG("[pcl::BoundaryEstimation::setNumberOfThreads] Setting number of threads "
63  "to %u.\n",
64  threads_);
65 #else
66  threads_ = 1;
67  if (nr_threads != 1)
68  PCL_WARN(
69  "[pcl::BoundaryEstimation::setNumberOfThreads] Parallelization is requested, "
70  "but OpenMP is not available! Continuing without parallelization.\n");
71 #endif // _OPENMP
72 }
73 
74 //////////////////////////////////////////////////////////////////////////////////////////////
75 template <typename PointInT, typename PointNT, typename PointOutT> bool
77  const pcl::PointCloud<PointInT> &cloud, int q_idx,
78  const pcl::Indices &indices,
79  const Eigen::Vector4f &u, const Eigen::Vector4f &v,
80  const float angle_threshold) const
81 {
82  return (isBoundaryPoint (cloud, cloud[q_idx], indices, u, v, angle_threshold));
83 }
84 
85 //////////////////////////////////////////////////////////////////////////////////////////////
86 template <typename PointInT, typename PointNT, typename PointOutT> bool
88  const pcl::PointCloud<PointInT> &cloud, const PointInT &q_point,
89  const pcl::Indices &indices,
90  const Eigen::Vector4f &u, const Eigen::Vector4f &v,
91  const float angle_threshold) const
92 {
93  if (indices.size () < 3)
94  return (false);
95 
96  if (!std::isfinite (q_point.x) || !std::isfinite (q_point.y) || !std::isfinite (q_point.z))
97  return (false);
98 
99  // Compute the angles between each neighboring point and the query point itself
100  std::vector<float> angles (indices.size ());
101  float max_dif = 0, dif;
102  int cp = 0;
103 
104  for (const auto &index : indices)
105  {
106  if (!std::isfinite (cloud[index].x) ||
107  !std::isfinite (cloud[index].y) ||
108  !std::isfinite (cloud[index].z))
109  continue;
110 
111  Eigen::Vector4f delta = cloud[index].getVector4fMap () - q_point.getVector4fMap ();
112  if (delta == Eigen::Vector4f::Zero())
113  continue;
114 
115  angles[cp++] = std::atan2 (v.dot (delta), u.dot (delta)); // the angles are fine between -PI and PI too
116  }
117  if (cp == 0)
118  return (false);
119 
120  angles.resize (cp);
121  std::sort (angles.begin (), angles.end ());
122 
123  // Compute the maximal angle difference between two consecutive angles
124  for (std::size_t i = 0; i < angles.size () - 1; ++i)
125  {
126  dif = angles[i + 1] - angles[i];
127  if (max_dif < dif)
128  max_dif = dif;
129  }
130  // Get the angle difference between the last and the first
131  dif = 2 * static_cast<float> (M_PI) - angles[angles.size () - 1] + angles[0];
132  if (max_dif < dif)
133  max_dif = dif;
134 
135  // Check results
136  return (max_dif > angle_threshold);
137 }
138 
139 //////////////////////////////////////////////////////////////////////////////////////////////
140 template <typename PointInT, typename PointNT, typename PointOutT> void
142 {
143  // Allocate enough space to hold the results
144  // \note This resize is irrelevant for a radiusSearch ().
145  pcl::Indices nn_indices (k_);
146  std::vector<float> nn_dists (k_);
147 
148  Eigen::Vector4f u = Eigen::Vector4f::Zero (), v = Eigen::Vector4f::Zero ();
149 
150  output.is_dense = true;
151  // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
152  if (input_->is_dense)
153  {
154  #pragma omp parallel for \
155  default(none) \
156  shared(output) \
157  firstprivate(nn_indices, nn_dists, u, v) \
158  num_threads(threads_) \
159  schedule(dynamic, chunk_size_)
160  // Iterating over the entire index vector
161  for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t>(indices_->size());
162  ++idx)
163  {
164  if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
165  {
166  output[idx].boundary_point = std::numeric_limits<std::uint8_t>::quiet_NaN ();
167  output.is_dense = false;
168  continue;
169  }
170 
171  // Obtain a coordinate system on the least-squares plane
172  //v = (*normals_)[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal ();
173  //u = (*normals_)[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v);
174  getCoordinateSystemOnPlane ((*normals_)[(*indices_)[idx]], u, v);
175 
176  // Estimate whether the point is lying on a boundary surface or not
177  output[idx].boundary_point = isBoundaryPoint (*surface_, (*input_)[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
178  }
179  }
180  else
181  {
182  #pragma omp parallel for \
183  default(none) \
184  shared(output) \
185  firstprivate(nn_indices, nn_dists, u, v) \
186  num_threads(threads_) \
187  schedule(dynamic, chunk_size_)
188  // Iterating over the entire index vector
189  for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t>(indices_->size());
190  ++idx)
191  {
192  if (!isFinite ((*input_)[(*indices_)[idx]]) ||
193  this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
194  {
195  output[idx].boundary_point = std::numeric_limits<std::uint8_t>::quiet_NaN ();
196  output.is_dense = false;
197  continue;
198  }
199 
200  // Obtain a coordinate system on the least-squares plane
201  //v = (*normals_)[(*indices_)[idx]].getNormalVector4fMap ().unitOrthogonal ();
202  //u = (*normals_)[(*indices_)[idx]].getNormalVector4fMap ().cross3 (v);
203  getCoordinateSystemOnPlane ((*normals_)[(*indices_)[idx]], u, v);
204 
205  // Estimate whether the point is lying on a boundary surface or not
206  output[idx].boundary_point = isBoundaryPoint (*surface_, (*input_)[(*indices_)[idx]], nn_indices, u, v, angle_threshold_);
207  }
208  }
209 }
210 
211 #define PCL_INSTANTIATE_BoundaryEstimation(PointInT,PointNT,PointOutT) template class PCL_EXPORTS pcl::BoundaryEstimation<PointInT, PointNT, PointOutT>;
212 
void computeFeature(PointCloudOut &output) override
Estimate whether a set of points is lying on surface boundaries using an angle criterion for all poin...
Definition: boundary.hpp:141
typename Feature< PointInT, PointOutT >::PointCloudOut PointCloudOut
Definition: boundary.h:98
void setNumberOfThreads(unsigned int nr_threads=0)
Initialize the scheduler and set the number of threads to use.
Definition: boundary.hpp:54
bool isBoundaryPoint(const pcl::PointCloud< PointInT > &cloud, int q_idx, const pcl::Indices &indices, const Eigen::Vector4f &u, const Eigen::Vector4f &v, const float angle_threshold) const
Check whether a point is a boundary point in a planar patch of projected points given by indices.
Definition: boundary.hpp:76
bool isFinite(const PointT &pt)
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if f...
Definition: point_tests.h:56
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
#define M_PI
Definition: pcl_macros.h:201