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>
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_descriptor > | graph_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< NLinks > | n_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 |
Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by Carsten Rother, Vladimir Kolmogorov and Andrew Blake.
typedef pcl::search::Search<PointT> pcl::GrabCut< PointT >::KdTree |
typedef pcl::search::Search<PointT>::Ptr pcl::GrabCut< PointT >::KdTreePtr |
typedef PCLBase<PointT>::PointCloudConstPtr pcl::GrabCut< PointT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef PCLBase<PointT>::PointCloudPtr pcl::GrabCut< PointT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
typedef pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor pcl::GrabCut< PointT >::vertex_descriptor [protected] |
pcl::GrabCut< PointT >::GrabCut | ( | uint32_t | K = 5 , |
float | lambda = 50.f |
||
) | [inline] |
virtual pcl::GrabCut< PointT >::~GrabCut | ( | ) | [inline, virtual] |
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.
void pcl::GrabCut< PointT >::computeBeta | ( | ) | [protected] |
Compute beta from image.
Update hard segmentation after running GraphCut,
Definition at line 321 of file grabcut.hpp.
void pcl::GrabCut< PointT >::computeL | ( | ) | [protected] |
Compute L parameter from given lambda.
Definition at line 362 of file grabcut.hpp.
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.
void pcl::GrabCut< PointT >::computeNLinks | ( | ) | [protected] |
Compute NLinks.
Definition at line 294 of file grabcut.hpp.
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.
[out] | clusters | clusters that were obtained. Each cluster is an array of point indices. |
Definition at line 368 of file grabcut.hpp.
void pcl::GrabCut< PointT >::fitGMMs | ( | ) | [protected, virtual] |
Fit Gaussian Multi Models.
Definition at line 143 of file grabcut.hpp.
uint32_t pcl::GrabCut< PointT >::getK | ( | ) | [inline] |
float pcl::GrabCut< PointT >::getLambda | ( | ) | [inline] |
int pcl::GrabCut< PointT >::getNumberOfNeighbours | ( | ) | const [inline] |
KdTreePtr pcl::GrabCut< PointT >::getSearchMethod | ( | ) | [inline] |
bool pcl::GrabCut< PointT >::initCompute | ( | ) | [protected] |
This method should get called before starting the actual computation.
Internally, initCompute() does the following:
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 29 of file grabcut.hpp.
void pcl::GrabCut< PointT >::initGraph | ( | ) | [protected] |
Build the graph for GraphCut.
Definition at line 228 of file grabcut.hpp.
bool pcl::GrabCut< PointT >::isSource | ( | vertex_descriptor | v | ) | [inline, protected] |
void pcl::GrabCut< PointT >::refine | ( | ) | [virtual] |
Run Grabcut refinement on the hard segmentation.
Definition at line 170 of file grabcut.hpp.
int pcl::GrabCut< PointT >::refineOnce | ( | ) | [virtual] |
Definition at line 153 of file grabcut.hpp.
void pcl::GrabCut< PointT >::setBackgroundPoints | ( | const PointCloudConstPtr & | background_points | ) |
Set background points, foreground points = points \ background points.
void pcl::GrabCut< PointT >::setBackgroundPointsIndices | ( | int | x1, |
int | y1, | ||
int | x2, | ||
int | y2 | ||
) |
Set background indices, foreground indices = indices \ background indices.
void pcl::GrabCut< PointT >::setBackgroundPointsIndices | ( | const PointIndicesConstPtr & | indices | ) |
Set background indices, foreground indices = indices \ background indices.
Definition at line 121 of file grabcut.hpp.
void pcl::GrabCut< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [virtual] |
Provide a pointer to the input dataset.
[in] | cloud | the const boost shared pointer to a PointCloud message |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 23 of file grabcut.hpp.
void pcl::GrabCut< PointT >::setK | ( | uint32_t | K | ) | [inline] |
void pcl::GrabCut< PointT >::setLambda | ( | float | lambda | ) | [inline] |
void pcl::GrabCut< PointT >::setNumberOfNeighbours | ( | int | nb_neighbours | ) | [inline] |
void pcl::GrabCut< PointT >::setSearchMethod | ( | const KdTreePtr & | tree | ) | [inline] |
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.
void pcl::GrabCut< PointT >::setTrimap | ( | const PointIndicesConstPtr & | indices, |
segmentation::grabcut::TrimapValue | t | ||
) | [protected] |
Edit Trimap.
Definition at line 210 of file grabcut.hpp.
int pcl::GrabCut< PointT >::updateHardSegmentation | ( | ) | [protected] |
Definition at line 179 of file grabcut.hpp.
segmentation::grabcut::GMM pcl::GrabCut< PointT >::background_GMM_ [protected] |
float pcl::GrabCut< PointT >::beta_ [protected] |
segmentation::grabcut::GMM pcl::GrabCut< PointT >::foreground_GMM_ [protected] |
std::vector<std::size_t> pcl::GrabCut< PointT >::GMM_component_ [protected] |
pcl::segmentation::grabcut::BoykovKolmogorov pcl::GrabCut< PointT >::graph_ [protected] |
std::vector<vertex_descriptor> pcl::GrabCut< PointT >::graph_nodes_ [protected] |
std::vector<segmentation::grabcut::SegmentationValue> pcl::GrabCut< PointT >::hard_segmentation_ [protected] |
uint32_t pcl::GrabCut< PointT >::height_ [protected] |
segmentation::grabcut::Image::Ptr pcl::GrabCut< PointT >::image_ [protected] |
bool pcl::GrabCut< PointT >::initialized_ [protected] |
uint32_t pcl::GrabCut< PointT >::K_ [protected] |
float pcl::GrabCut< PointT >::L_ [protected] |
float pcl::GrabCut< PointT >::lambda_ [protected] |
std::vector<NLinks> pcl::GrabCut< PointT >::n_links_ [protected] |
int pcl::GrabCut< PointT >::nb_neighbours_ [protected] |
std::vector<float> pcl::GrabCut< PointT >::soft_segmentation_ [protected] |
KdTreePtr pcl::GrabCut< PointT >::tree_ [protected] |
std::vector<segmentation::grabcut::TrimapValue> pcl::GrabCut< PointT >::trimap_ [protected] |
uint32_t pcl::GrabCut< PointT >::width_ [protected] |