Ordering implementation, unit tests
parent
bf22a49504
commit
0771b1658b
|
@ -216,7 +216,6 @@ configure_file(gtsam/3rdparty/gtsam_eigen_includes.h.in gtsam/3rdparty/gtsam_eig
|
|||
# Install the configuration file for Eigen
|
||||
install(FILES ${PROJECT_BINARY_DIR}/gtsam/3rdparty/gtsam_eigen_includes.h DESTINATION include/gtsam/3rdparty)
|
||||
|
||||
|
||||
###############################################################################
|
||||
# Global compile options
|
||||
|
||||
|
|
|
@ -46,3 +46,4 @@ add_subdirectory("libmetis")
|
|||
if(GTSAM_BUILD_METIS_EXECUTABLES)
|
||||
add_subdirectory("programs")
|
||||
endif()
|
||||
|
||||
|
|
|
@ -14,3 +14,4 @@ install(TARGETS metis
|
|||
RUNTIME DESTINATION include/gtsam/3rdparty/metis/lib
|
||||
ARCHIVE DESTINATION include/gtsam/3rdparty/metis/lib)
|
||||
|
||||
|
||||
|
|
|
@ -19,7 +19,6 @@ set(gtsam_srcs)
|
|||
message(STATUS "Building 3rdparty")
|
||||
add_subdirectory(3rdparty)
|
||||
|
||||
# build convenience library
|
||||
set (3rdparty_srcs
|
||||
${eigen_headers} # Set by 3rdparty/CMakeLists.txt
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/CCOLAMD/Source/ccolamd.c
|
||||
|
@ -91,12 +90,12 @@ set(gtsam_version ${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSIO
|
|||
set(gtsam_soversion ${GTSAM_VERSION_MAJOR})
|
||||
message(STATUS "GTSAM Version: ${gtsam_version}")
|
||||
message(STATUS "Install prefix: ${CMAKE_INSTALL_PREFIX}")
|
||||
|
||||
message(STATUS "GTSAM Additional: ${GTSAM_ADDITIONAL_LIBRARIES}")
|
||||
# build shared and static versions of the library
|
||||
if (GTSAM_BUILD_STATIC_LIBRARY)
|
||||
message(STATUS "Building GTSAM - static")
|
||||
add_library(gtsam STATIC ${gtsam_srcs})
|
||||
target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} ${GTSAM_ADDITIONAL_LIBRARIES})
|
||||
target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} metis ${GTSAM_ADDITIONAL_LIBRARIES})
|
||||
set_target_properties(gtsam PROPERTIES
|
||||
OUTPUT_NAME gtsam
|
||||
CLEAN_DIRECT_OUTPUT 1
|
||||
|
@ -113,7 +112,7 @@ if (GTSAM_BUILD_STATIC_LIBRARY)
|
|||
else()
|
||||
message(STATUS "Building GTSAM - shared")
|
||||
add_library(gtsam SHARED ${gtsam_srcs})
|
||||
target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} ${GTSAM_ADDITIONAL_LIBRARIES})
|
||||
target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} metis ${GTSAM_ADDITIONAL_LIBRARIES})
|
||||
set_target_properties(gtsam PROPERTIES
|
||||
OUTPUT_NAME gtsam
|
||||
CLEAN_DIRECT_OUTPUT 1
|
||||
|
|
|
@ -15,15 +15,12 @@
|
|||
* @date Oct. 10, 2014
|
||||
*/
|
||||
|
||||
#include <gtsam/inference/MetisIndex.h>
|
||||
#pragma once
|
||||
|
||||
#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>
|
||||
|
@ -50,10 +47,13 @@ namespace gtsam {
|
|||
xadj_.push_back(0);// Always set the first index to zero
|
||||
for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) {
|
||||
vector<int> temp;
|
||||
// Copy from the FastSet into a temporary vector
|
||||
copy(adjMapIt->second.begin(), adjMapIt->second.end(), std::back_inserter(temp));
|
||||
// Insert each index's set in order by appending them to the end of adj_
|
||||
adj_.insert(adj_.end(), temp.begin(), temp.end());
|
||||
//adj_.push_back(temp);
|
||||
xadj_.push_back(adj_.size());
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#include <gtsam/base/types.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/inference/FactorGraph.h>
|
||||
|
||||
namespace gtsam {
|
||||
/**
|
||||
|
@ -56,7 +57,7 @@ public:
|
|||
MetisIndex(const FG& factorGraph) : nFactors_(0), nValues_(0) {
|
||||
augment(factorGraph); }
|
||||
|
||||
~MetisIndex();
|
||||
~MetisIndex(){}
|
||||
/// @}
|
||||
/// @name Advanced Interface
|
||||
/// @{
|
||||
|
@ -68,11 +69,12 @@ public:
|
|||
template<class FACTOR>
|
||||
void augment(const FactorGraph<FACTOR>& factors);
|
||||
|
||||
std::vector<int> xadj() const;
|
||||
std::vector<int> adj() const;
|
||||
std::vector<int> xadj() const { return xadj_; }
|
||||
std::vector<int> adj() const { return adj_; }
|
||||
|
||||
/// @}
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#include <gtsam/inference/MetisIndex-inl.h>
|
||||
|
|
|
@ -199,19 +199,27 @@ namespace gtsam {
|
|||
|
||||
|
||||
/* ************************************************************************* */
|
||||
template<class FACTOR>
|
||||
Ordering Ordering::METIS(const FactorGraph<FACTOR>& graph)
|
||||
Ordering Ordering::METIS(const MetisIndex& met)
|
||||
{
|
||||
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
|
||||
|
||||
vector<int> xadj = met.xadj();
|
||||
vector<int> adj = met.adj();
|
||||
|
||||
vector<int> perm, iperm;
|
||||
int outputError;
|
||||
idx_t size = xadj.size();
|
||||
outputError = METIS_NodeND(&size, xadj.data(), adj.data(), NULL, NULL, perm.data(), iperm.data());
|
||||
Ordering result;
|
||||
|
||||
if (outputError != METIS_OK)
|
||||
{
|
||||
std::cout << "METIS ordering error!\n";
|
||||
return result;
|
||||
}
|
||||
|
||||
|
||||
//METIS_NodeND(graph.keys().size(), xadj, adj);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
#include <gtsam/base/FastSet.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/inference/VariableIndex.h>
|
||||
#include <gtsam/inference/MetisIndex.h>
|
||||
#include <gtsam/inference/FactorGraph.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -151,10 +152,13 @@ namespace gtsam {
|
|||
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 MetisIndex& met);
|
||||
|
||||
template<class FACTOR>
|
||||
static GTSAM_EXPORT Ordering METIS(const FactorGraph<FACTOR>& graph);
|
||||
static GTSAM_EXPORT Ordering METIS(const FactorGraph<FACTOR>& graph)
|
||||
{
|
||||
return METIS(MetisIndex(graph));
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -80,8 +80,6 @@ TEST(Ordering, grouped_constrained_ordering) {
|
|||
|
||||
/* ************************************************************************* */
|
||||
TEST(Ordering, csr_format) {
|
||||
|
||||
|
||||
// Example in METIS manual
|
||||
SymbolicFactorGraph sfg;
|
||||
sfg.push_factor(0, 1);
|
||||
|
@ -118,10 +116,18 @@ TEST(Ordering, csr_format) {
|
|||
EXPECT(xadjExpected == mi.xadj());
|
||||
EXPECT(adjExpected.size() == mi.adj().size());
|
||||
EXPECT( adjExpected == mi.adj());
|
||||
|
||||
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
TEST(Ordering, metis) {
|
||||
|
||||
SymbolicFactorGraph sfg;
|
||||
sfg.push_factor(0, 1);
|
||||
sfg.push_factor(1, 2);
|
||||
sfg.push_factor(2, 3);
|
||||
sfg.push_factor(3, 4);
|
||||
|
||||
Ordering::METIS(sfg);
|
||||
}
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
|
||||
/* ************************************************************************* */
|
||||
|
|
Loading…
Reference in New Issue