Point Cloud Library (PCL)  1.14.0-dev
grabcut_segmentation.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2012-, Open Perception, 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 #include <deque> // for deque
43 #include <map> // for map
44 #include <pcl/memory.h>
45 #include <pcl/point_cloud.h>
46 #include <pcl/pcl_base.h>
47 #include <pcl/pcl_macros.h>
48 #include <pcl/point_types.h>
49 #include <pcl/search/search.h>
50 
51 namespace pcl
52 {
53  namespace segmentation
54  {
55  namespace grabcut
56  {
57  /** boost implementation of Boykov and Kolmogorov's maxflow algorithm doesn't support
58  * negative flows which makes it inappropriate for this context.
59  * This implementation of Boykov and Kolmogorov's maxflow algorithm by Stephen Gould
60  * <stephen.gould@anu.edu.au> in DARWIN under BSD does the trick however solwer than original
61  * implementation.
62  */
64  {
65  public:
66  using vertex_descriptor = int;
67  using edge_capacity_type = double;
68 
69  /// construct a maxflow/mincut problem with estimated max_nodes
70  BoykovKolmogorov (std::size_t max_nodes = 0);
71  /// destructor
72  virtual ~BoykovKolmogorov () = default;
73  /// get number of nodes in the graph
74  std::size_t
75  numNodes () const { return nodes_.size (); }
76  /// reset all edge capacities to zero (but don't free the graph)
77  void
78  reset ();
79  /// clear the graph and internal datastructures
80  void
81  clear ();
82  /// add nodes to the graph (returns the id of the first node added)
83  int
84  addNodes (std::size_t n = 1);
85  /// add constant flow to graph
86  void
87  addConstant (double c) { flow_value_ += c; }
88  /// add edge from s to nodeId
89  void
90  addSourceEdge (int u, double cap);
91  /// add edge from nodeId to t
92  void
93  addTargetEdge (int u, double cap);
94  /// add edge from u to v and edge from v to u
95  /// (requires cap_uv + cap_vu >= 0)
96  void
97  addEdge (int u, int v, double cap_uv, double cap_vu = 0.0);
98  /// solve the max-flow problem and return the flow
99  double
100  solve ();
101  /// return true if \p u is in the s-set after calling \ref solve.
102  bool
103  inSourceTree (int u) const { return (cut_[u] == SOURCE); }
104  /// return true if \p u is in the t-set after calling \ref solve
105  bool
106  inSinkTree (int u) const { return (cut_[u] == TARGET); }
107  /// returns the residual capacity for an edge (use -1 for terminal (-1,-1) is the current flow
108  double
109  operator() (int u, int v) const;
110 
111  double
112  getSourceEdgeCapacity (int u) const;
113 
114  double
115  getTargetEdgeCapacity (int u) const;
116 
117  protected:
118  /// tree states
119  enum nodestate { FREE = 0x00, SOURCE = 0x01, TARGET = 0x02 };
120  /// capacitated edge
121  using capacitated_edge = std::map<int, double>;
122  /// edge pair
123  using edge_pair = std::pair<capacitated_edge::iterator, capacitated_edge::iterator>;
124  /// pre-augment s-u-t and s-u-v-t paths
125  void
127  /// initialize trees from source and target
128  void
130  /// expand trees until a path is found (or no path (-1, -1))
131  std::pair<int, int>
133  /// augment the path found by expandTrees; return orphaned subtrees
134  void
135  augmentPath (const std::pair<int, int>& path, std::deque<int>& orphans);
136  /// adopt orphaned subtrees
137  void
138  adoptOrphans (std::deque<int>& orphans);
139  /// clear active set
140  void clearActive ();
141  /// \return true if active set is empty
142  inline bool
143  isActiveSetEmpty () const { return (active_head_ == TERMINAL); }
144  /// active if head or previous node is not the terminal
145  inline bool
146  isActive (int u) const { return ((u == active_head_) || (active_list_[u].first != TERMINAL)); }
147  /// mark vertex as active
148  void
149  markActive (int u);
150  /// mark vertex as inactive
151  void
152  markInactive (int u);
153  /// edges leaving the source
154  std::vector<double> source_edges_;
155  /// edges entering the target
156  std::vector<double> target_edges_;
157  /// nodes and their outgoing internal edges
158  std::vector<capacitated_edge> nodes_;
159  /// current flow value (includes constant)
160  double flow_value_{0.0};
161  /// identifies which side of the cut a node falls
162  std::vector<unsigned char> cut_;
163 
164  private:
165  /// parents_ flag for terminal state
166  static const int TERMINAL; // -1
167  /// search tree (also uses cut_)
168  std::vector<std::pair<int, edge_pair> > parents_;
169  /// doubly-linked list (prev, next)
170  std::vector<std::pair<int, int> > active_list_;
171  int active_head_, active_tail_;
172  };
173 
174  /**\brief Structure to save RGB colors into floats */
175  struct Color
176  {
177  Color () : r (0), g (0), b (0) {}
178  Color (float _r, float _g, float _b) : r(_r), g(_g), b(_b) {}
179  Color (const pcl::RGB& color) : r (color.r), g (color.g), b (color.b) {}
180 
181  template<typename PointT>
182  Color (const PointT& p);
183 
184  template<typename PointT>
185  operator PointT () const;
186 
187  float r, g, b;
188  };
189  /// An Image is a point cloud of Color
191  /** \brief Compute squared distance between two colors
192  * \param[in] c1 first color
193  * \param[in] c2 second color
194  * \return the squared distance measure in RGB space
195  */
196  float
197  colorDistance (const Color& c1, const Color& c2);
198  /// User supplied Trimap values
200  /// Grabcut derived hard segmentation values
202  /// Gaussian structure
203  struct Gaussian
204  {
205  Gaussian () = default;
206  /// mean of the gaussian
208  /// covariance matrix of the gaussian
209  Eigen::Matrix3f covariance;
210  /// determinant of the covariance matrix
211  float determinant;
212  /// inverse of the covariance matrix
213  Eigen::Matrix3f inverse;
214  /// weighting of this gaussian in the GMM.
215  float pi;
216  /// highest eigenvalue of covariance matrix
217  float eigenvalue;
218  /// eigenvector corresponding to the highest eigenvector
219  Eigen::Vector3f eigenvector;
220  };
221 
223  {
224  public:
225  /// Initialize GMM with ddesired number of gaussians.
226  GMM () : gaussians_ (0) {}
227  /// Initialize GMM with ddesired number of gaussians.
228  GMM (std::size_t K) : gaussians_ (K) {}
229  /// Destructor
230  ~GMM () = default;
231  /// \return K
232  std::size_t
233  getK () const { return gaussians_.size (); }
234  /// resize gaussians
235  void
236  resize (std::size_t K) { gaussians_.resize (K); }
237  /// \return a reference to the gaussian at a given position
238  Gaussian&
239  operator[] (std::size_t pos) { return (gaussians_[pos]); }
240  /// \return a const reference to the gaussian at a given position
241  const Gaussian&
242  operator[] (std::size_t pos) const { return (gaussians_[pos]); }
243  /// \brief \return the computed probability density of a color in this GMM
244  float
246  /// \brief \return the computed probability density of a color in just one Gaussian
247  float
248  probabilityDensity(std::size_t i, const Color &c);
249 
250  private:
251  /// array of gaussians
252  std::vector<Gaussian> gaussians_;
253  };
254 
255  /** Helper class that fits a single Gaussian to color samples */
257  {
258  public:
259  GaussianFitter (float epsilon = 0.0001f)
260  : epsilon_ (epsilon)
261  {}
262 
263  /// Add a color sample
264  void
265  add (const Color &c);
266  /// Build the gaussian out of all the added color samples
267  void
268  fit (Gaussian& g, std::size_t total_count, bool compute_eigens = false) const;
269  /// \return epsilon
270  float
271  getEpsilon () { return (epsilon_); }
272  /** set epsilon which will be added to the covariance matrix diagonal which avoids singular
273  * covariance matrix
274  * \param[in] epsilon user defined epsilon
275  */
276  void
277  setEpsilon (float epsilon) { epsilon_ = epsilon; }
278 
279  private:
280  /// sum of r,g, and b
281  Eigen::Vector3f sum_{Eigen::Vector3f::Zero ()};
282  /// matrix of products (i.e. r*r, r*g, r*b), some values are duplicated.
283  Eigen::Matrix3f accumulator_{Eigen::Matrix3f::Zero ()};
284  /// count of color samples added to the gaussian
285  std::uint32_t count_{0};
286  /// small value to add to covariance matrix diagonal to avoid singular values
287  float epsilon_;
289  };
290 
291  /** Build the initial GMMs using the Orchard and Bouman color clustering algorithm */
292  PCL_EXPORTS void
293  buildGMMs (const Image &image,
294  const Indices& indices,
295  const std::vector<SegmentationValue> &hardSegmentation,
296  std::vector<std::size_t> &components,
297  GMM &background_GMM, GMM &foreground_GMM);
298  /** Iteratively learn GMMs using GrabCut updating algorithm */
299  PCL_EXPORTS void
300  learnGMMs (const Image& image,
301  const Indices& indices,
302  const std::vector<SegmentationValue>& hard_segmentation,
303  std::vector<std::size_t>& components,
304  GMM& background_GMM, GMM& foreground_GMM);
305  }
306  };
307 
308  /** \brief Implementation of the GrabCut segmentation in
309  * "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by
310  * Carsten Rother, Vladimir Kolmogorov and Andrew Blake.
311  *
312  * \author Justin Talbot, jtalbot@stanford.edu placed in Public Domain, 2010
313  * \author Nizar Sallem port to PCL and adaptation of original code.
314  * \ingroup segmentation
315  */
316  template <typename PointT>
317  class GrabCut : public pcl::PCLBase<PointT>
318  {
319  public:
321  using KdTreePtr = typename KdTree::Ptr;
327 
328  /// Constructor
329  GrabCut(std::uint32_t K = 5, float lambda = 50.f) : K_(K), lambda_(lambda) {}
330 
331  /// Destructor
332  ~GrabCut () override = default;
333  // /// Set input cloud
334  void
335  setInputCloud (const PointCloudConstPtr& cloud) override;
336  /// Set background points, foreground points = points \ background points
337  void
338  setBackgroundPoints (const PointCloudConstPtr& background_points);
339  /// Set background indices, foreground indices = indices \ background indices
340  void
341  setBackgroundPointsIndices (int x1, int y1, int x2, int y2);
342  /// Set background indices, foreground indices = indices \ background indices
343  void
345  /// Run Grabcut refinement on the hard segmentation
346  virtual void
347  refine ();
348  /// \return the number of pixels that have changed from foreground to background or vice versa
349  virtual int
350  refineOnce ();
351  /// \return lambda
352  float
353  getLambda () { return (lambda_); }
354  /** Set lambda parameter to user given value. Suggested value by the authors is 50
355  * \param[in] lambda
356  */
357  void
358  setLambda (float lambda) { lambda_ = lambda; }
359  /// \return the number of components in the GMM
360  std::uint32_t
361  getK () { return (K_); }
362  /** Set K parameter to user given value. Suggested value by the authors is 5
363  * \param[in] K the number of components used in GMM
364  */
365  void
366  setK (std::uint32_t K) { K_ = K; }
367  /** \brief Provide a pointer to the search object.
368  * \param tree a pointer to the spatial search object.
369  */
370  inline void
371  setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
372  /** \brief Get a pointer to the search method used. */
373  inline KdTreePtr
374  getSearchMethod () { return (tree_); }
375  /** \brief Allows to set the number of neighbours to find.
376  * \param[in] nb_neighbours new number of neighbours
377  */
378  void
379  setNumberOfNeighbours (int nb_neighbours) { nb_neighbours_ = nb_neighbours; }
380  /** \brief Returns the number of neighbours to find. */
381  int
382  getNumberOfNeighbours () const { return (nb_neighbours_); }
383  /** \brief This method launches the segmentation algorithm and returns the clusters that were
384  * obtained during the segmentation. The indices of points belonging to the object will be stored
385  * in the cluster with index 1, other indices will be stored in the cluster with index 0.
386  * \param[out] clusters clusters that were obtained. Each cluster is an array of point indices.
387  */
388  void
389  extract (std::vector<pcl::PointIndices>& clusters);
390 
391  protected:
392  // Storage for N-link weights, each pixel stores links to nb_neighbours
393  struct NLinks
394  {
395  NLinks () = default;
396 
397  int nb_links{0};
399  std::vector<float> dists{};
400  std::vector<float> weights{};
401  };
402  bool
403  initCompute ();
405  /// Compute beta from image
406  void
408  /// Compute beta from cloud
409  void
411  /// Compute L parameter from given lambda
412  void
413  computeL ();
414  /// Compute NLinks from image
415  void
417  /// Compute NLinks from cloud
418  void
420  /// Edit Trimap
421  void
423  int
425  /// Fit Gaussian Multi Models
426  virtual void
427  fitGMMs ();
428  /// Build the graph for GraphCut
429  void
430  initGraph ();
431  /// Add an edge to the graph, graph must be oriented so we add the edge and its reverse
432  void
433  addEdge (vertex_descriptor v1, vertex_descriptor v2, float capacity, float rev_capacity);
434  /// Set the weights of SOURCE --> v and v --> SINK
435  void
436  setTerminalWeights (vertex_descriptor v, float source_capacity, float sink_capacity);
437  /// \return true if v is in source tree
438  inline bool
440  /// image width
441  std::uint32_t width_{0};
442  /// image height
443  std::uint32_t height_{0};
444  // Variables used in formulas from the paper.
445  /// Number of GMM components
446  std::uint32_t K_;
447  /// lambda = 50. This value was suggested the GrabCut paper.
448  float lambda_;
449  /// beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels.
450  float beta_{0.0f};
451  /// L = a large value to force a pixel to be foreground or background
452  float L_{0.0f};
453  /// Pointer to the spatial search object.
454  KdTreePtr tree_{nullptr};
455  /// Number of neighbours
457  /// is segmentation initialized
458  bool initialized_{false};
459  /// Precomputed N-link weights
460  std::vector<NLinks> n_links_{};
461  /// Converted input
463  std::vector<segmentation::grabcut::TrimapValue> trimap_{};
464  std::vector<std::size_t> GMM_component_{};
465  std::vector<segmentation::grabcut::SegmentationValue> hard_segmentation_{};
466  // Not yet implemented (this would be interpreted as alpha)
467  std::vector<float> soft_segmentation_{};
469  // Graph part
470  /// Graph for Graphcut
472  /// Graph nodes
473  std::vector<vertex_descriptor> graph_nodes_{};
474  };
475 }
476 
477 #include <pcl/segmentation/impl/grabcut_segmentation.hpp>
Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iter...
void computeL()
Compute L parameter from given lambda.
std::uint32_t K_
Number of GMM components.
void setBackgroundPoints(const PointCloudConstPtr &background_points)
Set background points, foreground points = points \ background points.
void addEdge(vertex_descriptor v1, vertex_descriptor v2, float capacity, float rev_capacity)
Add an edge to the graph, graph must be oriented so we add the edge and its reverse.
std::vector< float > soft_segmentation_
void setLambda(float lambda)
Set lambda parameter to user given value.
virtual void fitGMMs()
Fit Gaussian Multi Models.
void computeNLinksNonOrganized()
Compute NLinks from cloud.
typename KdTree::Ptr KdTreePtr
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
virtual void refine()
Run Grabcut refinement on the hard segmentation.
void setTrimap(const PointIndicesConstPtr &indices, segmentation::grabcut::TrimapValue t)
Edit Trimap.
pcl::segmentation::grabcut::BoykovKolmogorov graph_
Graph for Graphcut.
std::vector< std::size_t > GMM_component_
std::uint32_t width_
image width
std::uint32_t height_
image height
void setNumberOfNeighbours(int nb_neighbours)
Allows to set the number of neighbours to find.
pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor vertex_descriptor
void extract(std::vector< pcl::PointIndices > &clusters)
This method launches the segmentation algorithm and returns the clusters that were obtained during th...
void initGraph()
Build the graph for GraphCut.
segmentation::grabcut::GMM background_GMM_
void computeBetaOrganized()
Compute beta from image.
~GrabCut() override=default
Destructor.
float L_
L = a large value to force a pixel to be foreground or background.
float lambda_
lambda = 50. This value was suggested the GrabCut paper.
std::vector< segmentation::grabcut::SegmentationValue > hard_segmentation_
void computeNLinksOrganized()
Compute NLinks from image.
bool isSource(vertex_descriptor v)
std::vector< NLinks > n_links_
Precomputed N-link weights.
void setTerminalWeights(vertex_descriptor v, float source_capacity, float sink_capacity)
Set the weights of SOURCE --> v and v --> SINK.
segmentation::grabcut::GMM foreground_GMM_
virtual int refineOnce()
segmentation::grabcut::Image::Ptr image_
Converted input.
KdTreePtr getSearchMethod()
Get a pointer to the search method used.
KdTreePtr tree_
Pointer to the spatial search object.
float beta_
beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels.
void setBackgroundPointsIndices(int x1, int y1, int x2, int y2)
Set background indices, foreground indices = indices \ background indices.
int nb_neighbours_
Number of neighbours.
std::vector< vertex_descriptor > graph_nodes_
Graph nodes.
void setK(std::uint32_t K)
Set K parameter to user given value.
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset.
void computeBetaNonOrganized()
Compute beta from cloud.
GrabCut(std::uint32_t K=5, float lambda=50.f)
Constructor.
bool initialized_
is segmentation initialized
std::uint32_t getK()
std::vector< segmentation::grabcut::TrimapValue > trimap_
int getNumberOfNeighbours() const
Returns the number of neighbours to find.
PCL base class.
Definition: pcl_base.h:70
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:73
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:74
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_base.h:77
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
Generic search class.
Definition: search.h:75
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:81
boost implementation of Boykov and Kolmogorov's maxflow algorithm doesn't support negative flows whic...
void preAugmentPaths()
pre-augment s-u-t and s-u-v-t paths
bool inSourceTree(int u) const
return true if u is in the s-set after calling solve.
std::vector< unsigned char > cut_
identifies which side of the cut a node falls
std::pair< capacitated_edge::iterator, capacitated_edge::iterator > edge_pair
edge pair
void addSourceEdge(int u, double cap)
add edge from s to nodeId
void addTargetEdge(int u, double cap)
add edge from nodeId to t
std::vector< capacitated_edge > nodes_
nodes and their outgoing internal edges
void markActive(int u)
mark vertex as active
void augmentPath(const std::pair< int, int > &path, std::deque< int > &orphans)
augment the path found by expandTrees; return orphaned subtrees
bool isActive(int u) const
active if head or previous node is not the terminal
void reset()
reset all edge capacities to zero (but don't free the graph)
std::map< int, double > capacitated_edge
capacitated edge
std::vector< double > target_edges_
edges entering the target
void markInactive(int u)
mark vertex as inactive
std::pair< int, int > expandTrees()
expand trees until a path is found (or no path (-1, -1))
bool inSinkTree(int u) const
return true if u is in the t-set after calling solve
std::size_t numNodes() const
get number of nodes in the graph
void clear()
clear the graph and internal datastructures
BoykovKolmogorov(std::size_t max_nodes=0)
construct a maxflow/mincut problem with estimated max_nodes
void adoptOrphans(std::deque< int > &orphans)
adopt orphaned subtrees
double solve()
solve the max-flow problem and return the flow
int addNodes(std::size_t n=1)
add nodes to the graph (returns the id of the first node added)
void addConstant(double c)
add constant flow to graph
void initializeTrees()
initialize trees from source and target
virtual ~BoykovKolmogorov()=default
destructor
void addEdge(int u, int v, double cap_uv, double cap_vu=0.0)
add edge from u to v and edge from v to u (requires cap_uv + cap_vu >= 0)
std::vector< double > source_edges_
edges leaving the source
float probabilityDensity(std::size_t i, const Color &c)
GMM()
Initialize GMM with ddesired number of gaussians.
GMM(std::size_t K)
Initialize GMM with ddesired number of gaussians.
void resize(std::size_t K)
resize gaussians
float probabilityDensity(const Color &c)
~GMM()=default
Destructor.
Helper class that fits a single Gaussian to color samples.
void setEpsilon(float epsilon)
set epsilon which will be added to the covariance matrix diagonal which avoids singular covariance ma...
void add(const Color &c)
Add a color sample.
void fit(Gaussian &g, std::size_t total_count, bool compute_eigens=false) const
Build the gaussian out of all the added color samples.
Defines all the PCL implemented PointT point type structures.
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
@ K
Definition: norms.h:54
Defines functions, macros and traits for allocating and using memory.
TrimapValue
User supplied Trimap values.
float colorDistance(const Color &c1, const Color &c2)
Compute squared distance between two colors.
PCL_EXPORTS void buildGMMs(const Image &image, const Indices &indices, const std::vector< SegmentationValue > &hardSegmentation, std::vector< std::size_t > &components, GMM &background_GMM, GMM &foreground_GMM)
Build the initial GMMs using the Orchard and Bouman color clustering algorithm.
SegmentationValue
Grabcut derived hard segmentation values.
PCL_EXPORTS void learnGMMs(const Image &image, const Indices &indices, const std::vector< SegmentationValue > &hard_segmentation, std::vector< std::size_t > &components, GMM &background_GMM, GMM &foreground_GMM)
Iteratively learn GMMs using GrabCut updating algorithm.
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
Defines all the PCL and non-PCL macros used.
#define PCL_EXPORTS
Definition: pcl_macros.h:323
A point structure representing Euclidean xyz coordinates, and the RGB color.
A structure representing RGB color information.
Structure to save RGB colors into floats.
Color(float _r, float _g, float _b)
float pi
weighting of this gaussian in the GMM.
float determinant
determinant of the covariance matrix
Eigen::Matrix3f covariance
covariance matrix of the gaussian
Eigen::Matrix3f inverse
inverse of the covariance matrix
Eigen::Vector3f eigenvector
eigenvector corresponding to the highest eigenvector
float eigenvalue
highest eigenvalue of covariance matrix