#include <grabcut.h>
Public Types | |
| typedef double | edge_capacity_type |
| typedef int | vertex_descriptor |
Public Member Functions | |
| void | addConstant (double c) |
| add constant flow to graph | |
| void | addEdge (int u, int v, double cap_uv, double cap_vu=0.0) |
| int | addNodes (std::size_t n=1) |
| add nodes to the graph (returns the id of the first node added) | |
| void | addSourceEdge (int u, double cap) |
| add edge from s to nodeId | |
| void | addTargetEdge (int u, double cap) |
| add edge from nodeId to t | |
| BoykovKolmogorov (std::size_t max_nodes=0) | |
| construct a maxflow/mincut problem with estimated max_nodes | |
| void | clear () |
| clear the graph and internal datastructures | |
| bool | inSinkTree (int u) const |
return true if u is in the t-set after calling solve | |
| bool | inSourceTree (int u) const |
return true if u is in the s-set after calling solve. | |
| size_t | numNodes () const |
| get number of nodes in the graph | |
| double | operator() (int u, int v) const |
| returns the residual capacity for an edge (use -1 for terminal (-1,-1) is the current flow | |
| void | reset () |
| reset all edge capacities to zero (but don't free the graph) | |
| double | solve () |
| solve the max-flow problem and return the flow | |
| virtual | ~BoykovKolmogorov () |
| destructor | |
Protected Types | |
| typedef std::map< int, double > | capacitated_edge |
| capacitated edge | |
| typedef std::pair < capacitated_edge::iterator, capacitated_edge::iterator > | edge_pair |
| edge pair | |
| enum | nodestate { FREE = 0x00, SOURCE = 0x01, TARGET = 0x02 } |
| tree states More... | |
Protected Member Functions | |
| void | adoptOrphans (std::deque< int > &orphans) |
| adopt orphaned subtrees | |
| void | augmentPath (const std::pair< int, int > &path, std::deque< int > &orphans) |
| augment the path found by expandTrees; return orphaned subtrees | |
| void | clearActive () |
| clear active set | |
| std::pair< int, int > | expandTrees () |
| expand trees until a path is found (or no path (-1, -1)) | |
| void | initializeTrees () |
| initialize trees from source and target | |
| bool | isActive (int u) const |
| active if head or previous node is not the terminal | |
| bool | isActiveSetEmpty () const |
| void | markActive (int u) |
| mark vertex as active | |
| void | markInactive (int u) |
| mark vertex as inactive | |
| void | preAugmentPaths () |
| pre-augment s-u-t and s-u-v-t paths | |
Protected Attributes | |
| std::vector< unsigned char > | cut_ |
| identifies which side of the cut a node falls | |
| double | flow_value_ |
| current flow value (includes constant) | |
| std::vector< capacitated_edge > | nodes_ |
| nodes and their outgoing internal edges | |
| std::vector< double > | source_edges_ |
| edges leaving the source | |
| std::vector< double > | target_edges_ |
| edges entering the target | |
Private Attributes | |
| int | active_head_ |
| std::vector< std::pair< int, int > > | active_list_ |
| doubly-linked list (prev, next) | |
| int | active_tail_ |
| std::vector< std::pair< int, edge_pair > > | parents_ |
| search tree (also uses cut_) | |
Static Private Attributes | |
| static const int | TERMINAL = -1 |
| parents_ flag for terminal state | |
boost implementation of Boykov and Kolmogorov's maxflow algorithm doesn't support negative flows which makes it inappropriate for this conext. This implementation of Boykov and Kolmogorov's maxflow algorithm by Stephen Gould <stephen.gould@anu.edu.au> in DARWIN under BSD does the trick however solwer than original implementation.
typedef std::map<int, double> pcl::segmentation::grabcut::BoykovKolmogorov::capacitated_edge [protected] |
typedef std::pair<capacitated_edge::iterator, capacitated_edge::iterator> pcl::segmentation::grabcut::BoykovKolmogorov::edge_pair [protected] |
enum pcl::segmentation::grabcut::BoykovKolmogorov::nodestate [protected] |
| pcl::segmentation::grabcut::BoykovKolmogorov::BoykovKolmogorov | ( | std::size_t | max_nodes = 0 | ) |
construct a maxflow/mincut problem with estimated max_nodes
Definition at line 48 of file grabcut.cpp.
| virtual pcl::segmentation::grabcut::BoykovKolmogorov::~BoykovKolmogorov | ( | ) | [inline, virtual] |
| void pcl::segmentation::grabcut::BoykovKolmogorov::addConstant | ( | double | c | ) | [inline] |
| void pcl::segmentation::grabcut::BoykovKolmogorov::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)
Definition at line 147 of file grabcut.cpp.
| int pcl::segmentation::grabcut::BoykovKolmogorov::addNodes | ( | std::size_t | n = 1 | ) |
add nodes to the graph (returns the id of the first node added)
Definition at line 103 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::addSourceEdge | ( | int | u, |
| double | cap | ||
| ) |
add edge from s to nodeId
Definition at line 121 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::addTargetEdge | ( | int | u, |
| double | cap | ||
| ) |
add edge from nodeId to t
Definition at line 134 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::adoptOrphans | ( | std::deque< int > & | orphans | ) | [protected] |
adopt orphaned subtrees
Definition at line 431 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::augmentPath | ( | const std::pair< int, int > & | path, |
| std::deque< int > & | orphans | ||
| ) | [protected] |
augment the path found by expandTrees; return orphaned subtrees
Definition at line 356 of file grabcut.cpp.
clear the graph and internal datastructures
Definition at line 229 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::clearActive | ( | ) | [protected] |
clear active set
Definition at line 495 of file grabcut.cpp.
| std::pair< int, int > pcl::segmentation::grabcut::BoykovKolmogorov::expandTrees | ( | ) | [protected] |
expand trees until a path is found (or no path (-1, -1))
Definition at line 294 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::initializeTrees | ( | ) | [protected] |
initialize trees from source and target
Definition at line 270 of file grabcut.cpp.
| bool pcl::segmentation::grabcut::BoykovKolmogorov::inSinkTree | ( | int | u | ) | const [inline] |
| bool pcl::segmentation::grabcut::BoykovKolmogorov::inSourceTree | ( | int | u | ) | const [inline] |
| bool pcl::segmentation::grabcut::BoykovKolmogorov::isActive | ( | int | u | ) | const [inline, protected] |
| bool pcl::segmentation::grabcut::BoykovKolmogorov::isActiveSetEmpty | ( | ) | const [inline, protected] |
| void pcl::segmentation::grabcut::BoykovKolmogorov::markActive | ( | int | u | ) | [protected] |
mark vertex as active
Definition at line 503 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::markInactive | ( | int | u | ) | [protected] |
mark vertex as inactive
Definition at line 517 of file grabcut.cpp.
| size_t pcl::segmentation::grabcut::BoykovKolmogorov::numNodes | ( | ) | const [inline] |
| double pcl::segmentation::grabcut::BoykovKolmogorov::operator() | ( | int | u, |
| int | v | ||
| ) | const |
returns the residual capacity for an edge (use -1 for terminal (-1,-1) is the current flow
Definition at line 60 of file grabcut.cpp.
| void pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths | ( | ) | [protected] |
pre-augment s-u-t and s-u-v-t paths
Definition at line 71 of file grabcut.cpp.
reset all edge capacities to zero (but don't free the graph)
Definition at line 211 of file grabcut.cpp.
solve the max-flow problem and return the flow
Definition at line 241 of file grabcut.cpp.
std::vector<std::pair<int, int> > pcl::segmentation::grabcut::BoykovKolmogorov::active_list_ [private] |
std::vector<unsigned char> pcl::segmentation::grabcut::BoykovKolmogorov::cut_ [protected] |
double pcl::segmentation::grabcut::BoykovKolmogorov::flow_value_ [protected] |
std::vector<capacitated_edge> pcl::segmentation::grabcut::BoykovKolmogorov::nodes_ [protected] |
std::vector<std::pair<int, edge_pair> > pcl::segmentation::grabcut::BoykovKolmogorov::parents_ [private] |
std::vector<double> pcl::segmentation::grabcut::BoykovKolmogorov::source_edges_ [protected] |
std::vector<double> pcl::segmentation::grabcut::BoykovKolmogorov::target_edges_ [protected] |
const int pcl::segmentation::grabcut::BoykovKolmogorov::TERMINAL = -1 [static, private] |