17 #include <boost/shared_array.hpp> 31 namespace gtsam {
namespace partition {
43 const sharedInts&
adjncy,
const sharedInts&
adjwgt,
bool verbose) {
46 std::vector<idx_t>
vwgt;
50 sharedInts part_(
new idx_t[n]);
58 printf(
"**********************************************************************\n");
59 printf(
"Graph Information ---------------------------------------------------\n");
60 printf(
" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+
n) / 2);
61 printf(
"\nND Partitioning... -------------------------------------------\n");
73 printf(
" Sep size: \t\t %d\n", sepsize);
74 printf(
"**********************************************************************\n");
77 return std::make_pair(sepsize, part_);
95 graph =
SetupGraph(ctrl, *nvtxs, 1, xadj, adjncy, vwgt,
nullptr,
nullptr);
106 for (i=0; i<
ncon; i++) {
108 tpwgts2[ncon+
i] = 1.0 - tpwgts2[
i];
117 std::cout <<
"Finished bisection:" << *edgecut << std::endl;
130 const sharedInts&
adjwgt,
bool verbose) {
133 std::vector<idx_t>
vwgt;
137 sharedInts part_(
new idx_t[n]);
145 printf(
"**********************************************************************\n");
146 printf(
"Graph Information ---------------------------------------------------\n");
147 printf(
" #Vertices: %d, #Edges: %u\n", n, *(xadj.get()+
n) / 2);
148 printf(
"\nND Partitioning... -------------------------------------------\n");
162 printf(
"\nTiming Information --------------------------------------------------\n");
164 printf(
" Edge cuts: \t\t %d\n", edgecut);
165 printf(
"**********************************************************************\n");
168 return std::make_pair(edgecut, part_);
177 template <
class GenericGraph>
179 sharedInts* ptr_xadj, sharedInts* ptr_adjncy, sharedInts* ptr_adjwgt) {
181 typedef std::vector<int>
Weights;
182 typedef std::vector<int> Neighbors;
183 typedef std::pair<Neighbors, Weights> NeighborsInfo;
186 std::vector<int>& dictionary = workspace.
dictionary;
190 int numNodes = keys.size();
192 std::vector<NeighborsInfo> adjacencyMap;
193 adjacencyMap.resize(numNodes);
194 std::cout <<
"Number of nodes: " << adjacencyMap.size() << std::endl;
197 for(
const typename GenericGraph::value_type& factor: graph){
198 index1 = dictionary[factor->key1.index];
199 index2 = dictionary[factor->key2.index];
200 std::cout <<
"index1: " << index1 << std::endl;
201 std::cout <<
"index2: " << index2 << std::endl;
203 if (index1 >= 0 && index2 >= 0) {
204 std::pair<Neighbors, Weights>& adjacencyMap1 = adjacencyMap[index1];
205 std::pair<Neighbors, Weights>& adjacencyMap2 = adjacencyMap[index2];
207 adjacencyMap1.first.push_back(index2);
208 adjacencyMap1.second.push_back(factor->weight);
209 adjacencyMap2.first.push_back(index1);
210 adjacencyMap2.second.push_back(factor->weight);
211 }
catch(std::exception&
e){
212 std::cout << e.what() << std::endl;
222 sharedInts&
xadj = *ptr_xadj;
223 sharedInts&
adjncy = *ptr_adjncy;
224 sharedInts&
adjwgt = *ptr_adjwgt;
225 int ind_xadj = 0, ind_adjncy = 0;
226 for(
const NeighborsInfo&
info: adjacencyMap) {
227 *(xadj.get() + ind_xadj) = ind_adjncy;
228 std::copy(
info.first .begin(),
info.first .end(), adjncy.get() + ind_adjncy);
229 std::copy(
info.second.begin(),
info.second.end(), adjwgt.get() + ind_adjncy);
230 assert(
info.first.size() ==
info.second.size());
231 ind_adjncy +=
info.first.size();
234 if (ind_xadj != numNodes)
throw std::runtime_error(
"prepareMetisGraph_: ind_xadj != numNodes");
235 *(xadj.get() + ind_xadj) = ind_adjncy;
239 template<
class GenericGraph>
241 const std::vector<size_t>&
keys,
WorkSpace& workspace,
bool verbose) {
243 size_t numKeys = keys.size();
245 std::cout << graph.size() <<
" factors,\t" << numKeys <<
" nodes;\t" << std::endl;
253 if (!sepsize)
return std::optional<MetisResult>();
258 result.C.reserve(sepsize);
259 result.A.reserve(numKeys - sepsize);
260 result.B.reserve(numKeys - sepsize);
261 int* ptr_part =
part.get();
262 std::vector<size_t>::const_iterator itKey = keys.begin();
263 std::vector<size_t>::const_iterator itKeyLast = keys.end();
264 while(itKey != itKeyLast) {
265 switch(*(ptr_part++)) {
266 case 0: result.A.push_back(*(itKey++));
break;
267 case 1: result.B.push_back(*(itKey++));
break;
268 case 2: result.C.push_back(*(itKey++));
break;
269 default:
throw std::runtime_error(
"separatorPartitionByMetis: invalid results from Metis ND!");
274 std::cout <<
"total key: " << keys.size()
275 <<
" result(A,B,C) = " << result.A.size() <<
", " << result.B.size() <<
", " 276 << result.C.size() <<
"; sepsize from Metis = " << sepsize << std::endl;
280 if(result.C.size() !=
sepsize) {
281 std::cout <<
"total key: " << keys.size()
282 <<
" result(A,B,C) = " << result.A.size() <<
", " << result.B.size() <<
", " << result.C.size()
283 <<
"; sepsize from Metis = " << sepsize << std::endl;
284 throw std::runtime_error(
"separatorPartitionByMetis: invalid sepsize from Metis ND!");
291 template<
class GenericGraph>
293 const std::vector<size_t>&
keys,
WorkSpace& workspace,
bool verbose) {
296 if (graph.size() == 1 && keys.size() == 2) {
298 result.
A.push_back(keys.front());
299 result.
B.push_back(keys.back());
304 size_t numKeys = keys.size();
305 if (verbose) std::cout << graph.size() <<
" factors,\t" << numKeys <<
" nodes;\t" << std::endl;
314 result.
A.reserve(numKeys);
315 result.
B.reserve(numKeys);
316 int* ptr_part =
part.get();
317 std::vector<size_t>::const_iterator itKey = keys.begin();
318 std::vector<size_t>::const_iterator itKeyLast = keys.end();
319 while(itKey != itKeyLast) {
320 if (*ptr_part != 0 && *ptr_part != 1)
321 std::cout << *ptr_part <<
"!!!" << std::endl;
322 switch(*(ptr_part++)) {
323 case 0: result.
A.push_back(*(itKey++));
break;
324 case 1: result.
B.push_back(*(itKey++));
break;
325 default:
throw std::runtime_error(
"edgePartitionByMetis: invalid results from Metis ND!");
330 std::cout <<
"the size of two submaps in the reduced graph: " << result.
A.size()
331 <<
" " << result.
B.size() << std::endl;
334 for(
const typename GenericGraph::value_type& factor: graph){
335 int key1 = factor->key1.index;
336 int key2 = factor->key2.index;
339 if (std::find(result.
A.begin(), result.
A.end(),
key1) != result.
A.end()) std::cout <<
"A ";
340 if (std::find(result.
B.begin(), result.
B.end(),
key1) != result.
B.end()) std::cout <<
"B ";
343 if (std::find(result.
A.begin(), result.
A.end(),
key2) != result.
A.end()) std::cout <<
"A ";
344 if (std::find(result.
B.begin(), result.
B.end(),
key2) != result.
B.end()) std::cout <<
"B ";
345 std::cout <<
"weight " << factor->weight;;
348 if ((std::find(result.
A.begin(), result.
A.end(),
key1) != result.
A.end() &&
349 std::find(result.
B.begin(), result.
B.end(),
key2) != result.
B.end()) ||
350 (std::find(result.
B.begin(), result.
B.end(),
key1) != result.
B.end() &&
351 std::find(result.
A.begin(), result.
A.end(),
key2) != result.
A.end())){
353 std::cout <<
" CUT ";
355 std::cout << std::endl;
357 std::cout <<
"edgeCut: " << edgeCut << std::endl;
364 bool isLargerIsland(
const std::vector<size_t>& island1,
const std::vector<size_t>& island2) {
365 return island1.size() > island2.size();
371 std::cout <<
"island: ";
372 for(
const size_t key: island)
373 std::cout <<
key <<
" ";
374 std::cout << std::endl;
378 for(
const std::vector<std::size_t>& island: islands)
383 int numCamera = 0, numLandmark = 0;
384 for(
const size_t key: keys)
385 if (int2symbol[
key].chr() ==
'x')
389 std::cout <<
"numCamera: " << numCamera <<
" numLandmark: " << numLandmark << std::endl;
393 template<
class GenericGraph>
398 std::vector<size_t>&
A = partitionResult.
A;
399 std::vector<size_t>&
B = partitionResult.
B;
400 std::vector<size_t>&
C = partitionResult.
C;
401 std::vector<int>& dictionary = workspace.
dictionary;
402 std::fill(dictionary.begin(), dictionary.end(), -1);
403 for(
const size_t a: A)
405 for(
const size_t b: B)
408 throw std::runtime_error(
"addLandmarkToPartitionResult: C is not empty");
412 for(
const typename GenericGraph::value_type& factor: graph) {
413 i = factor->key1.index;
414 j = factor->key2.index;
415 if (dictionary[j] == 0)
417 else if (dictionary[j] == -1)
418 dictionary[
j] = dictionary[
i];
420 if (dictionary[j] != dictionary[i])
427 for(
const size_t j: landmarkKeys) {
428 switch(dictionary[j]) {
429 case 0: C.push_back(j);
break;
430 case 1: A.push_back(j);
break;
431 case 2: B.push_back(j);
break;
432 default: std::cout << j <<
": " << dictionary[
j] << std::endl;
433 throw std::runtime_error(
"addLandmarkToPartitionResult: wrong status for landmark");
438 #define REDUCE_CAMERA_GRAPH 441 template<
class GenericGraph>
444 const std::optional<std::vector<Symbol> >& int2symbol,
const bool reduceGraph) {
445 std::optional<MetisResult>
result;
446 GenericGraph reducedGraph;
447 std::vector<size_t> keyToPartition;
448 std::vector<size_t> cameraKeys, landmarkKeys;
450 if (!int2symbol.has_value())
451 throw std::invalid_argument(
"findSeparator: int2symbol must be valid!");
454 cameraKeys.reserve(keys.size());
455 landmarkKeys.reserve(keys.size());
456 for(
const size_t key: keys) {
457 if((*int2symbol)[
key].chr() ==
'x')
458 cameraKeys.push_back(
key);
460 landmarkKeys.push_back(
key);
463 keyToPartition = cameraKeys;
465 const std::vector<int>& dictionary = workspace.
dictionary;
467 std::cout <<
"original graph: V" << keys.size() <<
", E" << graph.size()
468 <<
" --> reduced graph: V" << cameraKeys.size() <<
", E" << reducedGraph.size() << std::endl;
473 if (!result.has_value()) {
474 std::cout <<
"metis failed!" << std::endl;
480 std::cout <<
"the separator size: " << result->C.size() <<
" landmarks" << std::endl;
487 template<
class GenericGraph>
489 const int minNodesPerMap,
WorkSpace& workspace,
bool verbose,
490 const std::optional<std::vector<Symbol> >& int2symbol,
const bool reduceGraph,
491 const int minNrConstraintsPerCamera,
const int minNrConstraintsPerLandmark) {
494 verbose, int2symbol, reduceGraph);
497 typedef std::vector<size_t> Island;
498 std::list<Island> islands;
500 std::list<Island> islands_in_A =
findIslands(graph, result->A, workspace,
501 minNrConstraintsPerCamera, minNrConstraintsPerLandmark);
503 std::list<Island> islands_in_B =
findIslands(graph, result->B, workspace,
504 minNrConstraintsPerCamera, minNrConstraintsPerLandmark);
506 islands.insert(islands.end(), islands_in_A.begin(), islands_in_A.end());
507 islands.insert(islands.end(), islands_in_B.begin(), islands_in_B.end());
509 size_t numIsland0 = islands.size();
528 size_t oldSize = islands.size();
530 if (islands.size() < 2) {
531 std::cout <<
"numIsland: " << numIsland0 << std::endl;
532 throw std::runtime_error(
"findSeparator: found fewer than 2 submaps!");
535 std::list<Island>::reference island = islands.back();
536 if ((
int)island.size() >= minNodesPerMap)
break;
537 result->C.insert(result->C.end(), island.begin(), island.end());
540 if (islands.size() != oldSize){
541 if (verbose) std::cout << oldSize <<
"-" << oldSize - islands.size() <<
" submap(s);\t" << std::endl;
544 if (verbose) std::cout << oldSize <<
" submap(s);\t" << std::endl;
549 std::fill(partitionTable.begin(), partitionTable.end(), -1);
550 for(
const size_t key: result->C)
551 partitionTable[
key] = 0;
553 for(
const Island& island: islands) {
555 for(
const size_t key: island) {
556 partitionTable[
key] = idx;
560 return islands.size();
list< vector< size_t > > findIslands(const GenericGraph2D &graph, const vector< size_t > &keys, WorkSpace &workspace, const int minNrConstraintsPerCamera, const int minNrConstraintsPerLandmark)
const gtsam::Symbol key('X', 0)
std::optional< MetisResult > separatorPartitionByMetis(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, bool verbose)
idx_t idx_t idx_t idx_t * vwgt
idx_t idx_t idx_t idx_t idx_t * sepsize
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
boost::shared_array< idx_t > sharedInts
std::pair< int, sharedInts > edgeMetis(idx_t n, const sharedInts &xadj, const sharedInts &adjncy, const sharedInts &adjwgt, bool verbose)
void printIsland(const std::vector< size_t > &island)
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)
NonlinearFactorGraph graph
int METIS_SetDefaultOptions(idx_t *options)
PartitionTable partitionTable
std::optional< MetisResult > edgePartitionByMetis(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, bool verbose)
#define AllocateWorkSpace
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t idx_t * edgecut
bool isLargerIsland(const std::vector< size_t > &island1, const std::vector< size_t > &island2)
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)
void addLandmarkToPartitionResult(const GenericGraph &graph, const std::vector< size_t > &landmarkKeys, MetisResult &partitionResult, WorkSpace &workspace)
const Symbol key1('v', 1)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t * options
void reduceGenericGraph(const GenericGraph3D &graph, const std::vector< size_t > &cameraKeys, const std::vector< size_t > &landmarkKeys, const std::vector< int > &dictionary, GenericGraph3D &reducedGraph)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
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)
std::vector< int > dictionary
Matrix< Scalar, Dynamic, Dynamic > C
idx_t idx_t idx_t idx_t idx_t idx_t * adjwgt
void prepareMetisGraph(const GenericGraph &graph, const std::vector< size_t > &keys, WorkSpace &workspace, sharedInts *ptr_xadj, sharedInts *ptr_adjncy, sharedInts *ptr_adjwgt)
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)
std::pair< int, sharedInts > separatorMetis(idx_t n, const sharedInts &xadj, const sharedInts &adjncy, const sharedInts &adjwgt, bool verbose)
idx_t idx_t idx_t * adjncy
void printNumCamerasLandmarks(const std::vector< size_t > &keys, const std::vector< Symbol > &int2symbol)
void prepareDictionary(const std::vector< size_t > &keys)
Eigen::Matrix< double, 1, -1 > Weights
void printIslands(const std::list< std::vector< size_t > > &islands)
const Symbol key2('v', 2)