FindSeparator-inl.h
Go to the documentation of this file.
1 /*
2  * FindSeparator-inl.h
3  *
4  * Created on: Nov 23, 2010
5  * Updated: Feb 20. 2014
6  * Author: nikai
7  * Author: Andrew Melim
8  * Description: find the separator of bisectioning for a given graph
9  */
10 
11 #pragma once
12 
13 #include <stdexcept>
14 #include <iostream>
15 #include <vector>
16 #include <optional>
17 #include <cassert>
18 #include <boost/shared_array.hpp>
19 
20 #include <gtsam/base/timing.h>
21 
22 #include "FindSeparator.h"
23 
24 #include <metis.h>
25 
26 extern "C" {
27 #include <metislib.h>
28 }
29 
30 
31 
32 namespace gtsam { namespace partition {
33 
34  typedef boost::shared_array<idx_t> sharedInts;
35 
36  /* ************************************************************************* */
43  std::pair<idx_t, sharedInts> separatorMetis(idx_t n, const sharedInts& xadj,
44  const sharedInts& adjncy, const sharedInts& adjwgt, bool verbose) {
45 
46  // control parameters
47  std::vector<idx_t> vwgt; // the weights of the vertices
49  METIS_SetDefaultOptions(options); // use defaults
50  idx_t sepsize; // the size of the separator, output
51  sharedInts part_(new idx_t[n]); // the partition of each vertex, output
52 
53  // set uniform weights on the vertices
54  vwgt.assign(n, 1);
55 
56  // TODO: Fix at later time
57  //boost::timer::cpu_timer TOTALTmr;
58  if (verbose) {
59  printf("**********************************************************************\n");
60  printf("Graph Information ---------------------------------------------------\n");
61  printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2);
62  printf("\nND Partitioning... -------------------------------------------\n");
63  //TOTALTmr.start()
64  }
65 
66  // call metis parition routine
68  &vwgt[0], options, &sepsize, part_.get());
69 
70  if (verbose) {
71  //boost::cpu_times const elapsed_times(timer.elapsed());
72  //printf("\nTiming Information --------------------------------------------------\n");
73  //printf(" Total: \t\t %7.3f\n", elapsed_times);
74  printf(" Sep size: \t\t %d\n", sepsize);
75  printf("**********************************************************************\n");
76  }
77 
78  return std::make_pair(sepsize, part_);
79  }
80 
81  /* ************************************************************************* */
84  {
85  idx_t i, ncon;
86  graph_t *graph;
87  real_t *tpwgts2;
88  ctrl_t *ctrl;
89  ctrl = SetupCtrl(METIS_OP_OMETIS, options, 1, 3, nullptr, nullptr);
90  ctrl->iptype = METIS_IPTYPE_GROW;
91  //if () == nullptr)
92  // return METIS_ERROR_INPUT;
93 
94  InitRandom(ctrl->seed);
95 
96  graph = SetupGraph(ctrl, *nvtxs, 1, xadj, adjncy, vwgt, nullptr, nullptr);
97 
98  AllocateWorkSpace(ctrl, graph);
99 
100  ncon = graph->ncon;
101  ctrl->ncuts = 1;
102 
103  /* determine the weights of the two partitions as a function of the weight of the
104  target partition weights */
105 
106  tpwgts2 = rwspacemalloc(ctrl, 2*ncon);
107  for (i=0; i<ncon; i++) {
108  tpwgts2[i] = rsum((2>>1), ctrl->tpwgts+i, ncon);
109  tpwgts2[ncon+i] = 1.0 - tpwgts2[i];
110  }
111  /* perform the bisection */
112  *edgecut = MultilevelBisect(ctrl, graph, tpwgts2);
113 
114  // ConstructMinCoverSeparator(&ctrl, &graph, 1.05);
115  // *edgecut = graph->mincut;
116  // *sepsize = graph.pwgts[2];
117  icopy(*nvtxs, graph->where, part);
118  std::cout << "Finished bisection:" << *edgecut << std::endl;
119  FreeGraph(&graph);
120 
121  FreeCtrl(&ctrl);
122  }
123 
124  /* ************************************************************************* */
130  std::pair<int, sharedInts> edgeMetis(idx_t n, const sharedInts& xadj, const sharedInts& adjncy,
131  const sharedInts& adjwgt, bool verbose) {
132 
133  // control parameters
134  std::vector<idx_t> vwgt; // the weights of the vertices
136  METIS_SetDefaultOptions(options); // use defaults
137  idx_t edgecut; // the number of edge cuts, output
138  sharedInts part_(new idx_t[n]); // the partition of each vertex, output
139 
140  // set uniform weights on the vertices
141  vwgt.assign(n, 1);
142 
143  //TODO: Fix later
144  //boost::timer TOTALTmr;
145  if (verbose) {
146  printf("**********************************************************************\n");
147  printf("Graph Information ---------------------------------------------------\n");
148  printf(" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+n) / 2);
149  printf("\nND Partitioning... -------------------------------------------\n");
150  //cleartimer(TOTALTmr);
151  //starttimer(TOTALTmr);
152  }
153 
154  //int wgtflag = 1; // only edge weights
155  //int numflag = 0; // c style numbering starting from 0
156  //int nparts = 2; // partition the graph to 2 submaps
157  modefied_EdgeComputeSeparator(&n, xadj.get(), adjncy.get(), &vwgt[0], adjwgt.get(),
158  options, &edgecut, part_.get());
159 
160 
161  if (verbose) {
162  //stoptimer(TOTALTmr);
163  printf("\nTiming Information --------------------------------------------------\n");
164  //printf(" Total: \t\t %7.3f\n", gettimer(TOTALTmr));
165  printf(" Edge cuts: \t\t %d\n", edgecut);
166  printf("**********************************************************************\n");
167  }
168 
169  return std::make_pair(edgecut, part_);
170  }
171 
172  /* ************************************************************************* */
178  template <class GenericGraph>
179  void prepareMetisGraph(const GenericGraph& graph, const std::vector<size_t>& keys, WorkSpace& workspace,
180  sharedInts* ptr_xadj, sharedInts* ptr_adjncy, sharedInts* ptr_adjwgt) {
181 
182  typedef std::vector<int> Weights;
183  typedef std::vector<int> Neighbors;
184  typedef std::pair<Neighbors, Weights> NeighborsInfo;
185 
186  // set up dictionary
187  std::vector<int>& dictionary = workspace.dictionary;
188  workspace.prepareDictionary(keys);
189 
190  // prepare for {adjacencyMap}, a pair of neighbor indices and the correponding edge weights
191  int numNodes = keys.size();
192  int numEdges = 0;
193  std::vector<NeighborsInfo> adjacencyMap;
194  adjacencyMap.resize(numNodes);
195  std::cout << "Number of nodes: " << adjacencyMap.size() << std::endl;
196  int index1, index2;
197 
198  for(const typename GenericGraph::value_type& factor: graph){
199  index1 = dictionary[factor->key1.index];
200  index2 = dictionary[factor->key2.index];
201  std::cout << "index1: " << index1 << std::endl;
202  std::cout << "index2: " << index2 << std::endl;
203  // if both nodes are in the current graph, i.e. not a joint factor between frontal and separator
204  if (index1 >= 0 && index2 >= 0) {
205  std::pair<Neighbors, Weights>& adjacencyMap1 = adjacencyMap[index1];
206  std::pair<Neighbors, Weights>& adjacencyMap2 = adjacencyMap[index2];
207  try{
208  adjacencyMap1.first.push_back(index2);
209  adjacencyMap1.second.push_back(factor->weight);
210  adjacencyMap2.first.push_back(index1);
211  adjacencyMap2.second.push_back(factor->weight);
212  }catch(std::exception& e){
213  std::cout << e.what() << std::endl;
214  }
215  numEdges++;
216  }
217  }
218 
219  // prepare for {xadj}, {adjncy}, and {adjwgt}
220  *ptr_xadj = sharedInts(new idx_t[numNodes+1]);
221  *ptr_adjncy = sharedInts(new idx_t[numEdges*2]);
222  *ptr_adjwgt = sharedInts(new idx_t[numEdges*2]);
223  sharedInts& xadj = *ptr_xadj;
224  sharedInts& adjncy = *ptr_adjncy;
225  sharedInts& adjwgt = *ptr_adjwgt;
226  int ind_xadj = 0, ind_adjncy = 0;
227  for(const NeighborsInfo& info: adjacencyMap) {
228  *(xadj.get() + ind_xadj) = ind_adjncy;
229  std::copy(info.first .begin(), info.first .end(), adjncy.get() + ind_adjncy);
230  std::copy(info.second.begin(), info.second.end(), adjwgt.get() + ind_adjncy);
231  assert(info.first.size() == info.second.size());
232  ind_adjncy += info.first.size();
233  ind_xadj ++;
234  }
235  if (ind_xadj != numNodes) throw std::runtime_error("prepareMetisGraph_: ind_xadj != numNodes");
236  *(xadj.get() + ind_xadj) = ind_adjncy;
237  }
238 
239  /* ************************************************************************* */
240  template<class GenericGraph>
241  std::optional<MetisResult> separatorPartitionByMetis(const GenericGraph& graph,
242  const std::vector<size_t>& keys, WorkSpace& workspace, bool verbose) {
243  // create a metis graph
244  size_t numKeys = keys.size();
245  if (verbose)
246  std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl;
247 
249 
250  prepareMetisGraph<GenericGraph>(graph, keys, workspace, &xadj, &adjncy, &adjwgt);
251 
252  // run ND on the graph
253  const auto [sepsize, part] = separatorMetis(numKeys, xadj, adjncy, adjwgt, verbose);
254  if (!sepsize) return std::optional<MetisResult>();
255 
256  // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later
257  // we will have more submaps
259  result.C.reserve(sepsize);
260  result.A.reserve(numKeys - sepsize);
261  result.B.reserve(numKeys - sepsize);
262  int* ptr_part = part.get();
263  std::vector<size_t>::const_iterator itKey = keys.begin();
264  std::vector<size_t>::const_iterator itKeyLast = keys.end();
265  while(itKey != itKeyLast) {
266  switch(*(ptr_part++)) {
267  case 0: result.A.push_back(*(itKey++)); break;
268  case 1: result.B.push_back(*(itKey++)); break;
269  case 2: result.C.push_back(*(itKey++)); break;
270  default: throw std::runtime_error("separatorPartitionByMetis: invalid results from Metis ND!");
271  }
272  }
273 
274  if (verbose) {
275  std::cout << "total key: " << keys.size()
276  << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", "
277  << result.C.size() << "; sepsize from Metis = " << sepsize << std::endl;
278  //throw runtime_error("separatorPartitionByMetis:stop for debug");
279  }
280 
281  if(result.C.size() != size_t(sepsize)) {
282  std::cout << "total key: " << keys.size()
283  << " result(A,B,C) = " << result.A.size() << ", " << result.B.size() << ", " << result.C.size()
284  << "; sepsize from Metis = " << sepsize << std::endl;
285  throw std::runtime_error("separatorPartitionByMetis: invalid sepsize from Metis ND!");
286  }
287 
288  return result;
289  }
290 
291  /* *************************************************************************/
292  template<class GenericGraph>
293  std::optional<MetisResult> edgePartitionByMetis(const GenericGraph& graph,
294  const std::vector<size_t>& keys, WorkSpace& workspace, bool verbose) {
295 
296  // a small hack for handling the camera1-camera2 case used in the unit tests
297  if (graph.size() == 1 && keys.size() == 2) {
299  result.A.push_back(keys.front());
300  result.B.push_back(keys.back());
301  return result;
302  }
303 
304  // create a metis graph
305  size_t numKeys = keys.size();
306  if (verbose) std::cout << graph.size() << " factors,\t" << numKeys << " nodes;\t" << std::endl;
308  prepareMetisGraph<GenericGraph>(graph, keys, workspace, &xadj, &adjncy, &adjwgt);
309 
310  // run metis on the graph
311  const auto [edgecut, part] = edgeMetis(numKeys, xadj, adjncy, adjwgt, verbose);
312 
313  // convert the 0-1-2 from Metis to 1-2-0, so that the separator is 0, as later we will have more submaps
315  result.A.reserve(numKeys);
316  result.B.reserve(numKeys);
317  int* ptr_part = part.get();
318  std::vector<size_t>::const_iterator itKey = keys.begin();
319  std::vector<size_t>::const_iterator itKeyLast = keys.end();
320  while(itKey != itKeyLast) {
321  if (*ptr_part != 0 && *ptr_part != 1)
322  std::cout << *ptr_part << "!!!" << std::endl;
323  switch(*(ptr_part++)) {
324  case 0: result.A.push_back(*(itKey++)); break;
325  case 1: result.B.push_back(*(itKey++)); break;
326  default: throw std::runtime_error("edgePartitionByMetis: invalid results from Metis ND!");
327  }
328  }
329 
330  if (verbose) {
331  std::cout << "the size of two submaps in the reduced graph: " << result.A.size()
332  << " " << result.B.size() << std::endl;
333  int edgeCut = 0;
334 
335  for(const typename GenericGraph::value_type& factor: graph){
336  int key1 = factor->key1.index;
337  int key2 = factor->key2.index;
338  // print keys and their subgraph assignment
339  std::cout << key1;
340  if (std::find(result.A.begin(), result.A.end(), key1) != result.A.end()) std::cout <<"A ";
341  if (std::find(result.B.begin(), result.B.end(), key1) != result.B.end()) std::cout <<"B ";
342 
343  std::cout << key2;
344  if (std::find(result.A.begin(), result.A.end(), key2) != result.A.end()) std::cout <<"A ";
345  if (std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) std::cout <<"B ";
346  std::cout << "weight " << factor->weight;;
347 
348  // find vertices that were assigned to sets A & B. Their edge will be cut
349  if ((std::find(result.A.begin(), result.A.end(), key1) != result.A.end() &&
350  std::find(result.B.begin(), result.B.end(), key2) != result.B.end()) ||
351  (std::find(result.B.begin(), result.B.end(), key1) != result.B.end() &&
352  std::find(result.A.begin(), result.A.end(), key2) != result.A.end())){
353  edgeCut ++;
354  std::cout << " CUT ";
355  }
356  std::cout << std::endl;
357  }
358  std::cout << "edgeCut: " << edgeCut << std::endl;
359  }
360 
361  return result;
362  }
363 
364  /* ************************************************************************* */
365  bool isLargerIsland(const std::vector<size_t>& island1, const std::vector<size_t>& island2) {
366  return island1.size() > island2.size();
367  }
368 
369  /* ************************************************************************* */
370  // debug functions
371  void printIsland(const std::vector<size_t>& island) {
372  std::cout << "island: ";
373  for(const size_t key: island)
374  std::cout << key << " ";
375  std::cout << std::endl;
376  }
377 
378  void printIslands(const std::list<std::vector<size_t> >& islands) {
379  for(const std::vector<std::size_t>& island: islands)
380  printIsland(island);
381  }
382 
383  void printNumCamerasLandmarks(const std::vector<size_t>& keys, const std::vector<Symbol>& int2symbol) {
384  int numCamera = 0, numLandmark = 0;
385  for(const size_t key: keys)
386  if (int2symbol[key].chr() == 'x')
387  numCamera++;
388  else
389  numLandmark++;
390  std::cout << "numCamera: " << numCamera << " numLandmark: " << numLandmark << std::endl;
391  }
392 
393  /* ************************************************************************* */
394  template<class GenericGraph>
395  void addLandmarkToPartitionResult(const GenericGraph& graph, const std::vector<size_t>& landmarkKeys,
396  MetisResult& partitionResult, WorkSpace& workspace) {
397 
398  // set up cameras in the dictionary
399  std::vector<size_t>& A = partitionResult.A;
400  std::vector<size_t>& B = partitionResult.B;
401  std::vector<size_t>& C = partitionResult.C;
402  std::vector<int>& dictionary = workspace.dictionary;
403  std::fill(dictionary.begin(), dictionary.end(), -1);
404  for(const size_t a: A)
405  dictionary[a] = 1;
406  for(const size_t b: B)
407  dictionary[b] = 2;
408  if (!C.empty())
409  throw std::runtime_error("addLandmarkToPartitionResult: C is not empty");
410 
411  // set up landmarks
412  size_t i,j;
413  for(const typename GenericGraph::value_type& factor: graph) {
414  i = factor->key1.index;
415  j = factor->key2.index;
416  if (dictionary[j] == 0) // if the landmark is already in the separator, continue
417  continue;
418  else if (dictionary[j] == -1)
419  dictionary[j] = dictionary[i];
420  else {
421  if (dictionary[j] != dictionary[i])
422  dictionary[j] = 0;
423  }
424 // if (j == 67980)
425 // std::cout << "dictionary[67980]" << dictionary[j] << std::endl;
426  }
427 
428  for(const size_t j: landmarkKeys) {
429  switch(dictionary[j]) {
430  case 0: C.push_back(j); break;
431  case 1: A.push_back(j); break;
432  case 2: B.push_back(j); break;
433  default: std::cout << j << ": " << dictionary[j] << std::endl;
434  throw std::runtime_error("addLandmarkToPartitionResult: wrong status for landmark");
435  }
436  }
437  }
438 
439 #define REDUCE_CAMERA_GRAPH
440 
441  /* ************************************************************************* */
442  template<class GenericGraph>
443  std::optional<MetisResult> findPartitoning(const GenericGraph& graph, const std::vector<size_t>& keys,
444  WorkSpace& workspace, bool verbose,
445  const std::optional<std::vector<Symbol> >& int2symbol, const bool reduceGraph) {
446  std::optional<MetisResult> result;
447  GenericGraph reducedGraph;
448  std::vector<size_t> keyToPartition;
449  std::vector<size_t> cameraKeys, landmarkKeys;
450  if (reduceGraph) {
451  if (!int2symbol.has_value())
452  throw std::invalid_argument("findSeparator: int2symbol must be valid!");
453 
454  // find out all the landmark keys, which are to be eliminated
455  cameraKeys.reserve(keys.size());
456  landmarkKeys.reserve(keys.size());
457  for(const size_t key: keys) {
458  if((*int2symbol)[key].chr() == 'x')
459  cameraKeys.push_back(key);
460  else
461  landmarkKeys.push_back(key);
462  }
463 
464  keyToPartition = cameraKeys;
465  workspace.prepareDictionary(keyToPartition);
466  const std::vector<int>& dictionary = workspace.dictionary;
467  reduceGenericGraph(graph, cameraKeys, landmarkKeys, dictionary, reducedGraph);
468  std::cout << "original graph: V" << keys.size() << ", E" << graph.size()
469  << " --> reduced graph: V" << cameraKeys.size() << ", E" << reducedGraph.size() << std::endl;
470  result = edgePartitionByMetis(reducedGraph, keyToPartition, workspace, verbose);
471  } else // call Metis to partition the graph to A, B, C
472  result = separatorPartitionByMetis(graph, keys, workspace, verbose);
473 
474  if (!result.has_value()) {
475  std::cout << "metis failed!" << std::endl;
476  return {};
477  }
478 
479  if (reduceGraph) {
480  addLandmarkToPartitionResult(graph, landmarkKeys, *result, workspace);
481  std::cout << "the separator size: " << result->C.size() << " landmarks" << std::endl;
482  }
483 
484  return result;
485  }
486 
487  /* ************************************************************************* */
488  template<class GenericGraph>
489  int findSeparator(const GenericGraph& graph, const std::vector<size_t>& keys,
490  const int minNodesPerMap, WorkSpace& workspace, bool verbose,
491  const std::optional<std::vector<Symbol> >& int2symbol, const bool reduceGraph,
492  const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark) {
493 
494  std::optional<MetisResult> result = findPartitoning(graph, keys, workspace,
495  verbose, int2symbol, reduceGraph);
496 
497  // find the island in A and B, and make them separated submaps
498  typedef std::vector<size_t> Island;
499  std::list<Island> islands;
500 
501  std::list<Island> islands_in_A = findIslands(graph, result->A, workspace,
502  minNrConstraintsPerCamera, minNrConstraintsPerLandmark);
503 
504  std::list<Island> islands_in_B = findIslands(graph, result->B, workspace,
505  minNrConstraintsPerCamera, minNrConstraintsPerLandmark);
506 
507  islands.insert(islands.end(), islands_in_A.begin(), islands_in_A.end());
508  islands.insert(islands.end(), islands_in_B.begin(), islands_in_B.end());
509  islands.sort(isLargerIsland);
510  size_t numIsland0 = islands.size();
511 
512 #ifdef NDEBUG
513 // verbose = true;
514 // if (!int2symbol) throw std::invalid_argument("findSeparator: int2symbol is not set!");
515 // std::cout << "sep size: " << result->C.size() << "; ";
516 // printNumCamerasLandmarks(result->C, *int2symbol);
517 // std::cout << "no. of island: " << islands.size() << "; ";
518 // std::cout << "island size: ";
519 // for(const Island& island: islands)
520 // std::cout << island.size() << " ";
521 // std::cout << std::endl;
522 
523 // for(const Island& island: islands) {
524 // printNumCamerasLandmarks(island, int2symbol);
525 // }
526 #endif
527 
528  // absorb small components into the separator
529  size_t oldSize = islands.size();
530  while(true) {
531  if (islands.size() < 2) {
532  std::cout << "numIsland: " << numIsland0 << std::endl;
533  throw std::runtime_error("findSeparator: found fewer than 2 submaps!");
534  }
535 
536  std::list<Island>::reference island = islands.back();
537  if ((int)island.size() >= minNodesPerMap) break;
538  result->C.insert(result->C.end(), island.begin(), island.end());
539  islands.pop_back();
540  }
541  if (islands.size() != oldSize){
542  if (verbose) std::cout << oldSize << "-" << oldSize - islands.size() << " submap(s);\t" << std::endl;
543  }
544  else{
545  if (verbose) std::cout << oldSize << " submap(s);\t" << std::endl;
546  }
547 
548  // generate the node map
549  std::vector<int>& partitionTable = workspace.partitionTable;
550  std::fill(partitionTable.begin(), partitionTable.end(), -1);
551  for(const size_t key: result->C)
552  partitionTable[key] = 0;
553  int idx = 0;
554  for(const Island& island: islands) {
555  idx++;
556  for(const size_t key: island) {
557  partitionTable[key] = idx;
558  }
559  }
560 
561  return islands.size();
562  }
563 
564 }} //namespace
key1
const Symbol key1('v', 1)
timing.h
Timing utilities.
gtsam::partition::reduceGenericGraph
void reduceGenericGraph(const GenericGraph3D &graph, const std::vector< size_t > &cameraKeys, const std::vector< size_t > &landmarkKeys, const std::vector< int > &dictionary, GenericGraph3D &reducedGraph)
Definition: GenericGraph.cpp:353
FreeCtrl
#define FreeCtrl
Definition: rename.h:198
gtsam::partition::findPartitoning
std::optional< MetisResult > findPartitoning(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, bool verbose, const std::optional< std::vector< Symbol > > &int2symbol, const bool reduceGraph)
Definition: FindSeparator-inl.h:443
gtsam::partition::WorkSpace::dictionary
std::vector< int > dictionary
Definition: PartitionWorkSpace.h:20
gtsam::partition::WorkSpace
Definition: PartitionWorkSpace.h:19
adjwgt
idx_t idx_t idx_t idx_t idx_t idx_t * adjwgt
Definition: include/metis.h:198
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
FindSeparator.h
ctrl_t
Definition: libmetis/struct.h:139
gtsam::partition::prepareMetisGraph
void prepareMetisGraph(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, sharedInts *ptr_xadj, sharedInts *ptr_adjncy, sharedInts *ptr_adjwgt)
Definition: FindSeparator-inl.h:179
gtsam::partition::WorkSpace::partitionTable
PartitionTable partitionTable
Definition: PartitionWorkSpace.h:22
adjncy
idx_t idx_t idx_t * adjncy
Definition: include/metis.h:198
AllocateWorkSpace
#define AllocateWorkSpace
Definition: rename.h:250
B
Definition: test_numpy_dtypes.cpp:299
gtsam::partition::modefied_EdgeComputeSeparator
void modefied_EdgeComputeSeparator(idx_t *nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *adjwgt, idx_t *options, idx_t *edgecut, idx_t *part)
Definition: FindSeparator-inl.h:82
ctrl_t::tpwgts
real_t * tpwgts
Definition: libmetis/struct.h:169
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::partition::printNumCamerasLandmarks
void printNumCamerasLandmarks(const std::vector< size_t > &keys, const std::vector< Symbol > &int2symbol)
Definition: FindSeparator-inl.h:383
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
n
int n
Definition: BiCGSTAB_simple.cpp:1
METIS_ComputeVertexSeparator
int METIS_ComputeVertexSeparator(idx_t *nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *options, idx_t *r_sepsize, idx_t *part)
Definition: parmetis.c:161
MultilevelBisect
#define MultilevelBisect
Definition: rename.h:208
ncon
idx_t * ncon
Definition: include/metis.h:197
A
Definition: test_numpy_dtypes.cpp:298
key2
const Symbol key2('v', 2)
ctrl_t::iptype
miptype_et iptype
Definition: libmetis/struct.h:144
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
METIS_IPTYPE_GROW
@ METIS_IPTYPE_GROW
Definition: include/metis.h:321
SetupGraph
#define SetupGraph
Definition: rename.h:90
gtsam::partition::separatorPartitionByMetis
std::optional< MetisResult > separatorPartitionByMetis(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, bool verbose)
Definition: FindSeparator-inl.h:241
InitRandom
#define InitRandom
Definition: rename.h:246
gtsam::partition::printIslands
void printIslands(const std::list< std::vector< size_t > > &islands)
Definition: FindSeparator-inl.h:378
gtsam::Weights
Eigen::Matrix< double, 1, -1 > Weights
Definition: Basis.h:69
gtsam::partition::MetisResult::C
std::vector< size_t > C
Definition: FindSeparator.h:25
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
SetupCtrl
#define SetupCtrl
Definition: rename.h:194
gtsam::partition::findIslands
list< vector< size_t > > findIslands(const GenericGraph2D &graph, const vector< size_t > &keys, WorkSpace &workspace, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark)
Definition: GenericGraph.cpp:23
METIS_OP_OMETIS
@ METIS_OP_OMETIS
Definition: include/metis.h:265
vwgt
idx_t idx_t idx_t idx_t * vwgt
Definition: include/metis.h:198
gtsam::partition::WorkSpace::prepareDictionary
void prepareDictionary(const std::vector< size_t > &keys)
Definition: PartitionWorkSpace.h:29
part
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t idx_t idx_t * part
Definition: include/metis.h:200
edgecut
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t idx_t * edgecut
Definition: include/metis.h:200
gtsam::partition::MetisResult::B
std::vector< size_t > B
Definition: FindSeparator.h:24
key
const gtsam::Symbol key('X', 0)
gtsam::partition::sharedInts
boost::shared_array< idx_t > sharedInts
Definition: FindSeparator-inl.h:34
gtsam::b
const G & b
Definition: Group.h:79
METIS_SetDefaultOptions
int METIS_SetDefaultOptions(idx_t *options)
Definition: auxapi.c:36
xadj
idx_t idx_t * xadj
Definition: include/metis.h:197
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: SFMdata.h:40
FreeGraph
#define FreeGraph
Definition: rename.h:98
gtsam::partition::separatorMetis
std::pair< idx_t, sharedInts > separatorMetis(idx_t n, const sharedInts &xadj, const sharedInts &adjncy, const sharedInts &adjwgt, bool verbose)
Definition: FindSeparator-inl.h:43
gtsam::partition::printIsland
void printIsland(const std::vector< size_t > &island)
Definition: FindSeparator-inl.h:371
ctrl_t::seed
idx_t seed
Definition: libmetis/struct.h:156
gtsam::partition::edgeMetis
std::pair< int, sharedInts > edgeMetis(idx_t n, const sharedInts &xadj, const sharedInts &adjncy, const sharedInts &adjwgt, bool verbose)
Definition: FindSeparator-inl.h:130
rsum
#define rsum
Definition: gklib_rename.h:117
real_t
float real_t
Definition: include/metis.h:132
METIS_NOPTIONS
#define METIS_NOPTIONS
Definition: include/metis.h:175
metislib.h
ctrl_t::ncuts
idx_t ncuts
Definition: libmetis/struct.h:157
gtsam::partition::edgePartitionByMetis
std::optional< MetisResult > edgePartitionByMetis(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, bool verbose)
Definition: FindSeparator-inl.h:293
sepsize
idx_t idx_t idx_t idx_t idx_t * sepsize
Definition: include/metis.h:237
gtsam::partition::isLargerIsland
bool isLargerIsland(const std::vector< size_t > &island1, const std::vector< size_t > &island2)
Definition: FindSeparator-inl.h:365
icopy
#define icopy
Definition: gklib_rename.h:28
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::partition::MetisResult
Definition: FindSeparator.h:23
gtsam::partition::MetisResult::A
std::vector< size_t > A
Definition: FindSeparator.h:24
options
Definition: options.h:16
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
rwspacemalloc
#define rwspacemalloc
Definition: rename.h:257
graph_t
Definition: libmetis/struct.h:82
idx_t
int32_t idx_t
Definition: include/metis.h:101
gtsam::partition::addLandmarkToPartitionResult
void addLandmarkToPartitionResult(const GenericGraph &graph, const std::vector< size_t > &landmarkKeys, MetisResult &partitionResult, WorkSpace &workspace)
Definition: FindSeparator-inl.h:395
gtsam::partition::findSeparator
int findSeparator(const GenericGraph &graph, const std::vector< size_t > &keys, const int minNodesPerMap, WorkSpace &workspace, bool verbose, const std::optional< std::vector< Symbol > > &int2symbol, const bool reduceGraph, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark)
Definition: FindSeparator-inl.h:489


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:32