Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::GrabCut< PointT > Class Template Reference

Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by Carsten Rother, Vladimir Kolmogorov and Andrew Blake. More...

#include <grabcut.h>

Inheritance diagram for pcl::GrabCut< PointT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  NLinks

Public Types

typedef pcl::search::Search
< PointT
KdTree
typedef pcl::search::Search
< PointT >::Ptr 
KdTreePtr
typedef PCLBase< PointT >
::PointCloudConstPtr 
PointCloudConstPtr
typedef PCLBase< PointT >
::PointCloudPtr 
PointCloudPtr

Public Member Functions

void extract (std::vector< pcl::PointIndices > &clusters)
 This method launches the segmentation algorithm and returns the clusters that were obtained during the segmentation. The indices of points belonging to the object will be stored in the cluster with index 1, other indices will be stored in the cluster with index 0.
uint32_t getK ()
float getLambda ()
int getNumberOfNeighbours () const
 Returns the number of neighbours to find.
KdTreePtr getSearchMethod ()
 Get a pointer to the search method used.
 GrabCut (uint32_t K=5, float lambda=50.f)
 Constructor.
virtual void refine ()
 Run Grabcut refinement on the hard segmentation.
virtual int refineOnce ()
void setBackgroundPoints (const PointCloudConstPtr &background_points)
 Set background points, foreground points = points \ background points.
void setBackgroundPointsIndices (int x1, int y1, int x2, int y2)
 Set background indices, foreground indices = indices \ background indices.
void setBackgroundPointsIndices (const PointIndicesConstPtr &indices)
 Set background indices, foreground indices = indices \ background indices.
void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
void setK (uint32_t K)
void setLambda (float lambda)
void setNumberOfNeighbours (int nb_neighbours)
 Allows to set the number of neighbours to find.
void setSearchMethod (const KdTreePtr &tree)
 Provide a pointer to the search object.
virtual ~GrabCut ()
 Desctructor.

Protected Types

typedef
pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor 
vertex_descriptor

Protected Member Functions

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.
void computeBeta ()
 Compute beta from image.
void computeL ()
 Compute L parameter from given lambda.
float computeNLink (uint32_t x1, uint32_t y1, uint32_t x2, uint32_t y2)
 Compute NLinks at a specific rectangular location.
void computeNLinks ()
 Compute NLinks.
virtual void fitGMMs ()
 Fit Gaussian Multi Models.
bool initCompute ()
 This method should get called before starting the actual computation.
void initGraph ()
 Build the graph for GraphCut.
bool isSource (vertex_descriptor v)
void setTerminalWeights (vertex_descriptor v, float source_capacity, float sink_capacity)
 Set the weights of SOURCE --> v and v --> SINK.
void setTrimap (const PointIndicesConstPtr &indices, segmentation::grabcut::TrimapValue t)
 Edit Trimap.
int updateHardSegmentation ()

Protected Attributes

segmentation::grabcut::GMM background_GMM_
float beta_
 beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels.
segmentation::grabcut::GMM foreground_GMM_
std::vector< std::size_t > GMM_component_
pcl::segmentation::grabcut::BoykovKolmogorov graph_
 Graph for Graphcut.
std::vector< vertex_descriptorgraph_nodes_
 Graph nodes.
std::vector
< segmentation::grabcut::SegmentationValue
hard_segmentation_
uint32_t height_
 image height
segmentation::grabcut::Image::Ptr image_
 Converted input.
bool initialized_
 is segmentation initialized
uint32_t K_
 Number of GMM components.
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< NLinksn_links_
 Precomputed N-link weights.
int nb_neighbours_
 Number of neighbours.
std::vector< float > soft_segmentation_
KdTreePtr tree_
 Pointer to the spatial search object.
std::vector
< segmentation::grabcut::TrimapValue
trimap_
uint32_t width_
 image width

Detailed Description

template<typename PointT>
class pcl::GrabCut< PointT >

Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by Carsten Rother, Vladimir Kolmogorov and Andrew Blake.

Author:
Justin Talbot, jtalbot@stanford.edu placed in Public Domain, 2010
Nizar Sallem port to PCL and adaptation of original code.

Definition at line 323 of file grabcut.h.


Member Typedef Documentation

template<typename PointT >
typedef pcl::search::Search<PointT> pcl::GrabCut< PointT >::KdTree

Definition at line 326 of file grabcut.h.

template<typename PointT >
typedef pcl::search::Search<PointT>::Ptr pcl::GrabCut< PointT >::KdTreePtr

Definition at line 327 of file grabcut.h.

template<typename PointT >
typedef PCLBase<PointT>::PointCloudConstPtr pcl::GrabCut< PointT >::PointCloudConstPtr

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 328 of file grabcut.h.

template<typename PointT >
typedef PCLBase<PointT>::PointCloudPtr pcl::GrabCut< PointT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 329 of file grabcut.h.

Definition at line 414 of file grabcut.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::GrabCut< PointT >::GrabCut ( uint32_t  K = 5,
float  lambda = 50.f 
) [inline]

Constructor.

Definition at line 335 of file grabcut.h.

template<typename PointT >
virtual pcl::GrabCut< PointT >::~GrabCut ( ) [inline, virtual]

Desctructor.

Definition at line 342 of file grabcut.h.


Member Function Documentation

template<typename PointT >
void pcl::GrabCut< PointT >::addEdge ( vertex_descriptor  v1,
vertex_descriptor  v2,
float  capacity,
float  rev_capacity 
) [protected]

Add an edge to the graph, graph must be oriented so we add the edge and its reverse.

Definition at line 89 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::computeBeta ( ) [protected]

Compute beta from image.

Update hard segmentation after running GraphCut,

Returns:
the number of pixels that have changed from foreground to background or vice versa.

Definition at line 321 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::computeL ( ) [protected]

Compute L parameter from given lambda.

Definition at line 362 of file grabcut.hpp.

template<typename PointT >
float pcl::GrabCut< PointT >::computeNLink ( uint32_t  x1,
uint32_t  y1,
uint32_t  x2,
uint32_t  y2 
) [protected]

Compute NLinks at a specific rectangular location.

template<typename PointT >
void pcl::GrabCut< PointT >::computeNLinks ( ) [protected]

Compute NLinks.

Definition at line 294 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::extract ( std::vector< pcl::PointIndices > &  clusters)

This method launches the segmentation algorithm and returns the clusters that were obtained during the segmentation. The indices of points belonging to the object will be stored in the cluster with index 1, other indices will be stored in the cluster with index 0.

Parameters:
[out]clustersclusters that were obtained. Each cluster is an array of point indices.

Definition at line 368 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::fitGMMs ( ) [protected, virtual]

Fit Gaussian Multi Models.

Definition at line 143 of file grabcut.hpp.

template<typename PointT >
uint32_t pcl::GrabCut< PointT >::getK ( ) [inline]
Returns:
the number of components in the GMM

Definition at line 371 of file grabcut.h.

template<typename PointT >
float pcl::GrabCut< PointT >::getLambda ( ) [inline]
Returns:
lambda

Definition at line 363 of file grabcut.h.

template<typename PointT >
int pcl::GrabCut< PointT >::getNumberOfNeighbours ( ) const [inline]

Returns the number of neighbours to find.

Definition at line 392 of file grabcut.h.

template<typename PointT >
KdTreePtr pcl::GrabCut< PointT >::getSearchMethod ( ) [inline]

Get a pointer to the search method used.

Definition at line 384 of file grabcut.h.

template<typename PointT >
bool pcl::GrabCut< PointT >::initCompute ( ) [protected]

This method should get called before starting the actual computation.

Internally, initCompute() does the following:

  • checks if an input dataset is given, and returns false otherwise
  • checks whether a set of input indices has been given. Returns true if yes.
  • if no input indices have been given, a fake set is created, which will be used until:
    • either a new set is given via setIndices(), or
    • a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 29 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::initGraph ( ) [protected]

Build the graph for GraphCut.

Definition at line 228 of file grabcut.hpp.

template<typename PointT >
bool pcl::GrabCut< PointT >::isSource ( vertex_descriptor  v) [inline, protected]
Returns:
true if v is in source tree

Definition at line 451 of file grabcut.h.

template<typename PointT >
void pcl::GrabCut< PointT >::refine ( ) [virtual]

Run Grabcut refinement on the hard segmentation.

Definition at line 170 of file grabcut.hpp.

template<typename PointT >
int pcl::GrabCut< PointT >::refineOnce ( ) [virtual]
Returns:
the number of pixels that have changed from foreground to background or vice versa

Definition at line 153 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::setBackgroundPoints ( const PointCloudConstPtr background_points)

Set background points, foreground points = points \ background points.

template<typename PointT >
void pcl::GrabCut< PointT >::setBackgroundPointsIndices ( int  x1,
int  y1,
int  x2,
int  y2 
)

Set background indices, foreground indices = indices \ background indices.

template<typename PointT >
void pcl::GrabCut< PointT >::setBackgroundPointsIndices ( const PointIndicesConstPtr indices)

Set background indices, foreground indices = indices \ background indices.

Definition at line 121 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::setInputCloud ( const PointCloudConstPtr cloud) [virtual]

Provide a pointer to the input dataset.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 23 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::setK ( uint32_t  K) [inline]

Set K parameter to user given value. Suggested value by the authors is 5

Parameters:
[in]Kthe number of components used in GMM

Definition at line 376 of file grabcut.h.

template<typename PointT >
void pcl::GrabCut< PointT >::setLambda ( float  lambda) [inline]

Set lambda parameter to user given value. Suggested value by the authors is 50

Parameters:
[in]lambda

Definition at line 368 of file grabcut.h.

template<typename PointT >
void pcl::GrabCut< PointT >::setNumberOfNeighbours ( int  nb_neighbours) [inline]

Allows to set the number of neighbours to find.

Parameters:
[in]number_of_neighboursnew number of neighbours

Definition at line 389 of file grabcut.h.

template<typename PointT >
void pcl::GrabCut< PointT >::setSearchMethod ( const KdTreePtr tree) [inline]

Provide a pointer to the search object.

Parameters:
treea pointer to the spatial search object.

Definition at line 381 of file grabcut.h.

template<typename PointT >
void pcl::GrabCut< PointT >::setTerminalWeights ( vertex_descriptor  v,
float  source_capacity,
float  sink_capacity 
) [protected]

Set the weights of SOURCE --> v and v --> SINK.

Definition at line 95 of file grabcut.hpp.

template<typename PointT >
void pcl::GrabCut< PointT >::setTrimap ( const PointIndicesConstPtr indices,
segmentation::grabcut::TrimapValue  t 
) [protected]

Edit Trimap.

Definition at line 210 of file grabcut.hpp.

template<typename PointT >
int pcl::GrabCut< PointT >::updateHardSegmentation ( ) [protected]

Definition at line 179 of file grabcut.hpp.


Member Data Documentation

template<typename PointT >
segmentation::grabcut::GMM pcl::GrabCut< PointT >::background_GMM_ [protected]

Definition at line 480 of file grabcut.h.

template<typename PointT >
float pcl::GrabCut< PointT >::beta_ [protected]

beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels.

Definition at line 462 of file grabcut.h.

template<typename PointT >
segmentation::grabcut::GMM pcl::GrabCut< PointT >::foreground_GMM_ [protected]

Definition at line 480 of file grabcut.h.

template<typename PointT >
std::vector<std::size_t> pcl::GrabCut< PointT >::GMM_component_ [protected]

Definition at line 476 of file grabcut.h.

template<typename PointT >
pcl::segmentation::grabcut::BoykovKolmogorov pcl::GrabCut< PointT >::graph_ [protected]

Graph for Graphcut.

Definition at line 483 of file grabcut.h.

template<typename PointT >
std::vector<vertex_descriptor> pcl::GrabCut< PointT >::graph_nodes_ [protected]

Graph nodes.

Definition at line 485 of file grabcut.h.

template<typename PointT >
std::vector<segmentation::grabcut::SegmentationValue> pcl::GrabCut< PointT >::hard_segmentation_ [protected]

Definition at line 477 of file grabcut.h.

template<typename PointT >
uint32_t pcl::GrabCut< PointT >::height_ [protected]

image height

Definition at line 455 of file grabcut.h.

template<typename PointT >
segmentation::grabcut::Image::Ptr pcl::GrabCut< PointT >::image_ [protected]

Converted input.

Definition at line 474 of file grabcut.h.

template<typename PointT >
bool pcl::GrabCut< PointT >::initialized_ [protected]

is segmentation initialized

Definition at line 470 of file grabcut.h.

template<typename PointT >
uint32_t pcl::GrabCut< PointT >::K_ [protected]

Number of GMM components.

Definition at line 458 of file grabcut.h.

template<typename PointT >
float pcl::GrabCut< PointT >::L_ [protected]

L = a large value to force a pixel to be foreground or background.

Definition at line 464 of file grabcut.h.

template<typename PointT >
float pcl::GrabCut< PointT >::lambda_ [protected]

lambda = 50. This value was suggested the GrabCut paper.

Definition at line 460 of file grabcut.h.

template<typename PointT >
std::vector<NLinks> pcl::GrabCut< PointT >::n_links_ [protected]

Precomputed N-link weights.

Definition at line 472 of file grabcut.h.

template<typename PointT >
int pcl::GrabCut< PointT >::nb_neighbours_ [protected]

Number of neighbours.

Definition at line 468 of file grabcut.h.

template<typename PointT >
std::vector<float> pcl::GrabCut< PointT >::soft_segmentation_ [protected]

Definition at line 479 of file grabcut.h.

template<typename PointT >
KdTreePtr pcl::GrabCut< PointT >::tree_ [protected]

Pointer to the spatial search object.

Definition at line 466 of file grabcut.h.

template<typename PointT >
std::vector<segmentation::grabcut::TrimapValue> pcl::GrabCut< PointT >::trimap_ [protected]

Definition at line 475 of file grabcut.h.

template<typename PointT >
uint32_t pcl::GrabCut< PointT >::width_ [protected]

image width

Definition at line 453 of file grabcut.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:28