00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <pcl/segmentation/grabcut.h>
00041
00042 #include <cstdlib>
00043 #include <cassert>
00044 #include <vector>
00045 #include <map>
00046 #include <algorithm>
00047
00048 pcl::segmentation::grabcut::BoykovKolmogorov::BoykovKolmogorov (std::size_t max_nodes)
00049 : flow_value_(0.0)
00050 {
00051 if (max_nodes > 0)
00052 {
00053 source_edges_.reserve (max_nodes);
00054 target_edges_.reserve (max_nodes);
00055 nodes_.reserve (max_nodes);
00056 }
00057 }
00058
00059 double
00060 pcl::segmentation::grabcut::BoykovKolmogorov::operator() (int u, int v) const
00061 {
00062 if ((u < 0) && (v < 0)) return flow_value_;
00063 if (u < 0) { return source_edges_[v]; }
00064 if (v < 0) { return target_edges_[u]; }
00065 capacitated_edge::const_iterator it = nodes_[u].find (v);
00066 if (it == nodes_[u].end ()) return 0.0;
00067 return it->second;
00068 }
00069
00070 void
00071 pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths ()
00072 {
00073 for (int u = 0; u < (int)nodes_.size (); u++)
00074 {
00075
00076 if ((source_edges_[u] > 0.0) && (target_edges_[u] > 0.0))
00077 {
00078 const double cap = std::min (source_edges_[u], target_edges_[u]);
00079 flow_value_ += cap;
00080 source_edges_[u] -= cap;
00081 target_edges_[u] -= cap;
00082 }
00083
00084 if (source_edges_[u] == 0.0) continue;
00085
00086
00087 for (std::map<int, double>::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++)
00088 {
00089 const int v = it->first;
00090 if ((it->second == 0.0) || (target_edges_[v] == 0.0)) continue;
00091 const double w = std::min (it->second, std::min (source_edges_[u], target_edges_[v]));
00092 source_edges_[u] -= w;
00093 target_edges_[v] -= w;
00094 it->second -= w;
00095 nodes_[v][u] += w;
00096 flow_value_ += w;
00097 if (source_edges_[u] == 0.0) break;
00098 }
00099 }
00100 }
00101
00102 int
00103 pcl::segmentation::grabcut::BoykovKolmogorov::addNodes (size_t n)
00104 {
00105 int node_id = (int)nodes_.size ();
00106 nodes_.resize (nodes_.size () + n);
00107 source_edges_.resize (nodes_.size (), 0.0);
00108 target_edges_.resize (nodes_.size (), 0.0);
00109 return (node_id);
00110 }
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120 void
00121 pcl::segmentation::grabcut::BoykovKolmogorov::addSourceEdge (int u, double cap)
00122 {
00123 assert ((u >= 0) && (u < (int)nodes_.size ()));
00124 if (cap < 0.0)
00125 {
00126 flow_value_ += cap;
00127 target_edges_[u] -= cap;
00128 }
00129 else
00130 source_edges_[u] += cap;
00131 }
00132
00133 void
00134 pcl::segmentation::grabcut::BoykovKolmogorov::addTargetEdge (int u, double cap)
00135 {
00136 assert ((u >= 0) && (u < (int)nodes_.size ()));
00137 if (cap < 0.0)
00138 {
00139 flow_value_ += cap;
00140 source_edges_[u] -= cap;
00141 }
00142 else
00143 target_edges_[u] += cap;
00144 }
00145
00146 void
00147 pcl::segmentation::grabcut::BoykovKolmogorov::addEdge (int u, int v, double cap_uv, double cap_vu)
00148 {
00149 assert ((u >= 0) && (u < (int)nodes_.size ()));
00150 assert ((v >= 0) && (v < (int)nodes_.size ()));
00151 assert (u != v);
00152
00153 capacitated_edge::iterator it = nodes_[u].find (v);
00154 if (it == nodes_[u].end ())
00155 {
00156 assert (cap_uv + cap_vu >= 0.0);
00157 if (cap_uv < 0.0)
00158 {
00159 nodes_[u].insert (std::make_pair (v, 0.0));
00160 nodes_[v].insert (std::make_pair (u, cap_vu + cap_uv));
00161 source_edges_[u] -= cap_uv;
00162 target_edges_[v] -= cap_uv;
00163 flow_value_ += cap_uv;
00164 }
00165 else
00166 {
00167 if (cap_vu < 0.0)
00168 {
00169 nodes_[u].insert (std::make_pair (v, cap_uv + cap_vu));
00170 nodes_[v].insert (std::make_pair (u, 0.0));
00171 source_edges_[v] -= cap_vu;
00172 target_edges_[u] -= cap_vu;
00173 flow_value_ += cap_vu;
00174 }
00175 else
00176 {
00177 nodes_[u].insert (std::make_pair (v, cap_uv));
00178 nodes_[v].insert (std::make_pair (u, cap_vu));
00179 }
00180 }
00181 }
00182 else
00183 {
00184 capacitated_edge::iterator jt = nodes_[v].find (u);
00185 it->second += cap_uv;
00186 jt->second += cap_vu;
00187 assert (it->second + jt->second >= 0.0);
00188 if (it->second < 0.0)
00189 {
00190 jt->second += it->second;
00191 source_edges_[u] -= it->second;
00192 target_edges_[v] -= it->second;
00193 flow_value_ += it->second;
00194 it->second = 0.0;
00195 }
00196 else
00197 {
00198 if (jt->second < 0.0)
00199 {
00200 it->second += jt->second;
00201 source_edges_[v] -= jt->second;
00202 target_edges_[u] -= jt->second;
00203 flow_value_ += jt->second;
00204 jt->second = 0.0;
00205 }
00206 }
00207 }
00208 }
00209
00210 void
00211 pcl::segmentation::grabcut::BoykovKolmogorov::reset ()
00212 {
00213 flow_value_ = 0.0;
00214 std::fill (source_edges_.begin (), source_edges_.end (), 0.0);
00215 std::fill (target_edges_.begin (), target_edges_.end (), 0.0);
00216 for (int u = 0; u < (int)nodes_.size (); u++)
00217 {
00218 for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++)
00219 {
00220 it->second = 0.0;
00221 }
00222 }
00223 std::fill (cut_.begin (), cut_.end (), FREE);
00224 parents_.clear ();
00225 clearActive ();
00226 }
00227
00228 void
00229 pcl::segmentation::grabcut::BoykovKolmogorov::clear ()
00230 {
00231 flow_value_ = 0.0;
00232 source_edges_.clear ();
00233 target_edges_.clear ();
00234 nodes_.clear ();
00235 cut_.clear ();
00236 parents_.clear ();
00237 clearActive ();
00238 }
00239
00240 double
00241 pcl::segmentation::grabcut::BoykovKolmogorov::solve ()
00242 {
00243
00244 cut_.resize (nodes_.size ());
00245 std::fill (cut_.begin (), cut_.end (), FREE);
00246 parents_.resize (nodes_.size ());
00247
00248 clearActive ();
00249
00250
00251 preAugmentPaths ();
00252
00253
00254 initializeTrees ();
00255
00256 std::deque<int> orphans;
00257 while (!isActiveSetEmpty ())
00258 {
00259 const std::pair<int, int> path = expandTrees ();
00260 augmentPath (path, orphans);
00261 if (!orphans.empty ())
00262 {
00263 adoptOrphans (orphans);
00264 }
00265 }
00266 return (flow_value_);
00267 }
00268
00269 void
00270 pcl::segmentation::grabcut::BoykovKolmogorov::initializeTrees ()
00271 {
00272
00273 for (int u = 0; u < (int)nodes_.size (); u++)
00274 {
00275 if (source_edges_[u] > 0.0)
00276 {
00277 cut_[u] = SOURCE;
00278 parents_[u].first = TERMINAL;
00279 markActive (u);
00280 }
00281 else
00282 {
00283 if (target_edges_[u] > 0.0)
00284 {
00285 cut_[u] = TARGET;
00286 parents_[u].first = TERMINAL;
00287 markActive (u);
00288 }
00289 }
00290 }
00291 }
00292
00293 std::pair<int, int>
00294 pcl::segmentation::grabcut::BoykovKolmogorov::expandTrees ()
00295 {
00296
00297 while (!isActiveSetEmpty ())
00298 {
00299 const int u = active_head_;
00300
00301 if (cut_[u] == SOURCE) {
00302 for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++)
00303 {
00304 if (it->second > 0.0)
00305 {
00306 if (cut_[it->first] == FREE)
00307 {
00308 cut_[it->first] = SOURCE;
00309 parents_[it->first] = std::make_pair (u, std::make_pair (it, nodes_[it->first].find (u)));
00310 markActive (it->first);
00311 }
00312 else
00313 {
00314 if (cut_[it->first] == TARGET)
00315 {
00316
00317 return (std::make_pair (u, it->first));
00318 }
00319 }
00320 }
00321 }
00322 }
00323 else
00324 {
00325 for (capacitated_edge::iterator it = nodes_[u].begin (); it != nodes_[u].end (); it++)
00326 {
00327 if (cut_[it->first] == TARGET) continue;
00328 if (nodes_[it->first][u] > 0.0)
00329 {
00330 if (cut_[it->first] == FREE)
00331 {
00332 cut_[it->first] = TARGET;
00333 parents_[it->first] = std::make_pair (u, std::make_pair (nodes_[it->first].find (u), it));
00334 markActive (it->first);
00335 }
00336 else
00337 {
00338 if (cut_[it->first] == SOURCE)
00339 {
00340
00341 return (std::make_pair (it->first, u));
00342 }
00343 }
00344 }
00345 }
00346 }
00347
00348
00349 markInactive (u);
00350 }
00351
00352 return (std::make_pair (TERMINAL, TERMINAL));
00353 }
00354
00355 void
00356 pcl::segmentation::grabcut::BoykovKolmogorov::augmentPath (const std::pair<int, int>& path, std::deque<int>& orphans)
00357 {
00358 if ((path.first == TERMINAL) && (path.second == TERMINAL))
00359 return;
00360
00361
00362
00363
00364 const edge_pair e = std::make_pair (nodes_[path.first].find (path.second),
00365 nodes_[path.second].find (path.first));
00366 double c = e.first->second;
00367 int u = path.first;
00368 while (parents_[u].first != TERMINAL)
00369 {
00370 c = std::min (c, parents_[u].second.first->second);
00371 u = parents_[u].first;
00372
00373 }
00374 c = std::min (c, source_edges_[u]);
00375
00376
00377 u = path.second;
00378 while (parents_[u].first != TERMINAL)
00379 {
00380 c = std::min (c, parents_[u].second.first->second);
00381 u = parents_[u].first;
00382
00383 }
00384 c = std::min (c, target_edges_[u]);
00385
00386
00387 flow_value_ += c;
00388
00389
00390
00391 u = path.first;
00392 while (parents_[u].first != TERMINAL)
00393 {
00394
00395 parents_[u].second.second->second += c;
00396 parents_[u].second.first->second -= c;
00397 if (parents_[u].second.first->second == 0.0)
00398 {
00399 orphans.push_front (u);
00400 }
00401 u = parents_[u].first;
00402 }
00403 source_edges_[u] -= c;
00404 if (source_edges_[u] == 0.0)
00405 {
00406 orphans.push_front (u);
00407 }
00408
00409
00410 e.first->second -= c;
00411 e.second->second += c;
00412
00413
00414 u = path.second;
00415 while (parents_[u].first != TERMINAL) {
00416
00417 parents_[u].second.second->second += c;
00418 parents_[u].second.first->second -= c;
00419 if (parents_[u].second.first->second == 0.0) {
00420 orphans.push_back (u);
00421 }
00422 u = parents_[u].first;
00423 }
00424 target_edges_[u] -= c;
00425 if (target_edges_[u] == 0.0) {
00426 orphans.push_back (u);
00427 }
00428 }
00429
00430 void
00431 pcl::segmentation::grabcut::BoykovKolmogorov::adoptOrphans (std::deque<int>& orphans)
00432 {
00433
00434 while (!orphans.empty ())
00435 {
00436 const int u = orphans.front ();
00437 const char tree_label = cut_[u];
00438 orphans.pop_front ();
00439
00440
00441 if (tree_label == FREE) continue;
00442
00443
00444
00445 bool b_free_orphan = true;
00446 for (capacitated_edge::iterator jt = nodes_[u].begin (); jt != nodes_[u].end (); ++jt) {
00447
00448 if (cut_[jt->first] != tree_label) continue;
00449
00450
00451 const capacitated_edge::iterator kt = nodes_[jt->first].find (u);
00452 if (((tree_label == TARGET) && (jt->second <= 0.0)) ||
00453 ((tree_label == SOURCE) && (kt->second <= 0.0)))
00454 continue;
00455
00456
00457 int v = jt->first;
00458 while ((v != u) && (v != TERMINAL))
00459 {
00460 v = parents_[v].first;
00461 }
00462 if (v != TERMINAL) continue;
00463
00464
00465 const edge_pair e = (tree_label == SOURCE) ? std::make_pair (kt, jt) : std::make_pair (jt, kt);
00466 parents_[u] = std::make_pair (jt->first, e);
00467 b_free_orphan = false;
00468 break;
00469 }
00470
00471
00472 if (b_free_orphan)
00473 {
00474 for (capacitated_edge::const_iterator jt = nodes_[u].begin (); jt != nodes_[u].end (); ++jt)
00475 {
00476 if ((cut_[jt->first] == tree_label) && (parents_[jt->first].first == u))
00477 {
00478 orphans.push_front (jt->first);
00479 markActive (jt->first);
00480 }
00481 else if (cut_[jt->first] != FREE)
00482 {
00483 markActive (jt->first);
00484 }
00485 }
00486
00487
00488 markInactive (u);
00489 cut_[u] = FREE;
00490 }
00491 }
00492 }
00493
00494 void
00495 pcl::segmentation::grabcut::BoykovKolmogorov::clearActive ()
00496 {
00497 active_head_ = active_tail_ = TERMINAL;
00498 active_list_.resize (nodes_.size ());
00499 std::fill (active_list_.begin (), active_list_.end (), std::make_pair (TERMINAL, TERMINAL));
00500 }
00501
00502 void
00503 pcl::segmentation::grabcut::BoykovKolmogorov::markActive (int u)
00504 {
00505 if (isActive (u)) return;
00506
00507 active_list_[u].first = active_tail_;
00508 active_list_[u].second = TERMINAL;
00509 if (active_tail_ == TERMINAL)
00510 active_head_ = u;
00511 else
00512 active_list_[active_tail_].second = u;
00513 active_tail_ = u;
00514 }
00515
00516 void
00517 pcl::segmentation::grabcut::BoykovKolmogorov::markInactive (int u)
00518 {
00519
00520
00521 if (u == active_head_)
00522 {
00523 active_head_ = active_list_[u].second;
00524 if (u != active_tail_)
00525 {
00526 active_list_[active_list_[u].second].first = TERMINAL;
00527 }
00528 }
00529 else
00530 if (u == active_tail_)
00531 {
00532 active_tail_ = active_list_[u].first;
00533 active_list_[active_list_[u].first].second = TERMINAL;
00534 }
00535 else
00536 if (active_list_[u].first != TERMINAL)
00537 {
00538 active_list_[active_list_[u].first].second = active_list_[u].second;
00539 active_list_[active_list_[u].second].first = active_list_[u].first;
00540 }
00541
00542 active_list_[u].first = TERMINAL;
00543 }
00544
00545 void
00546 pcl::segmentation::grabcut::GaussianFitter::add (const Color &c)
00547 {
00548 sum_[0] += c.r; sum_[1] += c.g; sum_[2] += c.b;
00549 accumulator_ (0,0) += c.r*c.r; accumulator_ (0,1) += c.r*c.g; accumulator_ (0,2) += c.r*c.b;
00550 accumulator_ (1,0) += c.g*c.r; accumulator_ (1,1) += c.g*c.g; accumulator_ (1,2) += c.g*c.b;
00551 accumulator_ (2,0) += c.b*c.r; accumulator_ (2,1) += c.b*c.g; accumulator_ (2,2) += c.b*c.b;
00552
00553 ++count_;
00554 }
00555
00556
00557 void
00558 pcl::segmentation::grabcut::GaussianFitter::fit (Gaussian& g, std::size_t total_count, bool compute_eigens) const
00559 {
00560 if (count_==0)
00561 {
00562 g.pi = 0;
00563 }
00564 else
00565 {
00566 const float count_f = static_cast<float> (count_);
00567
00568
00569 g.mu.r = sum_[0]/count_f;
00570 g.mu.g = sum_[1]/count_f;
00571 g.mu.b = sum_[2]/count_f;
00572
00573
00574 g.covariance (0,0) = accumulator_ (0,0)/count_f - g.mu.r*g.mu.r + epsilon_;
00575 g.covariance (0,1) = accumulator_ (0,1)/count_f - g.mu.r*g.mu.g;
00576 g.covariance (0,2) = accumulator_ (0,2)/count_f - g.mu.r*g.mu.b;
00577 g.covariance (1,0) = accumulator_ (1,0)/count_f - g.mu.g*g.mu.r;
00578 g.covariance (1,1) = accumulator_ (1,1)/count_f - g.mu.g*g.mu.g + epsilon_;
00579 g.covariance (1,2) = accumulator_ (1,2)/count_f - g.mu.g*g.mu.b;
00580 g.covariance (2,0) = accumulator_ (2,0)/count_f - g.mu.b*g.mu.r;
00581 g.covariance (2,1) = accumulator_ (2,1)/count_f - g.mu.b*g.mu.g;
00582 g.covariance (2,2) = accumulator_ (2,2)/count_f - g.mu.b*g.mu.b + epsilon_;
00583
00584
00585 g.determinant = g.covariance (0,0)*(g.covariance (1,1)*g.covariance (2,2) - g.covariance (1,2)*g.covariance (2,1))
00586 - g.covariance (0,1)*(g.covariance (1,0)*g.covariance (2,2) - g.covariance (1,2)*g.covariance (2,0))
00587 + g.covariance (0,2)*(g.covariance (1,0)*g.covariance (2,1) - g.covariance (1,1)*g.covariance (2,0));
00588
00589
00590 g.inverse (0,0) = (g.covariance (1,1)*g.covariance (2,2) - g.covariance (1,2)*g.covariance (2,1)) / g.determinant;
00591 g.inverse (1,0) = -(g.covariance (1,0)*g.covariance (2,2) - g.covariance (1,2)*g.covariance (2,0)) / g.determinant;
00592 g.inverse (2,0) = (g.covariance (1,0)*g.covariance (2,1) - g.covariance (1,1)*g.covariance (2,0)) / g.determinant;
00593 g.inverse (0,1) = -(g.covariance (0,1)*g.covariance (2,2) - g.covariance (0,2)*g.covariance (2,1)) / g.determinant;
00594 g.inverse (1,1) = (g.covariance (0,0)*g.covariance (2,2) - g.covariance (0,2)*g.covariance (2,0)) / g.determinant;
00595 g.inverse (2,1) = -(g.covariance (0,0)*g.covariance (2,1) - g.covariance (0,1)*g.covariance (2,0)) / g.determinant;
00596 g.inverse (0,2) = (g.covariance (0,1)*g.covariance (1,2) - g.covariance (0,2)*g.covariance (1,1)) / g.determinant;
00597 g.inverse (1,2) = -(g.covariance (0,0)*g.covariance (1,2) - g.covariance (0,2)*g.covariance (1,0)) / g.determinant;
00598 g.inverse (2,2) = (g.covariance (0,0)*g.covariance (1,1) - g.covariance (0,1)*g.covariance (1,0)) / g.determinant;
00599
00600
00601
00602 g.pi = count_f / static_cast<float> (total_count);
00603
00604 if (compute_eigens)
00605 {
00606
00607 Eigen::JacobiSVD<Eigen::Matrix3f> svd (g.covariance, Eigen::ComputeFullU);
00608
00609 g.eigenvalue = svd.singularValues ()[0];
00610
00611 g.eigenvector = svd.matrixU ().col (0);
00612 }
00613 }
00614 }
00615
00616 float
00617 pcl::segmentation::grabcut::GMM::probabilityDensity (const Color &c)
00618 {
00619 float result = 0;
00620
00621 for (std::size_t i=0; i < gaussians_.size (); ++i)
00622 result += gaussians_[i].pi * probabilityDensity (i, c);
00623
00624 return (result);
00625 }
00626
00627 float
00628 pcl::segmentation::grabcut::GMM::probabilityDensity (std::size_t i, const Color &c)
00629 {
00630 float result = 0;
00631 const pcl::segmentation::grabcut::Gaussian &G = gaussians_[i];
00632 if (G.pi > 0 )
00633 {
00634 if (G.determinant > 0)
00635 {
00636 float r = c.r - G.mu.r;
00637 float g = c.g - G.mu.g;
00638 float b = c.b - G.mu.b;
00639
00640 float d = r * (r*G.inverse (0,0) + g*G.inverse (1,0) + b*G.inverse (2,0)) +
00641 g * (r*G.inverse (0,1) + g*G.inverse (1,1) + b*G.inverse (2,1)) +
00642 b * (r*G.inverse (0,2) + g*G.inverse (1,2) + b*G.inverse (2,2));
00643
00644 result = static_cast<float> (1.0/(sqrt (G.determinant)) * exp (-0.5*d));
00645 }
00646 }
00647
00648 return (result);
00649 }
00650
00651 void
00652 pcl::segmentation::grabcut::buildGMMs (const Image& image,
00653 const std::vector<int>& indices,
00654 const std::vector<SegmentationValue>& hard_segmentation,
00655 std::vector<std::size_t>& components,
00656 GMM& background_GMM, GMM& foreground_GMM)
00657 {
00658
00659
00660
00661 std::vector<GaussianFitter> back_fitters (background_GMM.getK ());
00662 std::vector<GaussianFitter> fore_fitters (foreground_GMM.getK ());
00663
00664 std::size_t fore_count = 0, back_count = 0;
00665 const int indices_size = static_cast<int> (indices.size ());
00666
00667 for (int idx = 0; idx < indices_size; ++idx)
00668 {
00669 components [idx] = 0;
00670
00671 if (hard_segmentation [idx] == SegmentationForeground)
00672 {
00673 fore_fitters[0].add (image[indices[idx]]);
00674 fore_count++;
00675 }
00676 else
00677 {
00678 back_fitters[0].add (image[indices[idx]]);
00679 back_count++;
00680 }
00681 }
00682
00683 back_fitters[0].fit (background_GMM[0], back_count, true);
00684 fore_fitters[0].fit (foreground_GMM[0], fore_count, true);
00685
00686 std::size_t n_back = 0, n_fore = 0;
00687 std::size_t max_K = (background_GMM.getK () > foreground_GMM.getK ()) ? background_GMM.getK () : foreground_GMM.getK ();
00688
00689
00690 for (std::size_t i = 1; i < max_K; ++i)
00691 {
00692
00693 back_fitters[n_back] = GaussianFitter ();
00694 fore_fitters[n_fore] = GaussianFitter ();
00695
00696
00697 Gaussian& bg = background_GMM[n_back];
00698 Gaussian& fg = foreground_GMM[n_fore];
00699
00700
00701 float split_background = bg.eigenvector[0] * bg.mu.r + bg.eigenvector[1] * bg.mu.g + bg.eigenvector[2] * bg.mu.b;
00702 float split_foreground = fg.eigenvector[0] * fg.mu.r + fg.eigenvector[1] * fg.mu.g + fg.eigenvector[2] * fg.mu.b;
00703
00704
00705 for (int idx = 0; idx < indices_size; ++idx)
00706 {
00707 const Color &c = image[indices[idx]];
00708
00709
00710 if (i < foreground_GMM.getK () &&
00711 hard_segmentation[idx] == SegmentationForeground &&
00712 components[idx] == n_fore)
00713 {
00714 if (fg.eigenvector[0] * c.r + fg.eigenvector[1] * c.g + fg.eigenvector[2] * c.b > split_foreground)
00715 {
00716 components[idx] = i;
00717 fore_fitters[i].add (c);
00718 }
00719 else
00720 {
00721 fore_fitters[n_fore].add (c);
00722 }
00723 }
00724 else if (i < background_GMM.getK () &&
00725 hard_segmentation[idx] == SegmentationBackground &&
00726 components[idx] == n_back)
00727 {
00728 if (bg.eigenvector[0] * c.r + bg.eigenvector[1] * c.g + bg.eigenvector[2] * c.b > split_background)
00729 {
00730 components[idx] = i;
00731 back_fitters[i].add (c);
00732 }
00733 else
00734 {
00735 back_fitters[n_back].add (c);
00736 }
00737 }
00738 }
00739
00740
00741 back_fitters[n_back].fit (background_GMM[n_back], back_count, true);
00742 fore_fitters[n_fore].fit (foreground_GMM[n_fore], fore_count, true);
00743
00744 if (i < background_GMM.getK ())
00745 back_fitters[i].fit (background_GMM[i], back_count, true);
00746 if (i < foreground_GMM.getK ())
00747 fore_fitters[i].fit (foreground_GMM[i], fore_count, true);
00748
00749
00750 n_back = 0;
00751 n_fore = 0;
00752
00753 for (std::size_t j = 0; j <= i; ++j)
00754 {
00755 if (j < background_GMM.getK () && background_GMM[j].eigenvalue > background_GMM[n_back].eigenvalue)
00756 n_back = j;
00757
00758 if (j < foreground_GMM.getK () && foreground_GMM[j].eigenvalue > foreground_GMM[n_fore].eigenvalue)
00759 n_fore = j;
00760 }
00761 }
00762
00763 back_fitters.clear ();
00764 fore_fitters.clear ();
00765 }
00766
00767 void
00768 pcl::segmentation::grabcut::learnGMMs (const Image& image,
00769 const std::vector<int>& indices,
00770 const std::vector<SegmentationValue>& hard_segmentation,
00771 std::vector<std::size_t>& components,
00772 GMM& background_GMM, GMM& foreground_GMM)
00773 {
00774 const std::size_t indices_size = static_cast<std::size_t> (indices.size ());
00775
00776 for (std::size_t idx = 0; idx < indices_size; ++idx)
00777 {
00778 const Color &c = image[indices[idx]];
00779
00780 if (hard_segmentation[idx] == SegmentationForeground)
00781 {
00782 std::size_t k = 0;
00783 float max = 0;
00784
00785 for (std::size_t i = 0; i < foreground_GMM.getK (); i++)
00786 {
00787 float p = foreground_GMM.probabilityDensity (i, c);
00788 if (p > max)
00789 {
00790 k = i;
00791 max = p;
00792 }
00793 }
00794 components[idx] = k;
00795 }
00796 else
00797 {
00798 std::size_t k = 0;
00799 float max = 0;
00800
00801 for (std::size_t i = 0; i < background_GMM.getK (); i++)
00802 {
00803 float p = background_GMM.probabilityDensity (i, c);
00804 if (p > max)
00805 {
00806 k = i;
00807 max = p;
00808 }
00809 }
00810 components[idx] = k;
00811 }
00812 }
00813
00814
00815
00816
00817 std::vector<GaussianFitter> back_fitters (background_GMM.getK ());
00818 std::vector<GaussianFitter> fore_fitters (foreground_GMM.getK ());
00819
00820 std::size_t fore_counter = 0, back_counter = 0;
00821 for (std::size_t idx = 0; idx < indices_size; ++idx)
00822 {
00823 const Color &c = image [indices [idx]];
00824
00825 if (hard_segmentation[idx] == SegmentationForeground)
00826 {
00827 fore_fitters[components[idx]].add (c);
00828 fore_counter++;
00829 }
00830 else
00831 {
00832 back_fitters[components[idx]].add (c);
00833 back_counter++;
00834 }
00835 }
00836
00837 for (std::size_t i = 0; i < background_GMM.getK (); ++i)
00838 back_fitters[i].fit (background_GMM[i], back_counter, false);
00839
00840 for (std::size_t i = 0; i < foreground_GMM.getK (); ++i)
00841 fore_fitters[i].fit (foreground_GMM[i], fore_counter, false);
00842
00843 back_fitters.clear ();
00844 fore_fitters.clear ();
00845 }