Point Cloud Library (PCL)  1.15.1-dev
gp3.h
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  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #pragma once
41 
42 // PCL includes
43 #include <pcl/surface/reconstruction.h>
44 
45 #include <fstream>
46 
47 #include <Eigen/Geometry> // for cross
48 
49 namespace pcl
50 {
51  struct PolygonMesh;
52 
53  /** \brief Returns if a point X is visible from point R (or the origin)
54  * when taking into account the segment between the points S1 and S2
55  * \param X 2D coordinate of the point
56  * \param S1 2D coordinate of the segment's first point
57  * \param S2 2D coordinate of the segment's second point
58  * \param R 2D coordinate of the reference point (defaults to 0,0)
59  * \ingroup surface
60  */
61  inline bool
62  isVisible (const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2,
63  const Eigen::Vector2f &R = Eigen::Vector2f::Zero ())
64  {
65  double a0 = S1[1] - S2[1];
66  double b0 = S2[0] - S1[0];
67  double c0 = S1[0]*S2[1] - S2[0]*S1[1];
68  double a1 = -X[1];
69  double b1 = X[0];
70  double c1 = 0;
71  if (R != Eigen::Vector2f::Zero())
72  {
73  a1 += R[1];
74  b1 -= R[0];
75  c1 = R[0]*X[1] - X[0]*R[1];
76  }
77  double div = a0*b1 - b0*a1;
78  double x = (b0*c1 - b1*c0) / div;
79  double y = (a1*c0 - a0*c1) / div;
80 
81  bool intersection_outside_XR;
82  if (R == Eigen::Vector2f::Zero())
83  {
84  if (X[0] > 0)
85  intersection_outside_XR = (x <= 0) || (x >= X[0]);
86  else if (X[0] < 0)
87  intersection_outside_XR = (x >= 0) || (x <= X[0]);
88  else if (X[1] > 0)
89  intersection_outside_XR = (y <= 0) || (y >= X[1]);
90  else if (X[1] < 0)
91  intersection_outside_XR = (y >= 0) || (y <= X[1]);
92  else
93  intersection_outside_XR = true;
94  }
95  else
96  {
97  if (X[0] > R[0])
98  intersection_outside_XR = (x <= R[0]) || (x >= X[0]);
99  else if (X[0] < R[0])
100  intersection_outside_XR = (x >= R[0]) || (x <= X[0]);
101  else if (X[1] > R[1])
102  intersection_outside_XR = (y <= R[1]) || (y >= X[1]);
103  else if (X[1] < R[1])
104  intersection_outside_XR = (y >= R[1]) || (y <= X[1]);
105  else
106  intersection_outside_XR = true;
107  }
108  if (intersection_outside_XR)
109  return true;
110  if (S1[0] > S2[0])
111  return (x <= S2[0]) || (x >= S1[0]);
112  if (S1[0] < S2[0])
113  return (x >= S2[0]) || (x <= S1[0]);
114  if (S1[1] > S2[1])
115  return (y <= S2[1]) || (y >= S1[1]);
116  if (S1[1] < S2[1])
117  return (y >= S2[1]) || (y <= S1[1]);
118  return false;
119  }
120 
121  /** \brief GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points
122  * based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between
123  * areas with different point densities.
124  * \tparam PointInT Point type must have XYZ and normal information, for example `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal`
125  * \author Zoltan Csaba Marton
126  * \ingroup surface
127  */
128  template <typename PointInT>
130  {
131  public:
132  using Ptr = shared_ptr<GreedyProjectionTriangulation<PointInT> >;
133  using ConstPtr = shared_ptr<const GreedyProjectionTriangulation<PointInT> >;
134 
138 
142 
143  enum GP3Type
144  {
145  NONE = -1, // not-defined
146  FREE = 0,
147  FRINGE = 1,
148  BOUNDARY = 2,
149  COMPLETED = 3
150  };
151 
152  /** \brief Empty constructor. */
154 
155  /** \brief Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point
156  * (this will make the algorithm adapt to different point densities in the cloud).
157  * \param[in] mu the multiplier
158  */
159  inline void
160  setMu (double mu) { mu_ = mu; }
161 
162  /** \brief Get the nearest neighbor distance multiplier. */
163  inline double
164  getMu () const { return (mu_); }
165 
166  /** \brief Set the maximum number of nearest neighbors to be searched for.
167  * \param[in] nnn the maximum number of nearest neighbors
168  */
169  inline void
170  setMaximumNearestNeighbors (int nnn) { nnn_ = nnn; }
171 
172  /** \brief Get the maximum number of nearest neighbors to be searched for. */
173  inline int
174  getMaximumNearestNeighbors () const { return (nnn_); }
175 
176  /** \brief Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulating.
177  * \param[in] radius the sphere radius that is to contain all k-nearest neighbors
178  * \note This distance limits the maximum edge length!
179  */
180  inline void
181  setSearchRadius (double radius) { search_radius_ = radius; }
182 
183  /** \brief Get the sphere radius used for determining the k-nearest neighbors. */
184  inline double
185  getSearchRadius () const { return (search_radius_); }
186 
187  /** \brief Set the minimum angle each triangle should have.
188  * \param[in] minimum_angle the minimum angle each triangle should have
189  * \note As this is a greedy approach, this will have to be violated from time to time
190  */
191  inline void
192  setMinimumAngle (double minimum_angle) { minimum_angle_ = minimum_angle; }
193 
194  /** \brief Get the parameter for distance based weighting of neighbors. */
195  inline double
196  getMinimumAngle () const { return (minimum_angle_); }
197 
198  /** \brief Set the maximum angle each triangle can have.
199  * \param[in] maximum_angle the maximum angle each triangle can have
200  * \note For best results, its value should be around 120 degrees
201  */
202  inline void
203  setMaximumAngle (double maximum_angle) { maximum_angle_ = maximum_angle; }
204 
205  /** \brief Get the parameter for distance based weighting of neighbors. */
206  inline double
207  getMaximumAngle () const { return (maximum_angle_); }
208 
209  /** \brief Don't consider points for triangulation if their normal deviates more than this value from the query point's normal.
210  * \param[in] eps_angle maximum surface angle
211  * \note As normal estimation methods usually give smooth transitions at sharp edges, this ensures correct triangulation
212  * by avoiding connecting points from one side to points from the other through forcing the use of the edge points.
213  */
214  inline void
215  setMaximumSurfaceAngle (double eps_angle) { eps_angle_ = eps_angle; }
216 
217  /** \brief Get the maximum surface angle. */
218  inline double
219  getMaximumSurfaceAngle () const { return (eps_angle_); }
220 
221  /** \brief Set the flag if the input normals are oriented consistently.
222  * \param[in] consistent set it to true if the normals are consistently oriented
223  */
224  inline void
225  setNormalConsistency (bool consistent) { consistent_ = consistent; }
226 
227  /** \brief Get the flag for consistently oriented normals. */
228  inline bool
229  getNormalConsistency () const { return (consistent_); }
230 
231  /** \brief Set the flag to order the resulting triangle vertices consistently (positive direction around normal).
232  * @note Assumes consistently oriented normals (towards the viewpoint) -- see setNormalConsistency ()
233  * \param[in] consistent_ordering set it to true if triangle vertices should be ordered consistently
234  */
235  inline void
236  setConsistentVertexOrdering (bool consistent_ordering) { consistent_ordering_ = consistent_ordering; }
237 
238  /** \brief Get the flag signaling consistently ordered triangle vertices. */
239  inline bool
241 
242  /** \brief Get the state of each point after reconstruction.
243  * \note Options are defined as constants: FREE, FRINGE, COMPLETED, BOUNDARY and NONE
244  */
245  inline std::vector<int>
246  getPointStates () const { return (state_); }
247 
248  /** \brief Get the ID of each point after reconstruction.
249  * \note parts are numbered from 0, a -1 denotes unconnected points
250  */
251  inline std::vector<int>
252  getPartIDs () const { return (part_); }
253 
254 
255  /** \brief Get the sfn list. */
256  inline pcl::Indices
257  getSFN () const { return (sfn_); }
258 
259  /** \brief Get the ffn list. */
260  inline pcl::Indices
261  getFFN () const { return (ffn_); }
262 
263  protected:
264  /** \brief The nearest neighbor distance multiplier to obtain the final search radius. */
265  double mu_{0.0};
266 
267  /** \brief The nearest neighbors search radius for each point and the maximum edge length. */
268  double search_radius_{0.0};
269 
270  /** \brief The maximum number of nearest neighbors accepted by searching. */
271  int nnn_{100};
272 
273  /** \brief The preferred minimum angle for the triangles. */
274  double minimum_angle_{M_PI/18};
275 
276  /** \brief The maximum angle for the triangles. */
277  double maximum_angle_{2*M_PI/3};
278 
279  /** \brief Maximum surface angle. */
280  double eps_angle_{M_PI/4};
281 
282  /** \brief Set this to true if the normals of the input are consistently oriented. */
283  bool consistent_{false};
284 
285  /** \brief Set this to true if the output triangle vertices should be consistently oriented. */
286  bool consistent_ordering_{false};
287 
288  private:
289  /** \brief Struct for storing the angles to nearest neighbors **/
290  struct nnAngle
291  {
292  double angle;
293  pcl::index_t index;
294  pcl::index_t nnIndex;
295  bool visible;
296  };
297 
298  /** \brief Struct for storing the edges starting from a fringe point **/
299  struct doubleEdge
300  {
301  doubleEdge () = default;
302  int index{0};
303  Eigen::Vector2f first;
304  Eigen::Vector2f second;
305  };
306 
307  // Variables made global to decrease the number of parameters to helper functions
308 
309  /** \brief Temporary variable to store a triangle (as a set of point indices) **/
310  pcl::Vertices triangle_{};
311  /** \brief Temporary variable to store point coordinates **/
312  std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > coords_{};
313 
314  /** \brief A list of angles to neighbors **/
315  std::vector<nnAngle> angles_{};
316  /** \brief Index of the current query point **/
317  pcl::index_t R_{};
318  /** \brief List of point states **/
319  std::vector<int> state_{};
320  /** \brief List of sources **/
321  pcl::Indices source_{};
322  /** \brief List of fringe neighbors in one direction **/
323  pcl::Indices ffn_{};
324  /** \brief List of fringe neighbors in other direction **/
325  pcl::Indices sfn_{};
326  /** \brief Connected component labels for each point **/
327  std::vector<int> part_{};
328  /** \brief Points on the outer edge from which the mesh has to be grown **/
329  std::vector<int> fringe_queue_{};
330 
331  /** \brief Flag to set if the current point is free **/
332  bool is_current_free_{false};
333  /** \brief Current point's index **/
334  pcl::index_t current_index_{};
335  /** \brief Flag to set if the previous point is the first fringe neighbor **/
336  bool prev_is_ffn_{false};
337  /** \brief Flag to set if the next point is the second fringe neighbor **/
338  bool prev_is_sfn_{false};
339  /** \brief Flag to set if the next point is the first fringe neighbor **/
340  bool next_is_ffn_{false};
341  /** \brief Flag to set if the next point is the second fringe neighbor **/
342  bool next_is_sfn_{false};
343  /** \brief Flag to set if the first fringe neighbor was changed **/
344  bool changed_1st_fn_{false};
345  /** \brief Flag to set if the second fringe neighbor was changed **/
346  bool changed_2nd_fn_{false};
347  /** \brief New boundary point **/
348  pcl::index_t new2boundary_{};
349 
350  /** \brief Flag to set if the next neighbor was already connected in the previous step.
351  * To avoid inconsistency it should not be connected again.
352  */
353  bool already_connected_{false};
354 
355  /** \brief Point coordinates projected onto the plane defined by the point normal **/
356  Eigen::Vector3f proj_qp_;
357  /** \brief First coordinate vector of the 2D coordinate frame **/
358  Eigen::Vector3f u_;
359  /** \brief Second coordinate vector of the 2D coordinate frame **/
360  Eigen::Vector3f v_;
361  /** \brief 2D coordinates of the first fringe neighbor **/
362  Eigen::Vector2f uvn_ffn_;
363  /** \brief 2D coordinates of the second fringe neighbor **/
364  Eigen::Vector2f uvn_sfn_;
365  /** \brief 2D coordinates of the first fringe neighbor of the next point **/
366  Eigen::Vector2f uvn_next_ffn_;
367  /** \brief 2D coordinates of the second fringe neighbor of the next point **/
368  Eigen::Vector2f uvn_next_sfn_;
369 
370  /** \brief Temporary variable to store 3 coordinates **/
371  Eigen::Vector3f tmp_;
372 
373  /** \brief The actual surface reconstruction method.
374  * \param[out] output the resultant polygonal mesh
375  */
376  void
377  performReconstruction (pcl::PolygonMesh &output) override;
378 
379  /** \brief The actual surface reconstruction method.
380  * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.
381  */
382  void
383  performReconstruction (std::vector<pcl::Vertices> &polygons) override;
384 
385  /** \brief The actual surface reconstruction method.
386  * \param[out] polygons the resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.
387  */
388  bool
389  reconstructPolygons (std::vector<pcl::Vertices> &polygons);
390 
391  /** \brief Class get name method. */
392  std::string
393  getClassName () const override { return ("GreedyProjectionTriangulation"); }
394 
395  /** \brief Forms a new triangle by connecting the current neighbor to the query point
396  * and the previous neighbor
397  * \param[out] polygons the polygon mesh to be updated
398  * \param[in] prev_index index of the previous point
399  * \param[in] next_index index of the next point
400  * \param[in] next_next_index index of the point after the next one
401  * \param[in] uvn_current 2D coordinate of the current point
402  * \param[in] uvn_prev 2D coordinates of the previous point
403  * \param[in] uvn_next 2D coordinates of the next point
404  */
405  void
406  connectPoint (std::vector<pcl::Vertices> &polygons,
407  const pcl::index_t prev_index,
408  const pcl::index_t next_index,
409  const pcl::index_t next_next_index,
410  const Eigen::Vector2f &uvn_current,
411  const Eigen::Vector2f &uvn_prev,
412  const Eigen::Vector2f &uvn_next);
413 
414  /** \brief Whenever a query point is part of a boundary loop containing 3 points, that triangle is created
415  * (called if angle constraints make it possible)
416  * \param[out] polygons the polygon mesh to be updated
417  */
418  void
419  closeTriangle (std::vector<pcl::Vertices> &polygons);
420 
421  /** \brief Get the list of containing triangles for each vertex in a PolygonMesh
422  * \param[in] polygonMesh the input polygon mesh
423  */
424  std::vector<std::vector<std::size_t> >
425  getTriangleList (const pcl::PolygonMesh &input);
426 
427  /** \brief Add a new triangle to the current polygon mesh
428  * \param[in] a index of the first vertex
429  * \param[in] b index of the second vertex
430  * \param[in] c index of the third vertex
431  * \param[out] polygons the polygon mesh to be updated
432  */
433  inline void
434  addTriangle (pcl::index_t a, pcl::index_t b, pcl::index_t c, std::vector<pcl::Vertices> &polygons)
435  {
436  triangle_.vertices.resize (3);
438  {
439  const PointInT p = input_->at (indices_->at (a));
440  const Eigen::Vector3f pv = p.getVector3fMap ();
441  if (p.getNormalVector3fMap ().dot (
442  (pv - input_->at (indices_->at (b)).getVector3fMap ()).cross (
443  pv - input_->at (indices_->at (c)).getVector3fMap ()) ) > 0)
444  {
445  triangle_.vertices[0] = a;
446  triangle_.vertices[1] = b;
447  triangle_.vertices[2] = c;
448  }
449  else
450  {
451  triangle_.vertices[0] = a;
452  triangle_.vertices[1] = c;
453  triangle_.vertices[2] = b;
454  }
455  }
456  else
457  {
458  triangle_.vertices[0] = a;
459  triangle_.vertices[1] = b;
460  triangle_.vertices[2] = c;
461  }
462  polygons.push_back (triangle_);
463  }
464 
465  /** \brief Add a new vertex to the advancing edge front and set its source point
466  * \param[in] v index of the vertex that was connected
467  * \param[in] s index of the source point
468  */
469  inline void
470  addFringePoint (int v, int s)
471  {
472  source_[v] = s;
473  part_[v] = part_[s];
474  fringe_queue_.push_back(v);
475  }
476 
477  /** \brief Function for ascending sort of nnAngle, taking visibility into account
478  * (angles to visible neighbors will be first, to the invisible ones after).
479  * \param[in] a1 the first angle
480  * \param[in] a2 the second angle
481  */
482  static inline bool
483  nnAngleSortAsc (const nnAngle& a1, const nnAngle& a2)
484  {
485  if (a1.visible == a2.visible)
486  return (a1.angle < a2.angle);
487  return a1.visible;
488  }
489  };
490 
491 } // namespace pcl
492 
493 #ifdef PCL_NO_PRECOMPILE
494 #include <pcl/surface/impl/gp3.hpp>
495 #endif
GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points ...
Definition: gp3.h:130
void setSearchRadius(double radius)
Set the sphere radius that is to be used for determining the k-nearest neighbors used for triangulati...
Definition: gp3.h:181
double eps_angle_
Maximum surface angle.
Definition: gp3.h:280
double maximum_angle_
The maximum angle for the triangles.
Definition: gp3.h:277
double getMaximumAngle() const
Get the parameter for distance based weighting of neighbors.
Definition: gp3.h:207
int getMaximumNearestNeighbors() const
Get the maximum number of nearest neighbors to be searched for.
Definition: gp3.h:174
void setConsistentVertexOrdering(bool consistent_ordering)
Set the flag to order the resulting triangle vertices consistently (positive direction around normal)...
Definition: gp3.h:236
typename PointCloudIn::ConstPtr PointCloudInConstPtr
Definition: gp3.h:141
bool getNormalConsistency() const
Get the flag for consistently oriented normals.
Definition: gp3.h:229
pcl::Indices getFFN() const
Get the ffn list.
Definition: gp3.h:261
bool consistent_ordering_
Set this to true if the output triangle vertices should be consistently oriented.
Definition: gp3.h:286
GreedyProjectionTriangulation()=default
Empty constructor.
shared_ptr< const GreedyProjectionTriangulation< PointInT > > ConstPtr
Definition: gp3.h:133
bool getConsistentVertexOrdering() const
Get the flag signaling consistently ordered triangle vertices.
Definition: gp3.h:240
int nnn_
The maximum number of nearest neighbors accepted by searching.
Definition: gp3.h:271
double getMaximumSurfaceAngle() const
Get the maximum surface angle.
Definition: gp3.h:219
pcl::Indices getSFN() const
Get the sfn list.
Definition: gp3.h:257
typename PointCloudIn::Ptr PointCloudInPtr
Definition: gp3.h:140
double mu_
The nearest neighbor distance multiplier to obtain the final search radius.
Definition: gp3.h:265
double search_radius_
The nearest neighbors search radius for each point and the maximum edge length.
Definition: gp3.h:268
void setNormalConsistency(bool consistent)
Set the flag if the input normals are oriented consistently.
Definition: gp3.h:225
void setMaximumNearestNeighbors(int nnn)
Set the maximum number of nearest neighbors to be searched for.
Definition: gp3.h:170
bool consistent_
Set this to true if the normals of the input are consistently oriented.
Definition: gp3.h:283
std::vector< int > getPartIDs() const
Get the ID of each point after reconstruction.
Definition: gp3.h:252
double getSearchRadius() const
Get the sphere radius used for determining the k-nearest neighbors.
Definition: gp3.h:185
double getMu() const
Get the nearest neighbor distance multiplier.
Definition: gp3.h:164
double getMinimumAngle() const
Get the parameter for distance based weighting of neighbors.
Definition: gp3.h:196
void setMinimumAngle(double minimum_angle)
Set the minimum angle each triangle should have.
Definition: gp3.h:192
double minimum_angle_
The preferred minimum angle for the triangles.
Definition: gp3.h:274
shared_ptr< GreedyProjectionTriangulation< PointInT > > Ptr
Definition: gp3.h:132
void setMaximumAngle(double maximum_angle)
Set the maximum angle each triangle can have.
Definition: gp3.h:203
void setMu(double mu)
Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point ...
Definition: gp3.h:160
std::vector< int > getPointStates() const
Get the state of each point after reconstruction.
Definition: gp3.h:246
void setMaximumSurfaceAngle(double eps_angle)
Don't consider points for triangulation if their normal deviates more than this value from the query ...
Definition: gp3.h:215
MeshConstruction represents a base surface reconstruction class.
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:147
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition: pcl_base.h:150
shared_ptr< PointCloud< PointInT > > Ptr
Definition: point_cloud.h:414
shared_ptr< const PointCloud< PointInT > > ConstPtr
Definition: point_cloud.h:415
bool isVisible(const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2, const Eigen::Vector2f &R=Eigen::Vector2f::Zero())
Returns if a point X is visible from point R (or the origin) when taking into account the segment bet...
Definition: gp3.h:62
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
Definition: types.h:112
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
#define M_PI
Definition: pcl_macros.h:203
Describes a set of vertices in a polygon mesh, by basically storing an array of indices.
Definition: Vertices.h:15
Indices vertices
Definition: Vertices.h:18