Working ordering format for Metis_NodeND
parent
f447481844
commit
bf22a49504
|
|
@ -0,0 +1,59 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file MetisIndex-inl.h
|
||||
* @author Andrew Melim
|
||||
* @date Oct. 10, 2014
|
||||
*/
|
||||
|
||||
#include <gtsam/inference/MetisIndex.h>
|
||||
#include <map>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
MetisIndex::~MetisIndex(){}
|
||||
|
||||
std::vector<int> MetisIndex::xadj() const { return xadj_; }
|
||||
std::vector<int> MetisIndex::adj() const { return adj_; }
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTOR>
|
||||
void MetisIndex::augment(const FactorGraph<FACTOR>& factors)
|
||||
{
|
||||
std::map<int, FastSet<int> > adjMap;
|
||||
std::map<int, FastSet<int> >::iterator adjMapIt;
|
||||
|
||||
/* ********** Convert to CSR format ********** */
|
||||
// Assuming that vertex numbering starts from 0 (C style),
|
||||
// then the adjacency list of vertex i is stored in array adjncy
|
||||
// starting at index xadj[i] and ending at(but not including)
|
||||
// index xadj[i + 1](i.e., adjncy[xadj[i]] through
|
||||
// and including adjncy[xadj[i + 1] - 1]).
|
||||
for (size_t i = 0; i < factors.size(); i++){
|
||||
if (factors[i])
|
||||
BOOST_FOREACH(const Key& k1, *factors[i])
|
||||
BOOST_FOREACH(const Key& k2, *factors[i])
|
||||
if (k1 != k2)
|
||||
adjMap[k1].insert(adjMap[k1].end(), k2); // Insert at the end
|
||||
}
|
||||
|
||||
|
||||
xadj_.push_back(0);// Always set the first index to zero
|
||||
for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) {
|
||||
vector<int> temp;
|
||||
copy(adjMapIt->second.begin(), adjMapIt->second.end(), std::back_inserter(temp));
|
||||
adj_.insert(adj_.end(), temp.begin(), temp.end());
|
||||
//adj_.push_back(temp);
|
||||
xadj_.push_back(adj_.size());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
|
||||
/**
|
||||
* @file MetisIndex.h
|
||||
* @author Andrew Melim
|
||||
* @date Oct. 10, 2014
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <boost/foreach.hpp>
|
||||
|
||||
#include <gtsam/base/FastList.h>
|
||||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
namespace gtsam {
|
||||
/**
|
||||
* The MetisIndex class converts a factor graph into the Compressed Sparse Row format for use in
|
||||
* METIS algorithms. Specifically, two vectors store the adjacency structure of the graph. It is built
|
||||
* fromt a factor graph prior to elimination, and stores the list of factors
|
||||
* that involve each variable.
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class GTSAM_EXPORT MetisIndex
|
||||
{
|
||||
public:
|
||||
typedef boost::shared_ptr<MetisIndex> shared_ptr;
|
||||
|
||||
private:
|
||||
FastVector<int> xadj_; // Index of node's adjacency list in adj
|
||||
FastVector<int> adj_; // Stores ajacency lists of all nodes, appended into a single vector
|
||||
size_t nFactors_; // Number of factors in the original factor graph
|
||||
size_t nValues_; //
|
||||
|
||||
public:
|
||||
/// @name Standard Constructors
|
||||
/// @{
|
||||
|
||||
/** Default constructor, creates empty MetisIndex */
|
||||
MetisIndex() : nFactors_(0), nValues_(0) {}
|
||||
|
||||
template<class FG>
|
||||
MetisIndex(const FG& factorGraph) : nFactors_(0), nValues_(0) {
|
||||
augment(factorGraph); }
|
||||
|
||||
~MetisIndex();
|
||||
/// @}
|
||||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
||||
/**
|
||||
* Augment the variable index with new factors. This can be used when
|
||||
* solving problems incrementally.
|
||||
*/
|
||||
template<class FACTOR>
|
||||
void augment(const FactorGraph<FACTOR>& factors);
|
||||
|
||||
std::vector<int> xadj() const;
|
||||
std::vector<int> adj() const;
|
||||
|
||||
/// @}
|
||||
};
|
||||
}
|
||||
|
||||
#include <gtsam/inference/MetisIndex-inl.h>
|
||||
|
|
@ -197,10 +197,21 @@ namespace gtsam {
|
|||
return Ordering::COLAMDConstrained(variableIndex, cmember);
|
||||
}
|
||||
|
||||
|
||||
/* ************************************************************************* */
|
||||
Ordering Ordering::METIS(const VariableIndex& variableIndex)
|
||||
template<class FACTOR>
|
||||
Ordering Ordering::METIS(const FactorGraph<FACTOR>& graph)
|
||||
{
|
||||
gttic(Ordering_METIS);
|
||||
// First develop the adjacency matrix for the
|
||||
// graph as described in Section 5.5 of the METIS manual
|
||||
// CSR Format
|
||||
// xadj is of size n+1
|
||||
// metis vars
|
||||
|
||||
|
||||
//METIS_NodeND(graph.keys().size(), xadj, adj);
|
||||
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
|||
|
|
@ -146,13 +146,15 @@ namespace gtsam {
|
|||
return Ordering(keys);
|
||||
}
|
||||
|
||||
/// METIS Formatting function
|
||||
template<class FACTOR>
|
||||
static GTSAM_EXPORT void CSRFormat(std::vector<int>& xadj, std::vector<int>& adj, const FactorGraph<FACTOR>& graph);
|
||||
|
||||
/// Compute an ordering determined by METIS from a VariableIndex
|
||||
static GTSAM_EXPORT Ordering METIS(const VariableIndex& variableIndex);
|
||||
//static GTSAM_EXPORT Ordering METIS(const VariableIndex& variableIndex);
|
||||
|
||||
template<class FACTOR>
|
||||
static Ordering METIS(const FactorGraph<FACTOR>& graph){
|
||||
return METIS(VariableIndex(graph)); }
|
||||
static GTSAM_EXPORT Ordering METIS(const FactorGraph<FACTOR>& graph);
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
@ -169,6 +171,7 @@ namespace gtsam {
|
|||
static GTSAM_EXPORT Ordering COLAMDConstrained(
|
||||
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
||||
|
||||
|
||||
/** Serialization function */
|
||||
friend class boost::serialization::access;
|
||||
template<class ARCHIVE>
|
||||
|
|
|
|||
|
|
@ -17,6 +17,7 @@
|
|||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/symbolic/SymbolicFactorGraph.h>
|
||||
#include <gtsam/inference/Ordering.h>
|
||||
#include <gtsam/inference/MetisIndex.h>
|
||||
#include <gtsam/base/TestableAssertions.h>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
|
|
@ -78,7 +79,46 @@ TEST(Ordering, grouped_constrained_ordering) {
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(Ordering, metis_ordering) {
|
||||
TEST(Ordering, csr_format) {
|
||||
|
||||
|
||||
// Example in METIS manual
|
||||
SymbolicFactorGraph sfg;
|
||||
sfg.push_factor(0, 1);
|
||||
sfg.push_factor(1, 2);
|
||||
sfg.push_factor(2, 3);
|
||||
sfg.push_factor(3, 4);
|
||||
sfg.push_factor(5, 6);
|
||||
sfg.push_factor(6, 7);
|
||||
sfg.push_factor(7, 8);
|
||||
sfg.push_factor(8, 9);
|
||||
sfg.push_factor(10, 11);
|
||||
sfg.push_factor(11, 12);
|
||||
sfg.push_factor(12, 13);
|
||||
sfg.push_factor(13, 14);
|
||||
|
||||
sfg.push_factor(0, 5);
|
||||
sfg.push_factor(5, 10);
|
||||
sfg.push_factor(1, 6);
|
||||
sfg.push_factor(6, 11);
|
||||
sfg.push_factor(2, 7);
|
||||
sfg.push_factor(7, 12);
|
||||
sfg.push_factor(3, 8);
|
||||
sfg.push_factor(8, 13);
|
||||
sfg.push_factor(4, 9);
|
||||
sfg.push_factor(9, 14);
|
||||
|
||||
MetisIndex mi(sfg);
|
||||
|
||||
vector<int> xadjExpected{ 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44};
|
||||
vector<int> adjExpected{ 1, 5, 0, 2, 6, 1, 3, 7, 2, 4, 8, 3, 9, 0, 6, 10, 1, 5, 7, 11,
|
||||
2, 6, 8, 12, 3, 7, 9, 13, 4, 8, 14, 5, 11, 6, 10, 12, 7, 11,
|
||||
13, 8, 12, 14, 9, 13 };
|
||||
|
||||
EXPECT(xadjExpected == mi.xadj());
|
||||
EXPECT(adjExpected.size() == mi.adj().size());
|
||||
EXPECT( adjExpected == mi.adj());
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue