From f447481844a884a51cd7f6a5aa57063634fa246e Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 3 Oct 2014 12:18:42 -0400 Subject: [PATCH 01/32] initial stub for metis ordering --- gtsam/inference/Ordering.cpp | 7 +++++++ gtsam/inference/Ordering.h | 8 ++++++++ gtsam/inference/tests/testOrdering.cpp | 5 +++++ 3 files changed, 20 insertions(+) diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 4f4b14bb5..7d3d7cc0b 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -22,6 +22,7 @@ #include #include +#include using namespace std; @@ -196,6 +197,12 @@ namespace gtsam { return Ordering::COLAMDConstrained(variableIndex, cmember); } + /* ************************************************************************* */ + Ordering Ordering::METIS(const VariableIndex& variableIndex) + { + gttic(Ordering_METIS); + } + /* ************************************************************************* */ void Ordering::print(const std::string& str, const KeyFormatter& keyFormatter) const { diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 7b1a2bb2e..1260c15fb 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -146,6 +146,14 @@ namespace gtsam { return Ordering(keys); } + + /// Compute an ordering determined by METIS from a VariableIndex + static GTSAM_EXPORT Ordering METIS(const VariableIndex& variableIndex); + + template + static Ordering METIS(const FactorGraph& graph){ + return METIS(VariableIndex(graph)); } + /// @} /// @name Testable @{ diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 3bf6f7ca0..5fcac15b4 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -77,6 +77,11 @@ TEST(Ordering, grouped_constrained_ordering) { EXPECT(assert_equal(expConstrained, actConstrained)); } +/* ************************************************************************* */ +TEST(Ordering, metis_ordering) { + +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From bf22a49504749af3a1b33faa21fd11346b9e5aae Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 13 Oct 2014 13:15:05 -0400 Subject: [PATCH 02/32] Working ordering format for Metis_NodeND --- gtsam/inference/MetisIndex-inl.h | 59 +++++++++++++++++++ gtsam/inference/MetisIndex.cpp | 0 gtsam/inference/MetisIndex.h | 78 ++++++++++++++++++++++++++ gtsam/inference/Ordering.cpp | 13 ++++- gtsam/inference/Ordering.h | 9 ++- gtsam/inference/tests/testOrdering.cpp | 42 +++++++++++++- 6 files changed, 196 insertions(+), 5 deletions(-) create mode 100644 gtsam/inference/MetisIndex-inl.h create mode 100644 gtsam/inference/MetisIndex.cpp create mode 100644 gtsam/inference/MetisIndex.h diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h new file mode 100644 index 000000000..35d8c00fc --- /dev/null +++ b/gtsam/inference/MetisIndex-inl.h @@ -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 +#include + +namespace gtsam { + + MetisIndex::~MetisIndex(){} + + std::vector MetisIndex::xadj() const { return xadj_; } + std::vector MetisIndex::adj() const { return adj_; } + + /* ************************************************************************* */ + template + void MetisIndex::augment(const FactorGraph& factors) + { + std::map > adjMap; + std::map >::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 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()); + } + } +} diff --git a/gtsam/inference/MetisIndex.cpp b/gtsam/inference/MetisIndex.cpp new file mode 100644 index 000000000..e69de29bb diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h new file mode 100644 index 000000000..57b999d7d --- /dev/null +++ b/gtsam/inference/MetisIndex.h @@ -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 +#include + +#include +#include +#include +#include + +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 shared_ptr; + +private: + FastVector xadj_; // Index of node's adjacency list in adj + FastVector 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 + 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 + void augment(const FactorGraph& factors); + + std::vector xadj() const; + std::vector adj() const; + + /// @} +}; +} + +#include diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 7d3d7cc0b..33cf2092d 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -197,10 +197,21 @@ namespace gtsam { return Ordering::COLAMDConstrained(variableIndex, cmember); } + /* ************************************************************************* */ - Ordering Ordering::METIS(const VariableIndex& variableIndex) + template + Ordering Ordering::METIS(const FactorGraph& 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); + } /* ************************************************************************* */ diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 1260c15fb..fad9fe9e9 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -146,13 +146,15 @@ namespace gtsam { return Ordering(keys); } + /// METIS Formatting function + template + static GTSAM_EXPORT void CSRFormat(std::vector& xadj, std::vector& adj, const FactorGraph& 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 - static Ordering METIS(const FactorGraph& graph){ - return METIS(VariableIndex(graph)); } + static GTSAM_EXPORT Ordering METIS(const FactorGraph& graph); /// @} @@ -169,6 +171,7 @@ namespace gtsam { static GTSAM_EXPORT Ordering COLAMDConstrained( const VariableIndex& variableIndex, std::vector& cmember); + /** Serialization function */ friend class boost::serialization::access; template diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 5fcac15b4..252106f88 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -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 xadjExpected{ 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44}; + vector 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()); + } From 0771b1658b468b5caf31de6dcff96da13a63d663 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 14 Oct 2014 15:18:05 -0400 Subject: [PATCH 03/32] Ordering implementation, unit tests --- CMakeLists.txt | 1 - gtsam/3rdparty/metis-5.1.0/CMakeLists.txt | 1 + .../metis-5.1.0/libmetis/CMakeLists.txt | 1 + gtsam/CMakeLists.txt | 7 +++-- gtsam/inference/MetisIndex-inl.h | 10 +++---- gtsam/inference/MetisIndex.h | 8 +++--- gtsam/inference/Ordering.cpp | 26 ++++++++++++------- gtsam/inference/Ordering.h | 8 ++++-- gtsam/inference/tests/testOrdering.cpp | 14 +++++++--- 9 files changed, 48 insertions(+), 28 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6fcce54b6..ba159c8e9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 diff --git a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt index 93c546be8..d3f2f1b0f 100644 --- a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt @@ -46,3 +46,4 @@ add_subdirectory("libmetis") if(GTSAM_BUILD_METIS_EXECUTABLES) add_subdirectory("programs") endif() + diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt index 66cfcba4a..df67d26b4 100644 --- a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt @@ -14,3 +14,4 @@ install(TARGETS metis RUNTIME DESTINATION include/gtsam/3rdparty/metis/lib ARCHIVE DESTINATION include/gtsam/3rdparty/metis/lib) + diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 9fac3b00b..ced644545 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -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 diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 35d8c00fc..356118dbb 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -15,15 +15,12 @@ * @date Oct. 10, 2014 */ -#include +#pragma once + #include namespace gtsam { - MetisIndex::~MetisIndex(){} - - std::vector MetisIndex::xadj() const { return xadj_; } - std::vector MetisIndex::adj() const { return adj_; } /* ************************************************************************* */ template @@ -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 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()); } } + } diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 57b999d7d..bcc9fc23f 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -25,6 +25,7 @@ #include #include #include +#include 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 void augment(const FactorGraph& factors); - std::vector xadj() const; - std::vector adj() const; + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } /// @} }; + } #include diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 33cf2092d..d8c590361 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -199,19 +199,27 @@ namespace gtsam { /* ************************************************************************* */ - template - Ordering Ordering::METIS(const FactorGraph& 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 xadj = met.xadj(); + vector adj = met.adj(); + + vector 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; } /* ************************************************************************* */ diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index fad9fe9e9..86038b028 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -24,6 +24,7 @@ #include #include #include +#include #include namespace gtsam { @@ -151,10 +152,13 @@ namespace gtsam { static GTSAM_EXPORT void CSRFormat(std::vector& xadj, std::vector& adj, const FactorGraph& 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 - static GTSAM_EXPORT Ordering METIS(const FactorGraph& graph); + static GTSAM_EXPORT Ordering METIS(const FactorGraph& graph) + { + return METIS(MetisIndex(graph)); + } /// @} diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 252106f88..22c86e191 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -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); } /* ************************************************************************* */ From ad74a4b8c9bbb01190862992b54859c6ca3728b3 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 14 Oct 2014 19:14:59 -0400 Subject: [PATCH 04/32] Update ms_stdint.h in metis. Export libraries correctly --- CMakeLists.txt | 10 ++- gtsam/3rdparty/CMakeLists.txt | 6 +- gtsam/3rdparty/metis-5.1.0/CMakeLists.txt | 2 + gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h | 81 ++++++++++++++----- .../metis-5.1.0/libmetis/CMakeLists.txt | 3 + gtsam/CMakeLists.txt | 48 ++++++----- gtsam/inference/Ordering.h | 2 +- 7 files changed, 101 insertions(+), 51 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ba159c8e9..951a0ec7e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -53,7 +53,7 @@ option(GTSAM_BUILD_STATIC_LIBRARY "Build a static gtsam library, instead option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF) option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF) option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." OFF) -option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) +option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF) option(GTSAM_WITH_TBB "Use Intel Threaded Building Blocks (TBB) if available" ON) option(GTSAM_WITH_EIGEN_MKL "Eigen will use Intel MKL if available" ON) option(GTSAM_WITH_EIGEN_MKL_OPENMP "Eigen, when using Intel MKL, will also use OpenMP for multithreading if available" ON) @@ -197,13 +197,13 @@ set(GTSAM_USE_SYSTEM_EIGEN OFF) if(GTSAM_USE_SYSTEM_EIGEN) # Use generic Eigen include paths e.g. set(GTSAM_EIGEN_INCLUDE_PREFIX "") - + find_package(Eigen3 REQUIRED) include_directories(AFTER "${EIGEN3_INCLUDE_DIR}") else() # Use bundled Eigen include paths e.g. set(GTSAM_EIGEN_INCLUDE_PREFIX "gtsam/3rdparty/Eigen/") - + # Clear any variables set by FindEigen3 if(EIGEN3_INCLUDE_DIR) set(EIGEN3_INCLUDE_DIR NOTFOUND CACHE STRING "" FORCE) @@ -262,7 +262,7 @@ include_directories(BEFORE ${Boost_INCLUDE_DIR}) # paths so that the compiler uses GTSAM headers in our source directory instead # of any previously installed GTSAM headers. include_directories(BEFORE - gtsam/3rdparty/UFconfig + gtsam/3rdparty/UFconfig gtsam/3rdparty/CCOLAMD/Include gtsam/3rdparty/metis-5.1.0/include gtsam/3rdparty/metis-5.1.0/libmetis @@ -322,8 +322,10 @@ endif(GTSAM_BUILD_UNSTABLE) # Install config and export files GtsamMakeConfigFile(GTSAM "${CMAKE_CURRENT_SOURCE_DIR}/gtsam_extra.cmake.in") +message("GTSAM export: ${GTSAM_EXPORTED_TARGETS}") export(TARGETS ${GTSAM_EXPORTED_TARGETS} FILE GTSAM-exports.cmake) + # Check for doxygen availability - optional dependency find_package(Doxygen) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 576da93bd..38c084e25 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -18,7 +18,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) # do the same for the unsupported eigen folder file(GLOB_RECURSE unsupported_eigen_headers "${CMAKE_CURRENT_SOURCE_DIR}/Eigen/unsupported/Eigen/*.h") - + file(GLOB unsupported_eigen_dir_headers_all "Eigen/unsupported/Eigen/*") foreach(unsupported_eigen_dir ${unsupported_eigen_dir_headers_all}) get_filename_component(filename ${unsupported_eigen_dir} NAME) @@ -36,7 +36,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) install(DIRECTORY Eigen/Eigen DESTINATION include/gtsam/3rdparty/Eigen FILES_MATCHING PATTERN "*.h") - + install(DIRECTORY Eigen/unsupported/Eigen DESTINATION include/gtsam/3rdparty/Eigen/unsupported/ FILES_MATCHING PATTERN "*.h") @@ -73,3 +73,5 @@ endif() if(GTSAM_INSTALL_GEOGRAPHICLIB) add_subdirectory(GeographicLib) endif() + +set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) diff --git a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt index d3f2f1b0f..fd9c7eaf7 100644 --- a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt @@ -47,3 +47,5 @@ if(GTSAM_BUILD_METIS_EXECUTABLES) add_subdirectory("programs") endif() +set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) + diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h b/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h index 7e200dc6f..39b8aed9d 100644 --- a/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h +++ b/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h @@ -1,7 +1,7 @@ // ISO C9x compliant stdint.h for Microsoft Visual Studio // Based on ISO/IEC 9899:TC2 Committee draft (May 6, 2005) WG14/N1124 // -// Copyright (c) 2006 Alexander Chemeris +// Copyright (c) 2006-2013 Alexander Chemeris // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are met: @@ -13,8 +13,9 @@ // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // -// 3. The name of the author may be used to endorse or promote products -// derived from this software without specific prior written permission. +// 3. Neither the name of the product nor the names of its contributors may +// be used to endorse or promote products derived from this software +// without specific prior written permission. // // THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED // WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF @@ -40,30 +41,59 @@ #pragma once #endif +#if _MSC_VER >= 1600 // [ +#include +#else // ] _MSC_VER >= 1600 [ + #include -// For Visual Studio 6 in C++ mode wrap include with 'extern "C++" {}' +// For Visual Studio 6 in C++ mode and for many Visual Studio versions when +// compiling for ARM we should wrap include with 'extern "C++" {}' // or compiler give many errors like this: // error C2733: second C linkage of overloaded function 'wmemchr' not allowed -#if (_MSC_VER < 1300) && defined(__cplusplus) - extern "C++" { -#endif -# include -#if (_MSC_VER < 1300) && defined(__cplusplus) - } +#ifdef __cplusplus +extern "C" { #endif +# include +#ifdef __cplusplus +} +#endif + +// Define _W64 macros to mark types changing their size, like intptr_t. +#ifndef _W64 +# if !defined(__midl) && (defined(_X86_) || defined(_M_IX86)) && _MSC_VER >= 1300 +# define _W64 __w64 +# else +# define _W64 +# endif +#endif + // 7.18.1 Integer types // 7.18.1.1 Exact-width integer types -typedef __int8 int8_t; -typedef __int16 int16_t; -typedef __int32 int32_t; -typedef __int64 int64_t; + +// Visual Studio 6 and Embedded Visual C++ 4 doesn't +// realize that, e.g. char has the same size as __int8 +// so we give up on __intX for them. +#if (_MSC_VER < 1300) +typedef signed char int8_t; +typedef signed short int16_t; +typedef signed int int32_t; +typedef unsigned char uint8_t; +typedef unsigned short uint16_t; +typedef unsigned int uint32_t; +#else +typedef signed __int8 int8_t; +typedef signed __int16 int16_t; +typedef signed __int32 int32_t; typedef unsigned __int8 uint8_t; typedef unsigned __int16 uint16_t; typedef unsigned __int32 uint32_t; -typedef unsigned __int64 uint64_t; +#endif +typedef signed __int64 int64_t; +typedef unsigned __int64 uint64_t; + // 7.18.1.2 Minimum-width integer types typedef int8_t int_least8_t; @@ -87,11 +117,11 @@ typedef uint64_t uint_fast64_t; // 7.18.1.4 Integer types capable of holding object pointers #ifdef _WIN64 // [ - typedef __int64 intptr_t; - typedef unsigned __int64 uintptr_t; +typedef signed __int64 intptr_t; +typedef unsigned __int64 uintptr_t; #else // _WIN64 ][ - typedef int intptr_t; - typedef unsigned int uintptr_t; +typedef _W64 signed int intptr_t; +typedef _W64 unsigned int uintptr_t; #endif // _WIN64 ] // 7.18.1.5 Greatest-width integer types @@ -213,10 +243,17 @@ typedef uint64_t uintmax_t; #define UINT64_C(val) val##ui64 // 7.18.4.2 Macros for greatest-width integer constants -#define INTMAX_C INT64_C -#define UINTMAX_C UINT64_C +// These #ifndef's are needed to prevent collisions with . +// Check out Issue 9 for the details. +#ifndef INTMAX_C // [ +# define INTMAX_C INT64_C +#endif // INTMAX_C ] +#ifndef UINTMAX_C // [ +# define UINTMAX_C UINT64_C +#endif // UINTMAX_C ] #endif // __STDC_CONSTANT_MACROS ] +#endif // _MSC_VER >= 1600 ] -#endif // _MSC_STDINT_H_ ] +#endif // _MSC_STDINT_H_ ] \ No newline at end of file diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt index df67d26b4..a18973427 100644 --- a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt @@ -14,4 +14,7 @@ install(TARGETS metis RUNTIME DESTINATION include/gtsam/3rdparty/metis/lib ARCHIVE DESTINATION include/gtsam/3rdparty/metis/lib) +install(TARGETS metis EXPORT GTSAM-exports ARCHIVE DESTINATION lib) +list(APPEND GTSAM_EXPORTED_TARGETS metis) +set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index ced644545..2d5706f33 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -1,14 +1,14 @@ # We split the library in to separate subfolders, each containing # tests, timing, and an optional convenience library. # The following variable is the master list of subdirs to add -set (gtsam_subdirs - base - geometry - inference - symbolic - discrete - linear - nonlinear +set (gtsam_subdirs + base + geometry + inference + symbolic + discrete + linear + nonlinear slam navigation ) @@ -16,12 +16,12 @@ set (gtsam_subdirs set(gtsam_srcs) # Build 3rdparty separately -message(STATUS "Building 3rdparty") +message(STATUS "Building 3rdparty") add_subdirectory(3rdparty) -set (3rdparty_srcs +set (3rdparty_srcs ${eigen_headers} # Set by 3rdparty/CMakeLists.txt - ${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/CCOLAMD/Source/ccolamd.c + ${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/CCOLAMD/Source/ccolamd.c ${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/CCOLAMD/Source/ccolamd_global.c ${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/UFconfig/UFconfig.c) gtsam_assign_source_folders("${3rdparty_srcs}") # Create MSVC structure @@ -36,7 +36,7 @@ set (excluded_sources #"") set (excluded_headers #"") "${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.h" ) - + if(GTSAM_USE_QUATERNIONS) set(excluded_sources ${excluded_sources} "${CMAKE_CURRENT_SOURCE_DIR}/geometry/Rot3M.cpp") else() @@ -58,10 +58,10 @@ foreach(subdir ${gtsam_subdirs}) set(${subdir}_srcs ${subdir_srcs}) # Build local library and tests - message(STATUS "Building ${subdir}") + message(STATUS "Building ${subdir}") add_subdirectory(${subdir}) endforeach(subdir) - + # To add additional sources to gtsam when building the full library (static or shared) # Add the subfolder with _srcs appended to the end to this list set(gtsam_srcs @@ -77,7 +77,7 @@ set(gtsam_srcs ${navigation_srcs} ${gtsam_core_headers} ) - + # Generate and install config and dllexport files configure_file(config.h.in config.h) set(library_name GTSAM) # For substitution in dllexport.h.in @@ -85,18 +85,22 @@ configure_file("${PROJECT_SOURCE_DIR}/cmake/dllexport.h.in" "dllexport.h") list(APPEND gtsam_srcs "${PROJECT_BINARY_DIR}/gtsam/config.h" "${PROJECT_BINARY_DIR}/gtsam/dllexport.h") install(FILES "${PROJECT_BINARY_DIR}/gtsam/config.h" "${PROJECT_BINARY_DIR}/gtsam/dllexport.h" DESTINATION include/gtsam) +list(APPEND GTSAM_ADDITIONAL_LIBRARIES metis) + # Versions set(gtsam_version ${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}) 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}") +message("GTSAM Additional: ${GTSAM_ADDITIONAL_LIBRARIES}") +message("GTSAM Exports: ${GTSAM_EXPORTED_TARGETS}") + # 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} metis ${GTSAM_ADDITIONAL_LIBRARIES}) - set_target_properties(gtsam PROPERTIES + target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} ${GTSAM_ADDITIONAL_LIBRARIES}) + set_target_properties(gtsam PROPERTIES OUTPUT_NAME gtsam CLEAN_DIRECT_OUTPUT 1 VERSION ${gtsam_version} @@ -112,8 +116,8 @@ if (GTSAM_BUILD_STATIC_LIBRARY) else() message(STATUS "Building GTSAM - shared") add_library(gtsam SHARED ${gtsam_srcs}) - target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} metis ${GTSAM_ADDITIONAL_LIBRARIES}) - set_target_properties(gtsam PROPERTIES + target_link_libraries(gtsam ${GTSAM_BOOST_LIBRARIES} ${GTSAM_ADDITIONAL_LIBRARIES}) + set_target_properties(gtsam PROPERTIES OUTPUT_NAME gtsam CLEAN_DIRECT_OUTPUT 1 VERSION ${gtsam_version} @@ -134,7 +138,7 @@ set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/slam/dataset.cpp" APPEND PROPERTY COMPILE_DEFINITIONS "SOURCE_TREE_DATASET_DIR=\"${PROJECT_SOURCE_DIR}/examples/Data\"" "INSTALLED_DATASET_DIR=\"${GTSAM_TOOLBOX_INSTALL_PATH}/gtsam_examples/Data\"") - + # Special cases if(MSVC) set_property(SOURCE @@ -147,7 +151,7 @@ endif() if (GTSAM_INSTALL_MATLAB_TOOLBOX) # Set up codegen include(GtsamMatlabWrap) - + # Generate, build and install toolbox set(mexFlags "${GTSAM_BUILD_MEX_BINARY_FLAGS}") if(GTSAM_BUILD_STATIC_LIBRARY) diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 86038b028..45f53f2ad 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -155,7 +155,7 @@ namespace gtsam { static GTSAM_EXPORT Ordering METIS(const MetisIndex& met); template - static GTSAM_EXPORT Ordering METIS(const FactorGraph& graph) + static Ordering METIS(const FactorGraph& graph) { return METIS(MetisIndex(graph)); } From 99caf8833a29a694fefe1b74841e491cc2d761bc Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 14 Oct 2014 23:46:12 -0400 Subject: [PATCH 05/32] Finished ordering implementation --- gtsam/inference/Ordering.cpp | 18 ++++++++++++++---- gtsam/inference/tests/testOrdering.cpp | 11 +++++------ 2 files changed, 19 insertions(+), 10 deletions(-) diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index d8c590361..99b116009 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -207,18 +207,28 @@ namespace gtsam { vector adj = met.adj(); vector perm, iperm; + + idx_t size = xadj.size() - 1; + for (int i = 0; i < size; i++) + { + perm.push_back(0); + iperm.push_back(0); + } + int outputError; - idx_t size = xadj.size(); - outputError = METIS_NodeND(&size, xadj.data(), adj.data(), NULL, NULL, perm.data(), iperm.data()); + + outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); Ordering result; if (outputError != METIS_OK) { - std::cout << "METIS ordering error!\n"; + std::cout << "METIS failed during Nested Dissection ordering!\n"; return result; } - + result.resize(size); + for (size_t j = 0; j < size; ++j) + result[j] = perm[j]; return result; } diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 22c86e191..90e1cbe66 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -119,14 +119,13 @@ TEST(Ordering, csr_format) { } /* ************************************************************************* */ 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); + sfg.push_factor(0, 1); + sfg.push_factor(1, 2); + + Ordering metis = Ordering::METIS(sfg); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } From 103ec596d7d840418c5c338ab525775bcca6c193 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Wed, 15 Oct 2014 00:03:57 -0400 Subject: [PATCH 06/32] Remove empty file and some code cleanup --- gtsam/inference/MetisIndex.cpp | 0 gtsam/inference/Ordering.cpp | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) delete mode 100644 gtsam/inference/MetisIndex.cpp diff --git a/gtsam/inference/MetisIndex.cpp b/gtsam/inference/MetisIndex.cpp deleted file mode 100644 index e69de29bb..000000000 diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 99b116009..685bbcd0d 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -209,7 +209,7 @@ namespace gtsam { vector perm, iperm; idx_t size = xadj.size() - 1; - for (int i = 0; i < size; i++) + for (idx_t i = 0; i < size; i++) { perm.push_back(0); iperm.push_back(0); From 8cd17f6a3065a221fe1f67f2eb45c192076a1a8d Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 17 Oct 2014 15:50:13 -0400 Subject: [PATCH 07/32] Updating nonlinear params to allow selection of orderings --- gtsam/inference/Ordering.cpp | 1 + gtsam/inference/Ordering.h | 1 + gtsam/inference/tests/testOrdering.cpp | 1 + gtsam/nonlinear/NonlinearOptimizerParams.cpp | 43 ++++++++++++++++++-- gtsam/nonlinear/NonlinearOptimizerParams.h | 27 ++++++++++-- 5 files changed, 66 insertions(+), 7 deletions(-) diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 685bbcd0d..fbda41ac0 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -12,6 +12,7 @@ /** * @file Ordering.cpp * @author Richard Roberts + * @author Andrew Melim * @date Sep 2, 2010 */ diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 45f53f2ad..6cf125551 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -12,6 +12,7 @@ /** * @file Ordering.h * @author Richard Roberts + * @author Andrew Melim * @date Sep 2, 2010 */ diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 90e1cbe66..b769551bf 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -12,6 +12,7 @@ /** * @file testOrdering * @author Alex Cunningham + * @author Andrew Melim */ #include diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index ef0f2aa9b..f20a36b5d 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -107,10 +107,17 @@ void NonlinearOptimizerParams::print(const std::string& str) const { break; } - if (ordering) - std::cout << " ordering: custom\n"; - else - std::cout << " ordering: COLAMD\n"; + switch (orderingType){ + case COLAMD: + std::cout << " ordering: COLAMD\n"; + break; + case METIS: + std::cout << " ordering: METIS\n"; + break; + default: + std::cout << " ordering: custom\n"; + break; + } std::cout.flush(); } @@ -155,6 +162,34 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve throw std::invalid_argument( "Unknown linear solver type in SuccessiveLinearizationOptimizer"); } + /* ************************************************************************* */ +std::string NonlinearOptimizerParams::orderingTypeTranslator(NonlinearOptimizerParams::OrderingType type) const +{ + switch (type) { + case METIS: + return "METIS"; + case COLAMD: + return "COLAMD"; + default: + if (ordering) + return "CUSTOM"; + else + throw std::invalid_argument( + "Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering"); + } +} + +/* ************************************************************************* */ +NonlinearOptimizerParams::OrderingType NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const +{ + if (type == "METIS") + return METIS; + if (type == "COLAMD") + return COLAMD; + throw std::invalid_argument( + "Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering"); +} + } // namespace diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index dafc1f065..a390555e2 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -37,15 +37,21 @@ public: SILENT, TERMINATION, ERROR, VALUES, DELTA, LINEAR }; + /** See NonlinearOptimizer::orderingType */ + enum OrderingType { + COLAMD, METIS, CUSTOM + }; + int maxIterations; ///< The maximum iterations to stop iterating (default 100) double relativeErrorTol; ///< The maximum relative error decrease to stop iterating (default 1e-5) double absoluteErrorTol; ///< The maximum absolute error decrease to stop iterating (default 1e-5) double errorTol; ///< The maximum total error to stop iterating (default 0.0) Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) + OrderingType orderingType; ///< The method of ordering use during variable elimination (default COLAMD) NonlinearOptimizerParams() : maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol( - 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY) { + 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(COLAMD) { } virtual ~NonlinearOptimizerParams() { @@ -152,12 +158,27 @@ public: void setOrdering(const Ordering& ordering) { this->ordering = ordering; + this->orderingType = CUSTOM; + } + + std::string getOrderingType() const { + return orderingTypeTranslator(orderingType); + } + + // Note that if you want to use a custom ordering, you must set the ordering directly, this will switch to custom type + void setOrderingType(const std::string& ordering){ + orderingType = orderingTypeTranslator(ordering); } private: std::string linearSolverTranslator(LinearSolverType linearSolverType) const; - LinearSolverType linearSolverTranslator( - const std::string& linearSolverType) const; + + LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; + + std::string orderingTypeTranslator(OrderingType type) const; + + OrderingType orderingTypeTranslator(const std::string& type) const; + }; // For backward compatibility: From 1d7bcb301a08725b74ebcee5e10a56e71e5741d1 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 20 Oct 2014 18:58:15 -0400 Subject: [PATCH 08/32] Ordering type enum --- gtsam/inference/Ordering.h | 6 ++++++ gtsam/nonlinear/NonlinearOptimizerParams.cpp | 17 +++++++++-------- gtsam/nonlinear/NonlinearOptimizerParams.h | 16 ++++++---------- 3 files changed, 21 insertions(+), 18 deletions(-) diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 6cf125551..dfb1deb0e 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -37,6 +37,12 @@ namespace gtsam { typedef Ordering This; ///< Typedef to this class typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class + /** See NonlinearOptimizer::orderingType */ + enum Type { + COLAMD_, METIS_, CUSTOM_ // Add underscores to prevent declaration errors + }; + + /// Create an empty ordering GTSAM_EXPORT Ordering() {} diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index f20a36b5d..1e964a481 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -5,6 +5,7 @@ * @author Yong-Dian Jian * @author Richard Roberts * @author Frank Dellaert + * @author Andrew Melim */ #include @@ -108,10 +109,10 @@ void NonlinearOptimizerParams::print(const std::string& str) const { } switch (orderingType){ - case COLAMD: + case Ordering::Type::COLAMD_: std::cout << " ordering: COLAMD\n"; break; - case METIS: + case Ordering::Type::METIS_: std::cout << " ordering: METIS\n"; break; default: @@ -164,12 +165,12 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve } /* ************************************************************************* */ -std::string NonlinearOptimizerParams::orderingTypeTranslator(NonlinearOptimizerParams::OrderingType type) const +std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type) const { switch (type) { - case METIS: + case Ordering::Type::METIS_: return "METIS"; - case COLAMD: + case Ordering::Type::COLAMD_: return "COLAMD"; default: if (ordering) @@ -181,12 +182,12 @@ std::string NonlinearOptimizerParams::orderingTypeTranslator(NonlinearOptimizerP } /* ************************************************************************* */ -NonlinearOptimizerParams::OrderingType NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const +Ordering::Type NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const { if (type == "METIS") - return METIS; + return Ordering::Type::METIS_; if (type == "COLAMD") - return COLAMD; + return Ordering::Type::COLAMD_; throw std::invalid_argument( "Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering"); } diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index a390555e2..04877c72e 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -15,6 +15,7 @@ * @author Yong-Dian Jian * @author Richard Roberts * @author Frank Dellaert + * @author Andrew Melim * @date Apr 1, 2012 */ @@ -37,21 +38,16 @@ public: SILENT, TERMINATION, ERROR, VALUES, DELTA, LINEAR }; - /** See NonlinearOptimizer::orderingType */ - enum OrderingType { - COLAMD, METIS, CUSTOM - }; - int maxIterations; ///< The maximum iterations to stop iterating (default 100) double relativeErrorTol; ///< The maximum relative error decrease to stop iterating (default 1e-5) double absoluteErrorTol; ///< The maximum absolute error decrease to stop iterating (default 1e-5) double errorTol; ///< The maximum total error to stop iterating (default 0.0) Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) - OrderingType orderingType; ///< The method of ordering use during variable elimination (default COLAMD) + Ordering::Type orderingType; ///< The method of ordering use during variable elimination (default COLAMD) NonlinearOptimizerParams() : maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol( - 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(COLAMD) { + 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(Ordering::Type::COLAMD_) { } virtual ~NonlinearOptimizerParams() { @@ -158,7 +154,7 @@ public: void setOrdering(const Ordering& ordering) { this->ordering = ordering; - this->orderingType = CUSTOM; + this->orderingType = Ordering::Type::CUSTOM_; } std::string getOrderingType() const { @@ -175,9 +171,9 @@ private: LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; - std::string orderingTypeTranslator(OrderingType type) const; + std::string orderingTypeTranslator(Ordering::Type type) const; - OrderingType orderingTypeTranslator(const std::string& type) const; + Ordering::Type orderingTypeTranslator(const std::string& type) const; }; From 81dfa6fe0ad27d39903654a578e05a4276541cd7 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 21 Oct 2014 01:34:47 -0400 Subject: [PATCH 09/32] Adding METIS ordering logic to elimination --- .../inference/EliminateableFactorGraph-inst.h | 20 +++++++++++++------ gtsam/inference/EliminateableFactorGraph.h | 13 ++++++++++-- gtsam/inference/MetisIndex-inl.h | 5 +++-- gtsam/nonlinear/NonlinearOptimizer.cpp | 3 ++- 4 files changed, 30 insertions(+), 11 deletions(-) diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index b64ebe259..0fe65e4c0 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -28,7 +28,8 @@ namespace gtsam { template boost::shared_ptr::BayesNetType> EliminateableFactorGraph::eliminateSequential( - OptionalOrdering ordering, const Eliminate& function, OptionalVariableIndex variableIndex) const + OptionalOrdering ordering, const Eliminate& function, + OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const { if(ordering && variableIndex) { gttic(eliminateSequential); @@ -47,13 +48,16 @@ namespace gtsam { // If no VariableIndex provided, compute one and call this function again IMPORTANT: we check // for no variable index first so that it's always computed if we need to call COLAMD because // no Ordering is provided. - return eliminateSequential(ordering, function, VariableIndex(asDerived())); + return eliminateSequential(ordering, function, VariableIndex(asDerived()), orderingType); } else /*if(!ordering)*/ { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - return eliminateSequential(Ordering::COLAMD(*variableIndex), function); + if (orderingType == Ordering::Type::METIS_) + return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + else + return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); } } @@ -61,7 +65,8 @@ namespace gtsam { template boost::shared_ptr::BayesTreeType> EliminateableFactorGraph::eliminateMultifrontal( - OptionalOrdering ordering, const Eliminate& function, OptionalVariableIndex variableIndex) const + OptionalOrdering ordering, const Eliminate& function, + OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const { if(ordering && variableIndex) { gttic(eliminateMultifrontal); @@ -81,13 +86,16 @@ namespace gtsam { // If no VariableIndex provided, compute one and call this function again IMPORTANT: we check // for no variable index first so that it's always computed if we need to call COLAMD because // no Ordering is provided. - return eliminateMultifrontal(ordering, function, VariableIndex(asDerived())); + return eliminateMultifrontal(ordering, function, VariableIndex(asDerived()), orderingType); } else /*if(!ordering)*/ { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function); + if (orderingType == Ordering::Type::METIS_) + return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + else + return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); } } diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index 717f49167..820bb2fd3 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -94,6 +94,9 @@ namespace gtsam { /// Typedef for an optional variable index as an argument to elimination functions typedef boost::optional OptionalVariableIndex; + /// Typedef for an optional ordering type + typedef boost::optional OptionalOrderingType; + /** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not * provided, the ordering provided by COLAMD will be used. * @@ -101,6 +104,10 @@ namespace gtsam { * \code * boost::shared_ptr result = graph.eliminateSequential(EliminateCholesky); * \endcode + * + * Example - METIS ordering for elimination + * \code + * boost::shared_ptr result = graph.eliminateSequential(Ordering::Type::METIS_); * * Example - Full QR elimination in specified order: * \code @@ -117,7 +124,8 @@ namespace gtsam { boost::shared_ptr eliminateSequential( OptionalOrdering ordering = boost::none, const Eliminate& function = EliminationTraitsType::DefaultEliminate, - OptionalVariableIndex variableIndex = boost::none) const; + OptionalVariableIndex variableIndex = boost::none, + OptionalOrderingType orderingType = boost::none) const; /** Do multifrontal elimination of all variables to produce a Bayes tree. If an ordering is not * provided, the ordering provided by COLAMD will be used. @@ -142,7 +150,8 @@ namespace gtsam { boost::shared_ptr eliminateMultifrontal( OptionalOrdering ordering = boost::none, const Eliminate& function = EliminationTraitsType::DefaultEliminate, - OptionalVariableIndex variableIndex = boost::none) const; + OptionalVariableIndex variableIndex = boost::none, + OptionalOrderingType orderingType = boost::none) const; /** Do sequential elimination of some variables, in \c ordering provided, to produce a Bayes net * and a remaining factor graph. This computes the factorization \f$ p(X) = p(A|B) p(B) \f$, diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 356118dbb..6da83b8bc 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -18,6 +18,7 @@ #pragma once #include +#include namespace gtsam { @@ -46,9 +47,9 @@ namespace gtsam { xadj_.push_back(0);// Always set the first index to zero for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { - vector temp; + std::vector temp; // Copy from the FastSet into a temporary vector - copy(adjMapIt->second.begin(), adjMapIt->second.end(), std::back_inserter(temp)); + std::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); diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index b4498bee4..eadfc5bb5 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -107,7 +107,8 @@ VectorValues NonlinearOptimizer::solve(const GaussianFactorGraph &gfg, delta = gfg.optimize(*params.ordering, params.getEliminationFunction()); } else if (params.isSequential()) { // Sequential QR or Cholesky (decided by params.getEliminationFunction()) - delta = gfg.eliminateSequential(*params.ordering, params.getEliminationFunction())->optimize(); + delta = gfg.eliminateSequential(*params.ordering, params.getEliminationFunction(), + boost::none, params.orderingType)->optimize(); } else if (params.isIterative()) { // Conjugate Gradient -> needs params.iterativeParams From 01f80c1fad2a2dc91eca53926fbe26f01e97bc07 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 21 Oct 2014 12:29:06 -0400 Subject: [PATCH 10/32] Correct installation of dll file for metis on windows --- gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt index a18973427..67c11e43e 100644 --- a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt @@ -9,12 +9,14 @@ if(UNIX) endif() -install(TARGETS metis - LIBRARY DESTINATION include/gtsam/3rdparty/metis/lib - RUNTIME DESTINATION include/gtsam/3rdparty/metis/lib - ARCHIVE DESTINATION include/gtsam/3rdparty/metis/lib) -install(TARGETS metis EXPORT GTSAM-exports ARCHIVE DESTINATION lib) +if(WIN32) + set_target_properties(metis PROPERTIES + PREFIX "" + RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin") +endif() +install(TARGETS metis EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) list(APPEND GTSAM_EXPORTED_TARGETS metis) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) + From 49d6b04eb8895eeb92e3e871b56a072a2c1c955d Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 21 Oct 2014 13:15:48 -0400 Subject: [PATCH 11/32] Metis ordering example --- examples/METISOrderingExample.cpp | 100 ++++++++++++++++++ .../metis-5.1.0/libmetis/CMakeLists.txt | 3 - 2 files changed, 100 insertions(+), 3 deletions(-) create mode 100644 examples/METISOrderingExample.cpp diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp new file mode 100644 index 000000000..145b8d5ca --- /dev/null +++ b/examples/METISOrderingExample.cpp @@ -0,0 +1,100 @@ +/* ---------------------------------------------------------------------------- + + * 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 METISOrdering.cpp + * @brief Simple robot motion example, with prior and two odometry measurements, using a METIS ordering + * @author Frank Dellaert + * @author Andrew Melim + */ + +/** + * Example of a simple 2D localization example + * - Robot poses are facing along the X axis (horizontal, to the right in 2D) + * - The robot moves 2 meters each step + * - We have full odometry between poses + */ + +// We will use Pose2 variables (x, y, theta) to represent the robot positions +#include + +// In GTSAM, measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. +// Here we will use Between factors for the relative motion described by odometry measurements. +// Also, we will initialize the robot at the origin using a Prior factor. +#include +#include + +// When the factors are created, we will add them to a Factor Graph. As the factors we are using +// are nonlinear factors, we will need a Nonlinear Factor Graph. +#include + +// Finally, once all of the factors have been added to our factor graph, we will want to +// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. +// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the +// Levenberg-Marquardt solver +#include + +// Once the optimized values have been calculated, we can also calculate the marginal covariance +// of desired variables +#include + +// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the +// nonlinear functions around an initial linearization point, then solve the linear system +// to update the linearization point. This happens repeatedly until the solver converges +// to a consistent set of variable values. This requires us to specify an initial guess +// for each variable, held in a Values container. +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char** argv) { + + // Create an empty nonlinear factor graph + NonlinearFactorGraph graph; + + // Add a prior on the first pose, setting it to the origin + // A prior factor consists of a mean and a noise model (covariance matrix) + Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin + noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.3, 0.3, 0.1)); + graph.add(PriorFactor(1, priorMean, priorNoise)); + + // Add odometry factors + Pose2 odometry(2.0, 0.0, 0.0); + // For simplicity, we will use the same noise model for each odometry factor + noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1)); + // Create odometry (Between) factors between consecutive poses + graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); + graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); + graph.print("\nFactor Graph:\n"); // print + + // Create the data structure to hold the initialEstimate estimate to the solution + // For illustrative purposes, these have been deliberately set to incorrect values + Values initial; + initial.insert(1, Pose2(0.5, 0.0, 0.2)); + initial.insert(2, Pose2(2.3, 0.1, -0.2)); + initial.insert(3, Pose2(4.1, 0.1, 0.1)); + initial.print("\nInitial Estimate:\n"); // print + + // optimize using Levenberg-Marquardt optimization + Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + result.print("Final Result:\n"); + + // Calculate and print marginal covariances for all variables + cout.precision(2); + Marginals marginals(graph, result); + cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; + cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; + cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; + + return 0; +} \ No newline at end of file diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt index 67c11e43e..ea3dd0298 100644 --- a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt @@ -8,8 +8,6 @@ if(UNIX) target_link_libraries(metis m) endif() - - if(WIN32) set_target_properties(metis PROPERTIES PREFIX "" @@ -19,4 +17,3 @@ endif() install(TARGETS metis EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) list(APPEND GTSAM_EXPORTED_TARGETS metis) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) - From a281240ff190998bb75f9bf0524d5372b8f9613b Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Tue, 21 Oct 2014 15:56:40 -0400 Subject: [PATCH 12/32] METIS ordering only works on values that are 0 indexed. Otherwise heap corruption occurs inside metis ordering function. Not sure how to fix/enforce --- examples/METISOrderingExample.cpp | 5 ++- .../inference/EliminateableFactorGraph-inst.h | 6 +-- gtsam/inference/MetisIndex-inl.h | 17 +++++--- gtsam/inference/MetisIndex.h | 1 + gtsam/inference/Ordering.cpp | 26 +++++------ gtsam/inference/tests/testOrdering.cpp | 43 +++++++++++++++++-- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 5 ++- gtsam/nonlinear/NonlinearOptimizerParams.h | 2 +- 8 files changed, 77 insertions(+), 28 deletions(-) diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp index 145b8d5ca..1b84364c0 100644 --- a/examples/METISOrderingExample.cpp +++ b/examples/METISOrderingExample.cpp @@ -86,7 +86,10 @@ int main(int argc, char** argv) { initial.print("\nInitial Estimate:\n"); // print // optimize using Levenberg-Marquardt optimization - Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + LevenbergMarquardtParams params; + params.orderingType = Ordering::Type::METIS_; + LevenbergMarquardtOptimizer optimizer(graph, initial, params); + Values result = optimizer.optimize(); result.print("Final Result:\n"); // Calculate and print marginal covariances for all variables diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index 0fe65e4c0..e14ba329b 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -55,9 +55,9 @@ namespace gtsam { // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. if (orderingType == Ordering::Type::METIS_) - return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType); - else - return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); + return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + else + return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); } } diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 6da83b8bc..08a0566a2 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -29,6 +29,7 @@ namespace gtsam { { std::map > adjMap; std::map >::iterator adjMapIt; + std::set values; /* ********** Convert to CSR format ********** */ // Assuming that vertex numbering starts from 0 (C style), @@ -37,13 +38,19 @@ namespace gtsam { // 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 + 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 + } + values.insert(values.end(), k1); // Keep a track of all unique values + } + } } + // Number of values referenced in this factorgraph + nValues_ = values.size(); xadj_.push_back(0);// Always set the first index to zero for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index bcc9fc23f..7bc595aba 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -71,6 +71,7 @@ public: std::vector xadj() const { return xadj_; } std::vector adj() const { return adj_; } + size_t nValues() const { return nValues_; } /// @} }; diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index fbda41ac0..2618d8f50 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -202,30 +202,30 @@ namespace gtsam { /* ************************************************************************* */ Ordering Ordering::METIS(const MetisIndex& met) { - gttic(Ordering_METIS); + gttic(Ordering_METIS); - vector xadj = met.xadj(); - vector adj = met.adj(); + vector xadj = met.xadj(); + vector adj = met.adj(); - vector perm, iperm; + vector perm, iperm; - idx_t size = xadj.size() - 1; + idx_t size = met.nValues(); for (idx_t i = 0; i < size; i++) { perm.push_back(0); iperm.push_back(0); } - int outputError; + int outputError; - outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); - Ordering result; + outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); + Ordering result; - if (outputError != METIS_OK) - { - std::cout << "METIS failed during Nested Dissection ordering!\n"; - return result; - } + if (outputError != METIS_OK) + { + std::cout << "METIS failed during Nested Dissection ordering!\n"; + return result; + } result.resize(size); for (size_t j = 0; j < size; ++j) diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index b769551bf..424eb7c19 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -116,17 +116,52 @@ TEST(Ordering, csr_format) { EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); - EXPECT( adjExpected == mi.adj()); + EXPECT(adjExpected == mi.adj()); } +/* ************************************************************************* */ + +TEST(Ordering, csr_format_2) { + SymbolicFactorGraph sfg; + + sfg.push_factor(0); + sfg.push_factor(0, 1); + sfg.push_factor(1, 2); + sfg.push_factor(2, 3); + sfg.push_factor(3, 4); + sfg.push_factor(4, 1); + + MetisIndex mi(sfg); + + vector xadjExpected { 0, 1, 4, 6, 8, 10 }; + vector adjExpected { 1, 0, 2, 4, 1, 3, 2, 4, 1, 3 }; + + EXPECT(xadjExpected == mi.xadj()); + EXPECT(adjExpected.size() == mi.adj().size()); + EXPECT(adjExpected == mi.adj()); + + //Ordering metis = Ordering::METIS(sfg); + +} + /* ************************************************************************* */ TEST(Ordering, metis) { - SymbolicFactorGraph sfg; + SymbolicFactorGraph sfg; - sfg.push_factor(0, 1); + sfg.push_factor(0); + sfg.push_factor(0, 1); sfg.push_factor(1, 2); - Ordering metis = Ordering::METIS(sfg); + MetisIndex mi(sfg); + + vector xadjExpected{ 0, 1, 3, 4 }; + vector adjExpected { 1, 0, 2, 1 }; + + EXPECT(xadjExpected == mi.xadj()); + EXPECT(adjExpected.size() == mi.adj().size()); + EXPECT(adjExpected == mi.adj()); + + Ordering metis = Ordering::METIS(sfg); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 002f8b237..5fca680a2 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -341,7 +341,10 @@ void LevenbergMarquardtOptimizer::iterate() { LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering( LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const { if (!params.ordering) - params.ordering = Ordering::COLAMD(graph); + if (params.orderingType = Ordering::Type::METIS_) + params.ordering = Ordering::METIS(graph); + else + params.ordering = Ordering::COLAMD(graph); return params; } diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index 04877c72e..d7ead9ca3 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -154,7 +154,7 @@ public: void setOrdering(const Ordering& ordering) { this->ordering = ordering; - this->orderingType = Ordering::Type::CUSTOM_; + this->orderingType = Ordering::Type::CUSTOM_; } std::string getOrderingType() const { From 88a11329c09b375e93dbe0a8d67ffb28271d5ac4 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 7 Nov 2014 21:54:59 -0500 Subject: [PATCH 13/32] Correct key index issue with metis ordering --- gtsam/inference/MetisIndex-inl.h | 22 ++++++++++++++++------ gtsam/inference/MetisIndex.h | 14 +++++++------- gtsam/inference/tests/testOrdering.cpp | 22 +++++++++++++++++++++- 3 files changed, 44 insertions(+), 14 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 08a0566a2..43bc7a111 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -29,7 +29,7 @@ namespace gtsam { { std::map > adjMap; std::map >::iterator adjMapIt; - std::set values; + std::set keySet; /* ********** Convert to CSR format ********** */ // Assuming that vertex numbering starts from 0 (C style), @@ -44,17 +44,22 @@ namespace gtsam { if (k1 != k2) adjMap[k1].insert(adjMap[k1].end(), k2); // Insert at the end } - values.insert(values.end(), k1); // Keep a track of all unique values + keySet.insert(keySet.end(), k1); // Keep a track of all unique keySet } } } - // Number of values referenced in this factorgraph - nValues_ = values.size(); - + // Number of keys referenced in this factor graph + nKeys_ = keySet.size(); + + + // Starting with a nonzero key crashes METIS + // Find the smallest key in the graph + size_t minKey = *keySet.begin(); // set is ordered + xadj_.push_back(0);// Always set the first index to zero for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { - std::vector temp; + std::vector temp; // Copy from the FastSet into a temporary vector std::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_ @@ -62,6 +67,11 @@ namespace gtsam { //adj_.push_back(temp); xadj_.push_back(adj_.size()); } + + // Normalize, subtract the smallest key + std::transform(adj_.begin(), adj_.end(), adj_.begin(), std::bind2nd(std::minus(), minKey)); + + } } diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 7bc595aba..6aaa9246d 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -43,18 +43,18 @@ public: private: FastVector xadj_; // Index of node's adjacency list in adj FastVector 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_; // + size_t nFactors_; // Number of factors in the original factor graph + size_t nKeys_; // public: /// @name Standard Constructors /// @{ /** Default constructor, creates empty MetisIndex */ - MetisIndex() : nFactors_(0), nValues_(0) {} + MetisIndex() : nFactors_(0), nKeys_(0) {} template - MetisIndex(const FG& factorGraph) : nFactors_(0), nValues_(0) { + MetisIndex(const FG& factorGraph) : nFactors_(0), nKeys_(0) { augment(factorGraph); } ~MetisIndex(){} @@ -69,9 +69,9 @@ public: template void augment(const FactorGraph& factors); - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } - size_t nValues() const { return nValues_; } + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } + size_t nValues() const { return nKeys_; } /// @} }; diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 424eb7c19..f2a0e1443 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -139,7 +139,27 @@ TEST(Ordering, csr_format_2) { EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); - //Ordering metis = Ordering::METIS(sfg); +} +/* ************************************************************************* */ + +TEST(Ordering, csr_format_3) { + SymbolicFactorGraph sfg; + + sfg.push_factor(100); + sfg.push_factor(100, 101); + sfg.push_factor(101, 102); + sfg.push_factor(102, 103); + sfg.push_factor(103, 104); + sfg.push_factor(104, 101); + + MetisIndex mi(sfg); + + vector xadjExpected{ 0, 1, 4, 6, 8, 10 }; + vector adjExpected{ 1, 0, 2, 4, 1, 3, 2, 4, 1, 3 }; + + EXPECT(xadjExpected == mi.xadj()); + EXPECT(adjExpected.size() == mi.adj().size()); + EXPECT(adjExpected == mi.adj()); } From ea19fae15582c4f681994f25d5640efac935d27a Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 7 Nov 2014 22:00:19 -0500 Subject: [PATCH 14/32] Formatting --- gtsam/inference/MetisIndex-inl.h | 86 ++++++++++++++++---------------- gtsam/inference/MetisIndex.h | 78 ++++++++++++++--------------- 2 files changed, 81 insertions(+), 83 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 43bc7a111..cab184ad0 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -23,55 +23,53 @@ namespace gtsam { - /* ************************************************************************* */ - template - void MetisIndex::augment(const FactorGraph& factors) - { - std::map > adjMap; - std::map >::iterator adjMapIt; - std::set keySet; +/* ************************************************************************* */ +template +void MetisIndex::augment(const FactorGraph& factors) +{ + std::map > adjMap; + std::map >::iterator adjMapIt; + std::set keySet; - /* ********** 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 - } - keySet.insert(keySet.end(), k1); // Keep a track of all unique keySet - } - } - } + /* ********** 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 + } + keySet.insert(keySet.end(), k1); // Keep a track of all unique keySet + } + } + } - // Number of keys referenced in this factor graph - nKeys_ = keySet.size(); + // Number of keys referenced in this factor graph + nKeys_ = keySet.size(); - // Starting with a nonzero key crashes METIS - // Find the smallest key in the graph - size_t minKey = *keySet.begin(); // set is ordered + // Starting with a nonzero key crashes METIS + // Find the smallest key in the graph + size_t minKey = *keySet.begin(); // set is ordered - xadj_.push_back(0);// Always set the first index to zero - for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { - std::vector temp; - // Copy from the FastSet into a temporary vector - std::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()); - } + xadj_.push_back(0);// Always set the first index to zero + for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { + std::vector temp; + // Copy from the FastSet into a temporary vector + std::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()); + } - // Normalize, subtract the smallest key - std::transform(adj_.begin(), adj_.end(), adj_.begin(), std::bind2nd(std::minus(), minKey)); - - - } + // Normalize, subtract the smallest key + std::transform(adj_.begin(), adj_.end(), adj_.begin(), std::bind2nd(std::minus(), minKey)); +} } diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 6aaa9246d..eaff2546f 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -28,53 +28,53 @@ #include 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 shared_ptr; + /** + * 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 shared_ptr; -private: - FastVector xadj_; // Index of node's adjacency list in adj - FastVector 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 nKeys_; // + private: + FastVector xadj_; // Index of node's adjacency list in adj + FastVector 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 nKeys_; // -public: - /// @name Standard Constructors - /// @{ + public: + /// @name Standard Constructors + /// @{ - /** Default constructor, creates empty MetisIndex */ - MetisIndex() : nFactors_(0), nKeys_(0) {} + /** Default constructor, creates empty MetisIndex */ + MetisIndex() : nFactors_(0), nKeys_(0) {} - template - MetisIndex(const FG& factorGraph) : nFactors_(0), nKeys_(0) { - augment(factorGraph); } + template + MetisIndex(const FG& factorGraph) : nFactors_(0), nKeys_(0) { + augment(factorGraph); } - ~MetisIndex(){} - /// @} - /// @name Advanced Interface - /// @{ + ~MetisIndex(){} + /// @} + /// @name Advanced Interface + /// @{ - /** - * Augment the variable index with new factors. This can be used when - * solving problems incrementally. - */ - template - void augment(const FactorGraph& factors); + /** + * Augment the variable index with new factors. This can be used when + * solving problems incrementally. + */ + template + void augment(const FactorGraph& factors); - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } - size_t nValues() const { return nKeys_; } + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } + size_t nValues() const { return nKeys_; } - /// @} -}; + /// @} + }; } From c520bf2b47055ca196c1919d14df9375ec1bb17a Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 7 Nov 2014 22:38:37 -0500 Subject: [PATCH 15/32] Working METIS ordering example. --- gtsam/inference/MetisIndex-inl.h | 19 ++++++++----------- gtsam/inference/MetisIndex.h | 8 +++++--- gtsam/inference/Ordering.cpp | 12 +++++++++--- gtsam/inference/tests/testOrdering.cpp | 8 +++++++- 4 files changed, 29 insertions(+), 18 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index cab184ad0..d9fb4cfd1 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -55,21 +55,18 @@ void MetisIndex::augment(const FactorGraph& factors) // Starting with a nonzero key crashes METIS // Find the smallest key in the graph - size_t minKey = *keySet.begin(); // set is ordered + minKey_ = *keySet.begin(); // set is ordered xadj_.push_back(0);// Always set the first index to zero for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { - std::vector temp; - // Copy from the FastSet into a temporary vector - std::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()); + std::vector temp; + // Copy from the FastSet into a temporary vector + std::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()); } - - // Normalize, subtract the smallest key - std::transform(adj_.begin(), adj_.end(), adj_.begin(), std::bind2nd(std::minus(), minKey)); } } diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index eaff2546f..57d097876 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -45,6 +45,7 @@ namespace gtsam { FastVector 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 nKeys_; // + size_t minKey_; public: /// @name Standard Constructors @@ -69,9 +70,10 @@ namespace gtsam { template void augment(const FactorGraph& factors); - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } - size_t nValues() const { return nKeys_; } + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } + size_t nValues() const { return nKeys_; } + size_t minKey() const { return minKey_; } /// @} }; diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 2618d8f50..654740163 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -206,6 +206,10 @@ namespace gtsam { vector xadj = met.xadj(); vector adj = met.adj(); + size_t minKey = met.minKey(); + + // Normalize, subtract the smallest key + std::transform(adj.begin(), adj.end(), adj.begin(), std::bind2nd(std::minus(), minKey)); vector perm, iperm; @@ -228,9 +232,11 @@ namespace gtsam { } result.resize(size); - for (size_t j = 0; j < size; ++j) - result[j] = perm[j]; - return result; + for (size_t j = 0; j < size; ++j){ + // We have to add the minKey value back to obtain the original key in the Values + result[j] = perm[j] + minKey; + } + return result; } /* ************************************************************************* */ diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index f2a0e1443..7e1ccb838 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -156,10 +156,16 @@ TEST(Ordering, csr_format_3) { vector xadjExpected{ 0, 1, 4, 6, 8, 10 }; vector adjExpected{ 1, 0, 2, 4, 1, 3, 2, 4, 1, 3 }; + size_t minKey = mi.minKey(); + + vector adjAcutal = mi.adj(); + + // Normalize, subtract the smallest key + std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(), std::bind2nd(std::minus(), minKey)); EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); - EXPECT(adjExpected == mi.adj()); + EXPECT(adjExpected == adjAcutal); } From f00f8d1d7afcf8c9c3cab39d34481b1aed08d162 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 17 Nov 2014 11:31:11 -0500 Subject: [PATCH 16/32] Formatting changes --- .../inference/EliminateableFactorGraph-inst.h | 14 +-- gtsam/inference/EliminateableFactorGraph.h | 18 ++-- gtsam/inference/MetisIndex.h | 93 +++++++++---------- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 3 +- gtsam/nonlinear/NonlinearOptimizerParams.cpp | 6 +- 5 files changed, 66 insertions(+), 68 deletions(-) diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index e14ba329b..153b828d9 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -65,8 +65,8 @@ namespace gtsam { template boost::shared_ptr::BayesTreeType> EliminateableFactorGraph::eliminateMultifrontal( - OptionalOrdering ordering, const Eliminate& function, - OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const + OptionalOrdering ordering, const Eliminate& function, + OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const { if(ordering && variableIndex) { gttic(eliminateMultifrontal); @@ -86,16 +86,16 @@ namespace gtsam { // If no VariableIndex provided, compute one and call this function again IMPORTANT: we check // for no variable index first so that it's always computed if we need to call COLAMD because // no Ordering is provided. - return eliminateMultifrontal(ordering, function, VariableIndex(asDerived()), orderingType); + return eliminateMultifrontal(ordering, function, VariableIndex(asDerived()), orderingType); } else /*if(!ordering)*/ { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - if (orderingType == Ordering::Type::METIS_) - return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType); - else - return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); + if (orderingType == Ordering::Type::METIS_) + return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + else + return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); } } diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index 820bb2fd3..c048de94b 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -94,8 +94,8 @@ namespace gtsam { /// Typedef for an optional variable index as an argument to elimination functions typedef boost::optional OptionalVariableIndex; - /// Typedef for an optional ordering type - typedef boost::optional OptionalOrderingType; + /// Typedef for an optional ordering type + typedef boost::optional OptionalOrderingType; /** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not * provided, the ordering provided by COLAMD will be used. @@ -104,10 +104,10 @@ namespace gtsam { * \code * boost::shared_ptr result = graph.eliminateSequential(EliminateCholesky); * \endcode - * - * Example - METIS ordering for elimination - * \code - * boost::shared_ptr result = graph.eliminateSequential(Ordering::Type::METIS_); + * + * Example - METIS ordering for elimination + * \code + * boost::shared_ptr result = graph.eliminateSequential(Ordering::Type::METIS_); * * Example - Full QR elimination in specified order: * \code @@ -125,7 +125,7 @@ namespace gtsam { OptionalOrdering ordering = boost::none, const Eliminate& function = EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex = boost::none, - OptionalOrderingType orderingType = boost::none) const; + OptionalOrderingType orderingType = boost::none) const; /** Do multifrontal elimination of all variables to produce a Bayes tree. If an ordering is not * provided, the ordering provided by COLAMD will be used. @@ -150,8 +150,8 @@ namespace gtsam { boost::shared_ptr eliminateMultifrontal( OptionalOrdering ordering = boost::none, const Eliminate& function = EliminationTraitsType::DefaultEliminate, - OptionalVariableIndex variableIndex = boost::none, - OptionalOrderingType orderingType = boost::none) const; + OptionalVariableIndex variableIndex = boost::none, + OptionalOrderingType orderingType = boost::none) const; /** Do sequential elimination of some variables, in \c ordering provided, to produce a Bayes net * and a remaining factor graph. This computes the factorization \f$ p(X) = p(A|B) p(B) \f$, diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 57d097876..b058b5564 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -9,7 +9,6 @@ * -------------------------------------------------------------------------- */ - /** * @file MetisIndex.h * @author Andrew Melim @@ -28,55 +27,55 @@ #include 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 shared_ptr; + +private: + FastVector xadj_; // Index of node's adjacency list in adj + FastVector 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 nKeys_; // + size_t minKey_; + +public: + /// @name Standard Constructors + /// @{ + + /** Default constructor, creates empty MetisIndex */ + MetisIndex() : nFactors_(0), nKeys_(0) {} + + template + MetisIndex(const FG& factorGraph) : nFactors_(0), nKeys_(0) { + augment(factorGraph); } + + ~MetisIndex(){} + /// @} + /// @name Advanced Interface + /// @{ + /** - * 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 shared_ptr; + * Augment the variable index with new factors. This can be used when + * solving problems incrementally. + */ + template + void augment(const FactorGraph& factors); - private: - FastVector xadj_; // Index of node's adjacency list in adj - FastVector 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 nKeys_; // - size_t minKey_; + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } + size_t nValues() const { return nKeys_; } + size_t minKey() const { return minKey_; } - public: - /// @name Standard Constructors - /// @{ - - /** Default constructor, creates empty MetisIndex */ - MetisIndex() : nFactors_(0), nKeys_(0) {} - - template - MetisIndex(const FG& factorGraph) : nFactors_(0), nKeys_(0) { - augment(factorGraph); } - - ~MetisIndex(){} - /// @} - /// @name Advanced Interface - /// @{ - - /** - * Augment the variable index with new factors. This can be used when - * solving problems incrementally. - */ - template - void augment(const FactorGraph& factors); - - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } - size_t nValues() const { return nKeys_; } - size_t minKey() const { return minKey_; } - - /// @} - }; + /// @} +}; } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 5fca680a2..a8dab8266 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -340,11 +340,12 @@ void LevenbergMarquardtOptimizer::iterate() { /* ************************************************************************* */ LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering( LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const { - if (!params.ordering) + if (!params.ordering){ if (params.orderingType = Ordering::Type::METIS_) params.ordering = Ordering::METIS(graph); else params.ordering = Ordering::COLAMD(graph); + } return params; } diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index 1e964a481..626758bcb 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -165,8 +165,7 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve } /* ************************************************************************* */ -std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type) const -{ +std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type) const{ switch (type) { case Ordering::Type::METIS_: return "METIS"; @@ -182,8 +181,7 @@ std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type } /* ************************************************************************* */ -Ordering::Type NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const -{ +Ordering::Type NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const{ if (type == "METIS") return Ordering::Type::METIS_; if (type == "COLAMD") From ffae14d42e6ee9b06b13848d2ee72147a54c9818 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 17 Nov 2014 11:57:22 -0500 Subject: [PATCH 17/32] Corrected scoped enum issue for non c++11 compilers --- examples/METISOrderingExample.cpp | 2 +- gtsam/inference/EliminateableFactorGraph-inst.h | 4 ++-- gtsam/inference/EliminateableFactorGraph.h | 4 ++-- gtsam/inference/Ordering.h | 11 +++++------ gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp | 2 +- gtsam/nonlinear/NonlinearOptimizerParams.cpp | 16 ++++++++-------- gtsam/nonlinear/NonlinearOptimizerParams.h | 10 +++++----- 7 files changed, 24 insertions(+), 25 deletions(-) diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp index 1b84364c0..6b54b8d70 100644 --- a/examples/METISOrderingExample.cpp +++ b/examples/METISOrderingExample.cpp @@ -87,7 +87,7 @@ int main(int argc, char** argv) { // optimize using Levenberg-Marquardt optimization LevenbergMarquardtParams params; - params.orderingType = Ordering::Type::METIS_; + params.orderingType = OrderingType::METIS; LevenbergMarquardtOptimizer optimizer(graph, initial, params); Values result = optimizer.optimize(); result.print("Final Result:\n"); diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index 153b828d9..c0c95ce88 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -54,7 +54,7 @@ namespace gtsam { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - if (orderingType == Ordering::Type::METIS_) + if (orderingType == OrderingType::METIS) return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType); else return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); @@ -92,7 +92,7 @@ namespace gtsam { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - if (orderingType == Ordering::Type::METIS_) + if (orderingType == OrderingType::METIS) return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType); else return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index c048de94b..f0baf55a0 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -95,7 +95,7 @@ namespace gtsam { typedef boost::optional OptionalVariableIndex; /// Typedef for an optional ordering type - typedef boost::optional OptionalOrderingType; + typedef boost::optional OptionalOrderingType; /** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not * provided, the ordering provided by COLAMD will be used. @@ -107,7 +107,7 @@ namespace gtsam { * * Example - METIS ordering for elimination * \code - * boost::shared_ptr result = graph.eliminateSequential(Ordering::Type::METIS_); + * boost::shared_ptr result = graph.eliminateSequential(OrderingType::METIS); * * Example - Full QR elimination in specified order: * \code diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index dfb1deb0e..3c5b41535 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -29,6 +29,11 @@ #include namespace gtsam { + + enum OrderingType { + COLAMD, METIS, CUSTOM + }; + class Ordering : public std::vector { protected: typedef std::vector Base; @@ -37,12 +42,6 @@ namespace gtsam { typedef Ordering This; ///< Typedef to this class typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class - /** See NonlinearOptimizer::orderingType */ - enum Type { - COLAMD_, METIS_, CUSTOM_ // Add underscores to prevent declaration errors - }; - - /// Create an empty ordering GTSAM_EXPORT Ordering() {} diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index a8dab8266..59acad3c3 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -341,7 +341,7 @@ void LevenbergMarquardtOptimizer::iterate() { LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering( LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const { if (!params.ordering){ - if (params.orderingType = Ordering::Type::METIS_) + if (params.orderingType = OrderingType::METIS) params.ordering = Ordering::METIS(graph); else params.ordering = Ordering::COLAMD(graph); diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index 626758bcb..79bc64414 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -109,10 +109,10 @@ void NonlinearOptimizerParams::print(const std::string& str) const { } switch (orderingType){ - case Ordering::Type::COLAMD_: + case OrderingType::COLAMD: std::cout << " ordering: COLAMD\n"; break; - case Ordering::Type::METIS_: + case OrderingType::METIS: std::cout << " ordering: METIS\n"; break; default: @@ -165,11 +165,11 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve } /* ************************************************************************* */ -std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type) const{ +std::string NonlinearOptimizerParams::orderingTypeTranslator(OrderingType type) const{ switch (type) { - case Ordering::Type::METIS_: + case OrderingType::METIS: return "METIS"; - case Ordering::Type::COLAMD_: + case OrderingType::COLAMD: return "COLAMD"; default: if (ordering) @@ -181,11 +181,11 @@ std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::Type type } /* ************************************************************************* */ -Ordering::Type NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const{ +OrderingType NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const{ if (type == "METIS") - return Ordering::Type::METIS_; + return OrderingType::METIS; if (type == "COLAMD") - return Ordering::Type::COLAMD_; + return OrderingType::COLAMD; throw std::invalid_argument( "Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering"); } diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index d7ead9ca3..2cb055465 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -43,11 +43,11 @@ public: double absoluteErrorTol; ///< The maximum absolute error decrease to stop iterating (default 1e-5) double errorTol; ///< The maximum total error to stop iterating (default 0.0) Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) - Ordering::Type orderingType; ///< The method of ordering use during variable elimination (default COLAMD) + OrderingType orderingType; ///< The method of ordering use during variable elimination (default COLAMD) NonlinearOptimizerParams() : maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol( - 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(Ordering::Type::COLAMD_) { + 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(COLAMD) { } virtual ~NonlinearOptimizerParams() { @@ -154,7 +154,7 @@ public: void setOrdering(const Ordering& ordering) { this->ordering = ordering; - this->orderingType = Ordering::Type::CUSTOM_; + this->orderingType = OrderingType::CUSTOM; } std::string getOrderingType() const { @@ -171,9 +171,9 @@ private: LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; - std::string orderingTypeTranslator(Ordering::Type type) const; + std::string orderingTypeTranslator(OrderingType type) const; - Ordering::Type orderingTypeTranslator(const std::string& type) const; + OrderingType orderingTypeTranslator(const std::string& type) const; }; From 9c2dcfb70c57e520088834220042c144600b19d3 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 17 Nov 2014 12:06:59 -0500 Subject: [PATCH 18/32] Slim down example to remove verbosity, added explanation on orderingType --- examples/METISOrderingExample.cpp | 47 +++---------------------------- 1 file changed, 4 insertions(+), 43 deletions(-) diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp index 6b54b8d70..1fae4c0b9 100644 --- a/examples/METISOrderingExample.cpp +++ b/examples/METISOrderingExample.cpp @@ -17,68 +17,34 @@ */ /** - * Example of a simple 2D localization example - * - Robot poses are facing along the X axis (horizontal, to the right in 2D) - * - The robot moves 2 meters each step - * - We have full odometry between poses + * Example of a simple 2D localization example optimized using METIS ordering + * - For more details on the full optimization pipeline, see OdometryExample.cpp */ -// We will use Pose2 variables (x, y, theta) to represent the robot positions #include - -// In GTSAM, measurement functions are represented as 'factors'. Several common factors -// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. -// Here we will use Between factors for the relative motion described by odometry measurements. -// Also, we will initialize the robot at the origin using a Prior factor. #include #include - -// When the factors are created, we will add them to a Factor Graph. As the factors we are using -// are nonlinear factors, we will need a Nonlinear Factor Graph. #include - -// Finally, once all of the factors have been added to our factor graph, we will want to -// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values. -// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the -// Levenberg-Marquardt solver #include - -// Once the optimized values have been calculated, we can also calculate the marginal covariance -// of desired variables #include - -// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the -// nonlinear functions around an initial linearization point, then solve the linear system -// to update the linearization point. This happens repeatedly until the solver converges -// to a consistent set of variable values. This requires us to specify an initial guess -// for each variable, held in a Values container. #include using namespace std; using namespace gtsam; int main(int argc, char** argv) { - - // Create an empty nonlinear factor graph NonlinearFactorGraph graph; - // Add a prior on the first pose, setting it to the origin - // A prior factor consists of a mean and a noise model (covariance matrix) Pose2 priorMean(0.0, 0.0, 0.0); // prior at origin noiseModel::Diagonal::shared_ptr priorNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.3, 0.3, 0.1)); graph.add(PriorFactor(1, priorMean, priorNoise)); - // Add odometry factors Pose2 odometry(2.0, 0.0, 0.0); - // For simplicity, we will use the same noise model for each odometry factor noiseModel::Diagonal::shared_ptr odometryNoise = noiseModel::Diagonal::Sigmas((Vector(3) << 0.2, 0.2, 0.1)); - // Create odometry (Between) factors between consecutive poses graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); graph.print("\nFactor Graph:\n"); // print - // Create the data structure to hold the initialEstimate estimate to the solution - // For illustrative purposes, these have been deliberately set to incorrect values Values initial; initial.insert(1, Pose2(0.5, 0.0, 0.2)); initial.insert(2, Pose2(2.3, 0.1, -0.2)); @@ -87,17 +53,12 @@ int main(int argc, char** argv) { // optimize using Levenberg-Marquardt optimization LevenbergMarquardtParams params; + // In order to specify the ordering type, we need to se the NonlinearOptimizerParameter "orderingType" + // By default this parameter is set to OrderingType::COLAMD params.orderingType = OrderingType::METIS; LevenbergMarquardtOptimizer optimizer(graph, initial, params); Values result = optimizer.optimize(); result.print("Final Result:\n"); - // Calculate and print marginal covariances for all variables - cout.precision(2); - Marginals marginals(graph, result); - cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; - cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; - cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; - return 0; } \ No newline at end of file From 36a485169d15e603f2e7607efd16e6d5edf5abf1 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 17 Nov 2014 16:16:52 -0500 Subject: [PATCH 19/32] Refactor Ordering parameters. Now compiles and passes with gcc --- examples/METISOrderingExample.cpp | 4 +- examples/SolverComparer.cpp | 2 +- .../inference/EliminateableFactorGraph-inst.h | 22 ++++---- gtsam/inference/EliminateableFactorGraph.h | 2 +- gtsam/inference/ISAM-inst.h | 2 +- gtsam/inference/Ordering.cpp | 20 +++---- gtsam/inference/Ordering.h | 42 ++++++++------- gtsam/inference/tests/testOrdering.cpp | 53 ++++++++++--------- gtsam/nonlinear/DoglegOptimizer.cpp | 2 +- gtsam/nonlinear/GaussNewtonOptimizer.cpp | 2 +- gtsam/nonlinear/ISAM2.cpp | 8 +-- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 6 +-- gtsam/nonlinear/NonlinearFactorGraph.cpp | 4 +- gtsam/nonlinear/NonlinearOptimizerParams.cpp | 16 +++--- gtsam/nonlinear/NonlinearOptimizerParams.h | 12 ++--- .../nonlinear/BatchFixedLagSmoother.cpp | 2 +- .../nonlinear/ConcurrentBatchFilter.cpp | 4 +- .../nonlinear/ConcurrentBatchSmoother.cpp | 2 +- tests/testNonlinearFactorGraph.cpp | 4 +- 19 files changed, 108 insertions(+), 101 deletions(-) diff --git a/examples/METISOrderingExample.cpp b/examples/METISOrderingExample.cpp index 1fae4c0b9..452ba523e 100644 --- a/examples/METISOrderingExample.cpp +++ b/examples/METISOrderingExample.cpp @@ -55,10 +55,10 @@ int main(int argc, char** argv) { LevenbergMarquardtParams params; // In order to specify the ordering type, we need to se the NonlinearOptimizerParameter "orderingType" // By default this parameter is set to OrderingType::COLAMD - params.orderingType = OrderingType::METIS; + params.orderingType = Ordering::METIS; LevenbergMarquardtOptimizer optimizer(graph, initial, params); Values result = optimizer.optimize(); result.print("Final Result:\n"); return 0; -} \ No newline at end of file +} diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index 26abfff85..3dd978ee3 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -589,7 +589,7 @@ void runStats() { cout << "Gathering statistics..." << endl; GaussianFactorGraph linear = *datasetMeasurements.linearize(initial); - GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::COLAMD(linear))); + GaussianJunctionTree jt(GaussianEliminationTree(linear, Ordering::colamd(linear))); treeTraversal::ForestStatistics statistics = treeTraversal::GatherStatistics(jt); ofstream file; diff --git a/gtsam/inference/EliminateableFactorGraph-inst.h b/gtsam/inference/EliminateableFactorGraph-inst.h index c0c95ce88..5e261e200 100644 --- a/gtsam/inference/EliminateableFactorGraph-inst.h +++ b/gtsam/inference/EliminateableFactorGraph-inst.h @@ -54,10 +54,10 @@ namespace gtsam { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - if (orderingType == OrderingType::METIS) - return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + if (orderingType == Ordering::METIS) + return eliminateSequential(Ordering::metis(asDerived()), function, variableIndex, orderingType); else - return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); + return eliminateSequential(Ordering::colamd(*variableIndex), function, variableIndex, orderingType); } } @@ -92,10 +92,10 @@ namespace gtsam { // If no Ordering provided, compute one and call this function again. We are guaranteed to // have a VariableIndex already here because we computed one if needed in the previous 'else' // block. - if (orderingType == OrderingType::METIS) - return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType); + if (orderingType == Ordering::METIS) + return eliminateMultifrontal(Ordering::metis(asDerived()), function, variableIndex, orderingType); else - return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType); + return eliminateMultifrontal(Ordering::colamd(*variableIndex), function, variableIndex, orderingType); } } @@ -125,7 +125,7 @@ namespace gtsam { if(variableIndex) { gttic(eliminatePartialSequential); // Compute full ordering - Ordering fullOrdering = Ordering::COLAMDConstrainedFirst(*variableIndex, variables); + Ordering fullOrdering = Ordering::colamdConstrainedFirst(*variableIndex, variables); // Split off the part of the ordering for the variables being eliminated Ordering ordering(fullOrdering.begin(), fullOrdering.begin() + variables.size()); @@ -163,7 +163,7 @@ namespace gtsam { if(variableIndex) { gttic(eliminatePartialMultifrontal); // Compute full ordering - Ordering fullOrdering = Ordering::COLAMDConstrainedFirst(*variableIndex, variables); + Ordering fullOrdering = Ordering::colamdConstrainedFirst(*variableIndex, variables); // Split off the part of the ordering for the variables being eliminated Ordering ordering(fullOrdering.begin(), fullOrdering.begin() + variables.size()); @@ -216,7 +216,7 @@ namespace gtsam { boost::get(&variables) : boost::get&>(&variables); Ordering totalOrdering = - Ordering::COLAMDConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); + Ordering::colamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); // Split up ordering const size_t nVars = variablesOrOrdering->size(); @@ -275,7 +275,7 @@ namespace gtsam { boost::get(&variables) : boost::get&>(&variables); Ordering totalOrdering = - Ordering::COLAMDConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); + Ordering::colamdConstrainedLast(*variableIndex, *variablesOrOrdering, unmarginalizedAreOrdered); // Split up ordering const size_t nVars = variablesOrOrdering->size(); @@ -301,7 +301,7 @@ namespace gtsam { if(variableIndex) { // Compute a total ordering for all variables - Ordering totalOrdering = Ordering::COLAMDConstrainedLast(*variableIndex, variables); + Ordering totalOrdering = Ordering::colamdConstrainedLast(*variableIndex, variables); // Split out the part for the marginalized variables Ordering marginalizationOrdering(totalOrdering.begin(), totalOrdering.end() - variables.size()); diff --git a/gtsam/inference/EliminateableFactorGraph.h b/gtsam/inference/EliminateableFactorGraph.h index f0baf55a0..5fb5fbdb1 100644 --- a/gtsam/inference/EliminateableFactorGraph.h +++ b/gtsam/inference/EliminateableFactorGraph.h @@ -95,7 +95,7 @@ namespace gtsam { typedef boost::optional OptionalVariableIndex; /// Typedef for an optional ordering type - typedef boost::optional OptionalOrderingType; + typedef boost::optional OptionalOrderingType; /** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not * provided, the ordering provided by COLAMD will be used. diff --git a/gtsam/inference/ISAM-inst.h b/gtsam/inference/ISAM-inst.h index 645499b2c..7cb3d9817 100644 --- a/gtsam/inference/ISAM-inst.h +++ b/gtsam/inference/ISAM-inst.h @@ -46,7 +46,7 @@ namespace gtsam { const VariableIndex varIndex(factors); const FastSet newFactorKeys = newFactors.keys(); const Ordering constrainedOrdering = - Ordering::COLAMDConstrainedLast(varIndex, std::vector(newFactorKeys.begin(), newFactorKeys.end())); + Ordering::colamdConstrainedLast(varIndex, std::vector(newFactorKeys.begin(), newFactorKeys.end())); Base bayesTree = *factors.eliminateMultifrontal(constrainedOrdering, function, varIndex); this->roots_.insert(this->roots_.end(), bayesTree.roots().begin(), bayesTree.roots().end()); this->nodes_.insert(bayesTree.nodes().begin(), bayesTree.nodes().end()); diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 654740163..6c72fe675 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -39,15 +39,15 @@ namespace gtsam { } /* ************************************************************************* */ - Ordering Ordering::COLAMD(const VariableIndex& variableIndex) + Ordering Ordering::colamd(const VariableIndex& variableIndex) { // Call constrained version with all groups set to zero vector dummy_groups(variableIndex.size(), 0); - return Ordering::COLAMDConstrained(variableIndex, dummy_groups); + return Ordering::colamdConstrained(variableIndex, dummy_groups); } /* ************************************************************************* */ - Ordering Ordering::COLAMDConstrained( + Ordering Ordering::colamdConstrained( const VariableIndex& variableIndex, std::vector& cmember) { gttic(Ordering_COLAMDConstrained); @@ -114,7 +114,7 @@ namespace gtsam { } /* ************************************************************************* */ - Ordering Ordering::COLAMDConstrainedLast( + Ordering Ordering::colamdConstrainedLast( const VariableIndex& variableIndex, const std::vector& constrainLast, bool forceOrder) { gttic(Ordering_COLAMDConstrainedLast); @@ -137,11 +137,11 @@ namespace gtsam { ++ group; } - return Ordering::COLAMDConstrained(variableIndex, cmember); + return Ordering::colamdConstrained(variableIndex, cmember); } /* ************************************************************************* */ - Ordering Ordering::COLAMDConstrainedFirst( + Ordering Ordering::colamdConstrainedFirst( const VariableIndex& variableIndex, const std::vector& constrainFirst, bool forceOrder) { gttic(Ordering_COLAMDConstrainedFirst); @@ -171,11 +171,11 @@ namespace gtsam { if(c == none) c = group; - return Ordering::COLAMDConstrained(variableIndex, cmember); + return Ordering::colamdConstrained(variableIndex, cmember); } /* ************************************************************************* */ - Ordering Ordering::COLAMDConstrained(const VariableIndex& variableIndex, + Ordering Ordering::colamdConstrained(const VariableIndex& variableIndex, const FastMap& groups) { gttic(Ordering_COLAMDConstrained); @@ -195,12 +195,12 @@ namespace gtsam { cmember[keyIndices.at(p.first)] = p.second; } - return Ordering::COLAMDConstrained(variableIndex, cmember); + return Ordering::colamdConstrained(variableIndex, cmember); } /* ************************************************************************* */ - Ordering Ordering::METIS(const MetisIndex& met) + Ordering Ordering::metis(const MetisIndex& met) { gttic(Ordering_METIS); diff --git a/gtsam/inference/Ordering.h b/gtsam/inference/Ordering.h index 3c5b41535..24c811841 100644 --- a/gtsam/inference/Ordering.h +++ b/gtsam/inference/Ordering.h @@ -30,15 +30,17 @@ namespace gtsam { - enum OrderingType { - COLAMD, METIS, CUSTOM - }; - class Ordering : public std::vector { protected: typedef std::vector Base; public: + + /// Type of ordering to use + enum OrderingType { + COLAMD, METIS, CUSTOM + }; + typedef Ordering This; ///< Typedef to this class typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class @@ -69,11 +71,11 @@ namespace gtsam { /// performance). This internally builds a VariableIndex so if you already have a VariableIndex, /// it is faster to use COLAMD(const VariableIndex&) template - static Ordering COLAMD(const FactorGraph& graph) { - return COLAMD(VariableIndex(graph)); } + static Ordering colamd(const FactorGraph& graph) { + return colamd(VariableIndex(graph)); } /// Compute a fill-reducing ordering using COLAMD from a VariableIndex. - static GTSAM_EXPORT Ordering COLAMD(const VariableIndex& variableIndex); + static GTSAM_EXPORT Ordering colamd(const VariableIndex& variableIndex); /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details /// for note on performance). This internally builds a VariableIndex so if you already have a @@ -84,9 +86,9 @@ namespace gtsam { /// constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. template - static Ordering COLAMDConstrainedLast(const FactorGraph& graph, + static Ordering colamdConstrainedLast(const FactorGraph& graph, const std::vector& constrainLast, bool forceOrder = false) { - return COLAMDConstrainedLast(VariableIndex(graph), constrainLast, forceOrder); } + return colamdConstrainedLast(VariableIndex(graph), constrainLast, forceOrder); } /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This /// function constrains the variables in \c constrainLast to the end of the ordering, and orders @@ -94,7 +96,7 @@ namespace gtsam { /// variables in \c constrainLast will be ordered in the same order specified in the vector /// \c constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. - static GTSAM_EXPORT Ordering COLAMDConstrainedLast(const VariableIndex& variableIndex, + static GTSAM_EXPORT Ordering colamdConstrainedLast(const VariableIndex& variableIndex, const std::vector& constrainLast, bool forceOrder = false); /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details @@ -106,9 +108,9 @@ namespace gtsam { /// constrainLast. If \c forceOrder is false, the variables in \c constrainFirst will be /// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well. template - static Ordering COLAMDConstrainedFirst(const FactorGraph& graph, + static Ordering colamdConstrainedFirst(const FactorGraph& graph, const std::vector& constrainFirst, bool forceOrder = false) { - return COLAMDConstrainedFirst(VariableIndex(graph), constrainFirst, forceOrder); } + return colamdConstrainedFirst(VariableIndex(graph), constrainFirst, forceOrder); } /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. This /// function constrains the variables in \c constrainFirst to the front of the ordering, and @@ -117,7 +119,7 @@ namespace gtsam { /// vector \c constrainFirst. If \c forceOrder is false, the variables in \c /// constrainFirst will be ordered after all the others, but will be rearranged by CCOLAMD to /// reduce fill-in as well. - static GTSAM_EXPORT Ordering COLAMDConstrainedFirst(const VariableIndex& variableIndex, + static GTSAM_EXPORT Ordering colamdConstrainedFirst(const VariableIndex& variableIndex, const std::vector& constrainFirst, bool forceOrder = false); /// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details @@ -130,9 +132,9 @@ namespace gtsam { /// function simply fills the \c cmember argument to CCOLAMD with the supplied indices, see the /// CCOLAMD documentation for more information. template - static Ordering COLAMDConstrained(const FactorGraph& graph, + static Ordering colamdConstrained(const FactorGraph& graph, const FastMap& groups) { - return COLAMDConstrained(VariableIndex(graph), groups); } + return colamdConstrained(VariableIndex(graph), groups); } /// Compute a fill-reducing ordering using constrained COLAMD from a VariableIndex. In this /// function, a group for each variable should be specified in \c groups, and each group of @@ -141,7 +143,7 @@ namespace gtsam { /// appear in \c groups in arbitrary order. Any variables not present in \c groups will be /// assigned to group 0. This function simply fills the \c cmember argument to CCOLAMD with the /// supplied indices, see the CCOLAMD documentation for more information. - static GTSAM_EXPORT Ordering COLAMDConstrained(const VariableIndex& variableIndex, + static GTSAM_EXPORT Ordering colamdConstrained(const VariableIndex& variableIndex, const FastMap& groups); /// Return a natural Ordering. Typically used by iterative solvers @@ -158,12 +160,12 @@ namespace gtsam { static GTSAM_EXPORT void CSRFormat(std::vector& xadj, std::vector& adj, const FactorGraph& graph); /// Compute an ordering determined by METIS from a VariableIndex - static GTSAM_EXPORT Ordering METIS(const MetisIndex& met); + static GTSAM_EXPORT Ordering metis(const MetisIndex& met); template - static Ordering METIS(const FactorGraph& graph) + static Ordering metis(const FactorGraph& graph) { - return METIS(MetisIndex(graph)); + return metis(MetisIndex(graph)); } /// @} @@ -178,7 +180,7 @@ namespace gtsam { private: /// Internal COLAMD function - static GTSAM_EXPORT Ordering COLAMDConstrained( + static GTSAM_EXPORT Ordering colamdConstrained( const VariableIndex& variableIndex, std::vector& cmember); diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 7e1ccb838..57de00646 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -22,7 +22,7 @@ #include #include -#include +#include using namespace std; using namespace gtsam; @@ -40,17 +40,17 @@ TEST(Ordering, constrained_ordering) { sfg.push_factor(4,5); // unconstrained version - Ordering actUnconstrained = Ordering::COLAMD(sfg); + Ordering actUnconstrained = Ordering::colamd(sfg); Ordering expUnconstrained = Ordering(list_of(0)(1)(2)(3)(4)(5)); EXPECT(assert_equal(expUnconstrained, actUnconstrained)); // constrained version - push one set to the end - Ordering actConstrained = Ordering::COLAMDConstrainedLast(sfg, list_of(2)(4)); + Ordering actConstrained = Ordering::colamdConstrainedLast(sfg, list_of(2)(4)); Ordering expConstrained = Ordering(list_of(0)(1)(5)(3)(4)(2)); EXPECT(assert_equal(expConstrained, actConstrained)); // constrained version - push one set to the start - Ordering actConstrained2 = Ordering::COLAMDConstrainedFirst(sfg, list_of(2)(4)); + Ordering actConstrained2 = Ordering::colamdConstrainedFirst(sfg, list_of(2)(4)); Ordering expConstrained2 = Ordering(list_of(2)(4)(0)(1)(3)(5)); EXPECT(assert_equal(expConstrained2, actConstrained2)); } @@ -74,7 +74,7 @@ TEST(Ordering, grouped_constrained_ordering) { constraints[4] = 1; constraints[5] = 2; - Ordering actConstrained = Ordering::COLAMDConstrained(sfg, constraints); + Ordering actConstrained = Ordering::colamdConstrained(sfg, constraints); Ordering expConstrained = list_of(0)(1)(3)(2)(4)(5); EXPECT(assert_equal(expConstrained, actConstrained)); } @@ -109,17 +109,18 @@ TEST(Ordering, csr_format) { MetisIndex mi(sfg); - vector xadjExpected{ 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44}; - vector adjExpected{ 1, 5, 0, 2, 6, 1, 3, 7, 2, 4, 8, 3, 9, 0, 6, 10, 1, 5, 7, 11, + vector xadjExpected, adjExpected; + xadjExpected += 0, 2, 5, 8, 11, 13, 16, 20, 24, 28, 31, 33, 36, 39, 42, 44; + 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 }; + 13, 8, 12, 14, 9, 13 ; EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); } -/* ************************************************************************* */ +/* ************************************************************************* */ TEST(Ordering, csr_format_2) { SymbolicFactorGraph sfg; @@ -132,16 +133,17 @@ TEST(Ordering, csr_format_2) { MetisIndex mi(sfg); - vector xadjExpected { 0, 1, 4, 6, 8, 10 }; - vector adjExpected { 1, 0, 2, 4, 1, 3, 2, 4, 1, 3 }; + vector xadjExpected, adjExpected; + xadjExpected += 0, 1, 4, 6, 8, 10; + adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3; EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); } -/* ************************************************************************* */ +/* ************************************************************************* */ TEST(Ordering, csr_format_3) { SymbolicFactorGraph sfg; @@ -154,40 +156,43 @@ TEST(Ordering, csr_format_3) { MetisIndex mi(sfg); - vector xadjExpected{ 0, 1, 4, 6, 8, 10 }; - vector adjExpected{ 1, 0, 2, 4, 1, 3, 2, 4, 1, 3 }; - size_t minKey = mi.minKey(); + vector xadjExpected, adjExpected; + xadjExpected += 0, 1, 4, 6, 8, 10; + adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3; + size_t minKey = mi.minKey(); - vector adjAcutal = mi.adj(); + vector adjAcutal = mi.adj(); - // Normalize, subtract the smallest key - std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(), std::bind2nd(std::minus(), minKey)); + // Normalize, subtract the smallest key + std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(), + std::bind2nd(std::minus(), minKey)); EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); - EXPECT(adjExpected == adjAcutal); + EXPECT(adjExpected == adjAcutal); } /* ************************************************************************* */ TEST(Ordering, metis) { - + SymbolicFactorGraph sfg; sfg.push_factor(0); sfg.push_factor(0, 1); - sfg.push_factor(1, 2); + sfg.push_factor(1, 2); MetisIndex mi(sfg); - vector xadjExpected{ 0, 1, 3, 4 }; - vector adjExpected { 1, 0, 2, 1 }; + vector xadjExpected, adjExpected; + xadjExpected += 0, 1, 3, 4; + adjExpected += 1, 0, 2, 1; EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == mi.adj()); - Ordering metis = Ordering::METIS(sfg); + Ordering metis = Ordering::metis(sfg); } /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 082cc66c8..e148bd65d 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -96,7 +96,7 @@ void DoglegOptimizer::iterate(void) { /* ************************************************************************* */ DoglegParams DoglegOptimizer::ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph& graph) const { if(!params.ordering) - params.ordering = Ordering::COLAMD(graph); + params.ordering = Ordering::colamd(graph); return params; } diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.cpp b/gtsam/nonlinear/GaussNewtonOptimizer.cpp index 823f3a6ac..7a115e1c4 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.cpp +++ b/gtsam/nonlinear/GaussNewtonOptimizer.cpp @@ -49,7 +49,7 @@ GaussNewtonParams GaussNewtonOptimizer::ensureHasOrdering( GaussNewtonParams params, const NonlinearFactorGraph& graph) const { if(!params.ordering) - params.ordering = Ordering::COLAMD(graph); + params.ordering = Ordering::colamd(graph); return params; } diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 6d6785b14..3b3d76285 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -341,7 +341,7 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe Ordering order; if(constrainKeys) { - order = Ordering::COLAMDConstrained(variableIndex_, *constrainKeys); + order = Ordering::colamdConstrained(variableIndex_, *constrainKeys); } else { @@ -351,11 +351,11 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe FastMap constraintGroups; BOOST_FOREACH(Key var, observedKeys) constraintGroups[var] = 1; - order = Ordering::COLAMDConstrained(variableIndex_, constraintGroups); + order = Ordering::colamdConstrained(variableIndex_, constraintGroups); } else { - order = Ordering::COLAMD(variableIndex_); + order = Ordering::colamd(variableIndex_); } } gttoc(ordering); @@ -481,7 +481,7 @@ boost::shared_ptr > ISAM2::recalculate(const FastSet& markedKe // Generate ordering gttic(Ordering); - Ordering ordering = Ordering::COLAMDConstrained(affectedFactorsVarIndex, constraintGroups); + Ordering ordering = Ordering::colamdConstrained(affectedFactorsVarIndex, constraintGroups); gttoc(Ordering); ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree( diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 59acad3c3..473caa35e 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -341,10 +341,10 @@ void LevenbergMarquardtOptimizer::iterate() { LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering( LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const { if (!params.ordering){ - if (params.orderingType = OrderingType::METIS) - params.ordering = Ordering::METIS(graph); + if (params.orderingType == Ordering::METIS) + params.ordering = Ordering::metis(graph); else - params.ordering = Ordering::COLAMD(graph); + params.ordering = Ordering::colamd(graph); } return params; } diff --git a/gtsam/nonlinear/NonlinearFactorGraph.cpp b/gtsam/nonlinear/NonlinearFactorGraph.cpp index 63a1a2218..fd14750ac 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.cpp +++ b/gtsam/nonlinear/NonlinearFactorGraph.cpp @@ -282,13 +282,13 @@ FastSet NonlinearFactorGraph::keys() const { /* ************************************************************************* */ Ordering NonlinearFactorGraph::orderingCOLAMD() const { - return Ordering::COLAMD(*this); + return Ordering::colamd(*this); } /* ************************************************************************* */ Ordering NonlinearFactorGraph::orderingCOLAMDConstrained(const FastMap& constraints) const { - return Ordering::COLAMDConstrained(*this, constraints); + return Ordering::colamdConstrained(*this, constraints); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index 79bc64414..5a163ffb9 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -109,10 +109,10 @@ void NonlinearOptimizerParams::print(const std::string& str) const { } switch (orderingType){ - case OrderingType::COLAMD: + case Ordering::COLAMD: std::cout << " ordering: COLAMD\n"; break; - case OrderingType::METIS: + case Ordering::METIS: std::cout << " ordering: METIS\n"; break; default: @@ -165,11 +165,11 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve } /* ************************************************************************* */ -std::string NonlinearOptimizerParams::orderingTypeTranslator(OrderingType type) const{ +std::string NonlinearOptimizerParams::orderingTypeTranslator(Ordering::OrderingType type) const{ switch (type) { - case OrderingType::METIS: + case Ordering::METIS: return "METIS"; - case OrderingType::COLAMD: + case Ordering::COLAMD: return "COLAMD"; default: if (ordering) @@ -181,11 +181,11 @@ std::string NonlinearOptimizerParams::orderingTypeTranslator(OrderingType type) } /* ************************************************************************* */ -OrderingType NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const{ +Ordering::OrderingType NonlinearOptimizerParams::orderingTypeTranslator(const std::string& type) const{ if (type == "METIS") - return OrderingType::METIS; + return Ordering::METIS; if (type == "COLAMD") - return OrderingType::COLAMD; + return Ordering::COLAMD; throw std::invalid_argument( "Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering"); } diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index 2cb055465..10de6994f 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -43,12 +43,12 @@ public: double absoluteErrorTol; ///< The maximum absolute error decrease to stop iterating (default 1e-5) double errorTol; ///< The maximum total error to stop iterating (default 0.0) Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT) - OrderingType orderingType; ///< The method of ordering use during variable elimination (default COLAMD) + Ordering::OrderingType orderingType; ///< The method of ordering use during variable elimination (default COLAMD) NonlinearOptimizerParams() : maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol( - 0.0), verbosity(SILENT), linearSolverType(MULTIFRONTAL_CHOLESKY), orderingType(COLAMD) { - } + 0.0), verbosity(SILENT), orderingType(Ordering::COLAMD), + linearSolverType(MULTIFRONTAL_CHOLESKY) {} virtual ~NonlinearOptimizerParams() { } @@ -154,7 +154,7 @@ public: void setOrdering(const Ordering& ordering) { this->ordering = ordering; - this->orderingType = OrderingType::CUSTOM; + this->orderingType = Ordering::CUSTOM; } std::string getOrderingType() const { @@ -171,9 +171,9 @@ private: LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const; - std::string orderingTypeTranslator(OrderingType type) const; + std::string orderingTypeTranslator(Ordering::OrderingType type) const; - OrderingType orderingTypeTranslator(const std::string& type) const; + Ordering::OrderingType orderingTypeTranslator(const std::string& type) const; }; diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp index ed4b66616..05b0bb49e 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp @@ -191,7 +191,7 @@ void BatchFixedLagSmoother::reorder(const std::set& marginalizeKeys) { } // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1 - ordering_ = Ordering::COLAMDConstrainedFirst(factors_, std::vector(marginalizeKeys.begin(), marginalizeKeys.end())); + ordering_ = Ordering::colamdConstrainedFirst(factors_, std::vector(marginalizeKeys.begin(), marginalizeKeys.end())); if(debug) { ordering_.print("New Ordering: "); diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp index 3bb9c7e44..fcaae9626 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp @@ -362,9 +362,9 @@ void ConcurrentBatchFilter::reorder(const boost::optional >& keysT // COLAMD groups will be used to place marginalize keys in Group 0, and everything else in Group 1 if(keysToMove && keysToMove->size() > 0) { - ordering_ = Ordering::COLAMDConstrainedFirst(factors_, std::vector(keysToMove->begin(), keysToMove->end())); + ordering_ = Ordering::colamdConstrainedFirst(factors_, std::vector(keysToMove->begin(), keysToMove->end())); }else{ - ordering_ = Ordering::COLAMD(factors_); + ordering_ = Ordering::colamd(factors_); } } diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp index 8606538bf..0f6515056 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp +++ b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.cpp @@ -231,7 +231,7 @@ void ConcurrentBatchSmoother::reorder() { variableIndex_ = VariableIndex(factors_); FastList separatorKeys = separatorValues_.keys(); - ordering_ = Ordering::COLAMDConstrainedLast(variableIndex_, std::vector(separatorKeys.begin(), separatorKeys.end())); + ordering_ = Ordering::colamdConstrainedLast(variableIndex_, std::vector(separatorKeys.begin(), separatorKeys.end())); } diff --git a/tests/testNonlinearFactorGraph.cpp b/tests/testNonlinearFactorGraph.cpp index 9c2eddcc3..f398a33fe 100644 --- a/tests/testNonlinearFactorGraph.cpp +++ b/tests/testNonlinearFactorGraph.cpp @@ -79,14 +79,14 @@ TEST( NonlinearFactorGraph, GET_ORDERING) { Ordering expected; expected += L(1), X(2), X(1); // For starting with l1,x1,x2 NonlinearFactorGraph nlfg = createNonlinearFactorGraph(); - Ordering actual = Ordering::COLAMD(nlfg); + Ordering actual = Ordering::colamd(nlfg); EXPECT(assert_equal(expected,actual)); // Constrained ordering - put x2 at the end Ordering expectedConstrained; expectedConstrained += L(1), X(1), X(2); FastMap constraints; constraints[X(2)] = 1; - Ordering actualConstrained = Ordering::COLAMDConstrained(nlfg, constraints); + Ordering actualConstrained = Ordering::colamdConstrained(nlfg, constraints); EXPECT(assert_equal(expectedConstrained, actualConstrained)); } From b19ed67545109307c3e0c4db769b6e249ce88ab7 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Fri, 21 Nov 2014 15:23:01 -0500 Subject: [PATCH 20/32] Work in progress on correcting bug with key casting to int32. Causes overflow on cast, causing bad array indexing in metis --- examples/StereoVOExample_large.cpp | 4 ++- gtsam/inference/MetisIndex-inl.h | 4 +-- gtsam/inference/MetisIndex.h | 8 +++--- gtsam/inference/Ordering.cpp | 43 +++++++++++++++++++++++++----- 4 files changed, 46 insertions(+), 13 deletions(-) diff --git a/examples/StereoVOExample_large.cpp b/examples/StereoVOExample_large.cpp index b9ab663d9..4d39a191a 100644 --- a/examples/StereoVOExample_large.cpp +++ b/examples/StereoVOExample_large.cpp @@ -103,7 +103,9 @@ int main(int argc, char** argv){ cout << "Optimizing" << endl; //create Levenberg-Marquardt optimizer to optimize the factor graph - LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate); + LevenbergMarquardtParams params; + params.orderingType = OrderingType::METIS; + LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate, params); Values result = optimizer.optimize(); cout << "Final result sample:" << endl; diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index d9fb4cfd1..006ba075f 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -27,8 +27,8 @@ namespace gtsam { template void MetisIndex::augment(const FactorGraph& factors) { - std::map > adjMap; - std::map >::iterator adjMapIt; + std::map > adjMap; + std::map >::iterator adjMapIt; std::set keySet; /* ********** Convert to CSR format ********** */ diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index b058b5564..476d34980 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -40,8 +40,8 @@ public: typedef boost::shared_ptr shared_ptr; private: - FastVector xadj_; // Index of node's adjacency list in adj - FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector + FastVector xadj_; // Index of node's adjacency list in adj + FastVector 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 nKeys_; // size_t minKey_; @@ -69,8 +69,8 @@ public: template void augment(const FactorGraph& factors); - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } size_t nValues() const { return nKeys_; } size_t minKey() const { return minKey_; } diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 654740163..e54ad3fde 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -204,12 +204,43 @@ namespace gtsam { { gttic(Ordering_METIS); - vector xadj = met.xadj(); - vector adj = met.adj(); - size_t minKey = met.minKey(); + vector xadj = met.xadj(); + vector adj = met.adj(); + Key minKey = met.minKey(); + + // TODO(Andrew): Debug + Key min = std::numeric_limits::max(); + for (int i = 0; i < adj.size(); i++) + { + if (adj[i] < min) + min = adj[i]; + } + + std::cout << "Min: " << min << " minkey: " << minKey << std::endl; // Normalize, subtract the smallest key - std::transform(adj.begin(), adj.end(), adj.begin(), std::bind2nd(std::minus(), minKey)); + //std::transform(adj.begin(), adj.end(), adj.begin(), std::bind2nd(std::minus(), minKey)); + for (vector::iterator it = adj.begin(); it != adj.end(); ++it) + *it = *it - minKey; + + // Cast the adjacency formats into idx_t (int32) + // NOTE: Keys can store quite large values and hence may overflow during conversion to int + // It's important that the normalization is performed first. + vector adj_idx; + for (vector::iterator it = adj.begin(); it != adj.end(); ++it) + adj_idx.push_back(static_cast(*it)); + + vector xadj_idx; + for (vector::iterator it = xadj.begin(); it != xadj.end(); ++it) + xadj_idx.push_back(static_cast(*it)); + + // TODO(Andrew): Debug + for (int i = 0; i < adj.size(); i++) + { + assert(adj[i] >= 0); + if (adj[i] < 0) + std::cout << adj[i] << std::endl; + } vector perm, iperm; @@ -222,7 +253,7 @@ namespace gtsam { int outputError; - outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); + outputError = METIS_NodeND(&size, &xadj_idx[0], &adj_idx[0], NULL, NULL, &perm[0], &iperm[0]); Ordering result; if (outputError != METIS_OK) @@ -234,7 +265,7 @@ namespace gtsam { result.resize(size); for (size_t j = 0; j < size; ++j){ // We have to add the minKey value back to obtain the original key in the Values - result[j] = perm[j] + minKey; + result[j] = (Key)perm[j] + minKey; } return result; } From 7aa07a9e16a99625ca1954317837c779c97a2585 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 02:06:40 -0500 Subject: [PATCH 21/32] Reworked ordering to work with symbols, large keys, and non-zero indexed keys. No longer subtract min key to send to metis, but now creates bimap between keys and int values used in metis --- gtsam/inference/MetisIndex-inl.h | 46 +++++++++++------- gtsam/inference/MetisIndex.h | 27 +++++++---- gtsam/inference/Ordering.cpp | 64 ++++++-------------------- gtsam/inference/tests/testOrdering.cpp | 8 ++-- 4 files changed, 64 insertions(+), 81 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index 006ba075f..b9272990a 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -27,8 +27,8 @@ namespace gtsam { template void MetisIndex::augment(const FactorGraph& factors) { - std::map > adjMap; - std::map >::iterator adjMapIt; + std::map > iAdjMap; // Stores a set of keys that are adjacent to key x, with adjMap.first + std::map >::iterator iAdjMapIt; std::set keySet; /* ********** Convert to CSR format ********** */ @@ -37,31 +37,43 @@ void MetisIndex::augment(const FactorGraph& factors) // 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]). + idx_t keyCounter = 0; + + // First: Record a copy of each key inside the factorgraph and create a + // key to integer mapping. This is referenced during the adjaceny step + for (size_t i = 0; i < factors.size(); i++){ + if (factors[i]) + BOOST_FOREACH(const Key& key, *factors[i]){ + keySet.insert(keySet.end(), key); // Keep a track of all unique keys + if (intKeyBMap_.left.find(key) == intKeyBMap_.left.end()){ + intKeyBMap_.insert(bm_type::value_type(key, keyCounter)); + keyCounter++; + } + } + } + + // Create an adjacency mapping that stores the set of all adjacent keys for every key 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 - } - keySet.insert(keySet.end(), k1); // Keep a track of all unique keySet - } + BOOST_FOREACH(const Key& k1, *factors[i]) + BOOST_FOREACH(const Key& k2, *factors[i]) + if (k1 != k2){ + // Store both in Key and idx_t format + int i = intKeyBMap_.left.at(k1); + int j = intKeyBMap_.left.at(k2); + iAdjMap[i].insert(iAdjMap[i].end(), j); + } } } // Number of keys referenced in this factor graph nKeys_ = keySet.size(); - - - // Starting with a nonzero key crashes METIS - // Find the smallest key in the graph - minKey_ = *keySet.begin(); // set is ordered xadj_.push_back(0);// Always set the first index to zero - for (adjMapIt = adjMap.begin(); adjMapIt != adjMap.end(); ++adjMapIt) { - std::vector temp; + for (iAdjMapIt = iAdjMap.begin(); iAdjMapIt != iAdjMap.end(); ++iAdjMapIt) { + std::vector temp; // Copy from the FastSet into a temporary vector - std::copy(adjMapIt->second.begin(), adjMapIt->second.end(), std::back_inserter(temp)); + std::copy(iAdjMapIt->second.begin(), iAdjMapIt->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); diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 476d34980..e3b7ea33d 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -25,12 +25,14 @@ #include #include #include +#include +#include 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 + * from a factor graph prior to elimination, and stores the list of factors * that involve each variable. * \nosubgrouping */ @@ -38,13 +40,15 @@ class GTSAM_EXPORT MetisIndex { public: typedef boost::shared_ptr shared_ptr; + typedef boost::bimap bm_type; private: - FastVector xadj_; // Index of node's adjacency list in adj - FastVector 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 nKeys_; // - size_t minKey_; + FastVector xadj_; // Index of node's adjacency list in adj + FastVector adj_; // Stores ajacency lists of all nodes, appended into a single vector + FastVector iadj_; // Integer keys for passing into metis. One to one mapping with adj_; + boost::bimap intKeyBMap_; // Stores Key <-> integer value relationship + size_t nFactors_; // Number of factors in the original factor graph + size_t nKeys_; public: /// @name Standard Constructors @@ -69,10 +73,13 @@ public: template void augment(const FactorGraph& factors); - std::vector xadj() const { return xadj_; } - std::vector adj() const { return adj_; } - size_t nValues() const { return nKeys_; } - size_t minKey() const { return minKey_; } + std::vector xadj() const { return xadj_; } + std::vector adj() const { return adj_; } + size_t nValues() const { return nKeys_; } + Key intToKey(idx_t value) const { + assert(value >= 0); + return intKeyBMap_.right.find(value)->second; + } /// @} }; diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index dcc2bd00a..a069fd4f6 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -204,56 +204,20 @@ namespace gtsam { { gttic(Ordering_METIS); - vector xadj = met.xadj(); - vector adj = met.adj(); - Key minKey = met.minKey(); - - // TODO(Andrew): Debug - Key min = std::numeric_limits::max(); - for (int i = 0; i < adj.size(); i++) - { - if (adj[i] < min) - min = adj[i]; - } - - std::cout << "Min: " << min << " minkey: " << minKey << std::endl; - - // Normalize, subtract the smallest key - //std::transform(adj.begin(), adj.end(), adj.begin(), std::bind2nd(std::minus(), minKey)); - for (vector::iterator it = adj.begin(); it != adj.end(); ++it) - *it = *it - minKey; - - // Cast the adjacency formats into idx_t (int32) - // NOTE: Keys can store quite large values and hence may overflow during conversion to int - // It's important that the normalization is performed first. - vector adj_idx; - for (vector::iterator it = adj.begin(); it != adj.end(); ++it) - adj_idx.push_back(static_cast(*it)); - - vector xadj_idx; - for (vector::iterator it = xadj.begin(); it != xadj.end(); ++it) - xadj_idx.push_back(static_cast(*it)); - - // TODO(Andrew): Debug - for (int i = 0; i < adj.size(); i++) - { - assert(adj[i] >= 0); - if (adj[i] < 0) - std::cout << adj[i] << std::endl; - } - + vector xadj = met.xadj(); + vector adj = met.adj(); vector perm, iperm; - idx_t size = met.nValues(); - for (idx_t i = 0; i < size; i++) - { - perm.push_back(0); - iperm.push_back(0); - } + idx_t size = met.nValues(); + for (idx_t i = 0; i < size; i++) + { + perm.push_back(0); + iperm.push_back(0); + } int outputError; - outputError = METIS_NodeND(&size, &xadj_idx[0], &adj_idx[0], NULL, NULL, &perm[0], &iperm[0]); + outputError = METIS_NodeND(&size, &xadj[0], &adj[0], NULL, NULL, &perm[0], &iperm[0]); Ordering result; if (outputError != METIS_OK) @@ -262,11 +226,11 @@ namespace gtsam { return result; } - result.resize(size); - for (size_t j = 0; j < size; ++j){ - // We have to add the minKey value back to obtain the original key in the Values - result[j] = (Key)perm[j] + minKey; - } + result.resize(size); + for (size_t j = 0; j < size; ++j){ + // We have to add the minKey value back to obtain the original key in the Values + result[j] = met.intToKey(perm[j]); + } return result; } diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 57de00646..5cd4c77b2 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -159,18 +159,18 @@ TEST(Ordering, csr_format_3) { vector xadjExpected, adjExpected; xadjExpected += 0, 1, 4, 6, 8, 10; adjExpected += 1, 0, 2, 4, 1, 3, 2, 4, 1, 3; - size_t minKey = mi.minKey(); + //size_t minKey = mi.minKey(); vector adjAcutal = mi.adj(); // Normalize, subtract the smallest key - std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(), - std::bind2nd(std::minus(), minKey)); + //std::transform(adjAcutal.begin(), adjAcutal.end(), adjAcutal.begin(), + // std::bind2nd(std::minus(), minKey)); EXPECT(xadjExpected == mi.xadj()); EXPECT(adjExpected.size() == mi.adj().size()); EXPECT(adjExpected == adjAcutal); - + } /* ************************************************************************* */ From 6fd24118be3791aa0f8257c5ad143110661d2fb4 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 24 Nov 2014 12:37:17 -0500 Subject: [PATCH 22/32] Fix gcc warnings --- gtsam/inference/MetisIndex-inl.h | 3 ++- gtsam/inference/Ordering.cpp | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index b9272990a..a8e9aef2f 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -42,7 +42,7 @@ void MetisIndex::augment(const FactorGraph& factors) // First: Record a copy of each key inside the factorgraph and create a // key to integer mapping. This is referenced during the adjaceny step for (size_t i = 0; i < factors.size(); i++){ - if (factors[i]) + if (factors[i]) { BOOST_FOREACH(const Key& key, *factors[i]){ keySet.insert(keySet.end(), key); // Keep a track of all unique keys if (intKeyBMap_.left.find(key) == intKeyBMap_.left.end()){ @@ -50,6 +50,7 @@ void MetisIndex::augment(const FactorGraph& factors) keyCounter++; } } + } } // Create an adjacency mapping that stores the set of all adjacent keys for every key diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index a069fd4f6..81f9ddb5c 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -227,7 +227,7 @@ namespace gtsam { } result.resize(size); - for (size_t j = 0; j < size; ++j){ + for (size_t j = 0; j < (size_t)size; ++j){ // We have to add the minKey value back to obtain the original key in the Values result[j] = met.intToKey(perm[j]); } From 8678754dbd2e7dded3212d3f1fc421e9968d93be Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 12:41:24 -0500 Subject: [PATCH 23/32] Ordering test for symbols --- gtsam/inference/tests/testOrdering.cpp | 37 ++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 5cd4c77b2..013f569e0 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -173,6 +173,43 @@ TEST(Ordering, csr_format_3) { } +/* ************************************************************************* */ +TEST(Ordering, csr_format_4) { + SymbolicFactorGraph sfg; + + sfg.push_factor(Symbol('x', 1)); + sfg.push_factor(Symbol('x', 1), Symbol('x', 2)); + sfg.push_factor(Symbol('x', 2), Symbol('x', 3)); + sfg.push_factor(Symbol('x', 3), Symbol('x', 4)); + sfg.push_factor(Symbol('x', 4), Symbol('x', 5)); + sfg.push_factor(Symbol('x', 5), Symbol('x', 6)); + + MetisIndex mi(sfg); + + vector xadjExpected, adjExpected; + xadjExpected += 0, 1, 3, 5, 7, 9, 10; + adjExpected += 1, 0, 2, 1, 3, 2, 4, 3, 5, 4; + + vector adjAcutal = mi.adj(); + vector xadjActual = mi.xadj(); + + EXPECT(xadjExpected == mi.xadj()); + EXPECT(adjExpected.size() == mi.adj().size()); + EXPECT(adjExpected == adjAcutal); + + Ordering metOrder = Ordering::metis(sfg); + + // Test different symbol types + sfg.push_factor(Symbol('l', 1)); + sfg.push_factor(Symbol('x', 1), Symbol('l', 1)); + sfg.push_factor(Symbol('x', 2), Symbol('l', 1)); + sfg.push_factor(Symbol('x', 3), Symbol('l', 1)); + sfg.push_factor(Symbol('x', 4), Symbol('l', 1)); + + Ordering metOrder2 = Ordering::metis(sfg); + +} + /* ************************************************************************* */ TEST(Ordering, metis) { From e8e502137b9ab4c0cff10bf6c6bbfa4cb4bb95e3 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 12:50:55 -0500 Subject: [PATCH 24/32] Update ordering --- examples/StereoVOExample_large.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/StereoVOExample_large.cpp b/examples/StereoVOExample_large.cpp index 4d39a191a..e357745be 100644 --- a/examples/StereoVOExample_large.cpp +++ b/examples/StereoVOExample_large.cpp @@ -104,7 +104,7 @@ int main(int argc, char** argv){ cout << "Optimizing" << endl; //create Levenberg-Marquardt optimizer to optimize the factor graph LevenbergMarquardtParams params; - params.orderingType = OrderingType::METIS; + params.orderingType = Ordering::METIS; LevenbergMarquardtOptimizer optimizer = LevenbergMarquardtOptimizer(graph, initial_estimate, params); Values result = optimizer.optimize(); From b76185cf5e2ad8136b3b47369bdfcfe74a50086e Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 13:02:27 -0500 Subject: [PATCH 25/32] Include metis.h correction --- gtsam/inference/MetisIndex.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index e3b7ea33d..684755895 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -25,7 +25,7 @@ #include #include #include -#include +#include #include namespace gtsam { From ce93030b0005df1506bef578bf2c183925c032ca Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 13:31:47 -0500 Subject: [PATCH 26/32] Correcting warnings on windows --- CMakeLists.txt | 2 ++ gtsam/3rdparty/metis-5.1.0/include/metis.h | 14 +++++++++++++- gtsam/CMakeLists.txt | 4 ++-- gtsam/inference/MetisIndex-inl.h | 2 +- 4 files changed, 18 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 951a0ec7e..b2e7aa3d9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -95,6 +95,8 @@ if(MSVC) add_definitions(-DBOOST_ALL_NO_LIB) add_definitions(-DBOOST_ALL_DYN_LINK) endif() + # Also disable certain warnings + add_definitions(/wd4503) endif() find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time regex timer chrono) diff --git a/gtsam/3rdparty/metis-5.1.0/include/metis.h b/gtsam/3rdparty/metis-5.1.0/include/metis.h index dc5406ae5..2866a946b 100644 --- a/gtsam/3rdparty/metis-5.1.0/include/metis.h +++ b/gtsam/3rdparty/metis-5.1.0/include/metis.h @@ -65,17 +65,29 @@ #ifndef _GKLIB_H_ #ifdef COMPILER_MSC #include - typedef __int32 int32_t; typedef __int64 int64_t; #define PRId32 "I32d" #define PRId64 "I64d" #define SCNd32 "ld" #define SCNd64 "I64d" + +#ifndef INT32_MIN #define INT32_MIN ((int32_t)_I32_MIN) +#endif + +#ifndef INT32_MAX #define INT32_MAX _I32_MAX +#endif + +#ifndef INT64_MIN #define INT64_MIN ((int64_t)_I64_MIN) +#endif + +#ifndef INT64_MAX #define INT64_MAX _I64_MAX +#endif + #else #include #endif diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 2d5706f33..d08ded7e8 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -5,7 +5,7 @@ set (gtsam_subdirs base geometry inference - symbolic + symbolic discrete linear nonlinear @@ -69,7 +69,7 @@ set(gtsam_srcs ${base_srcs} ${geometry_srcs} ${inference_srcs} - ${symbolic_srcs} + ${symbolic_srcs} ${discrete_srcs} ${linear_srcs} ${nonlinear_srcs} diff --git a/gtsam/inference/MetisIndex-inl.h b/gtsam/inference/MetisIndex-inl.h index a8e9aef2f..0be1c503c 100644 --- a/gtsam/inference/MetisIndex-inl.h +++ b/gtsam/inference/MetisIndex-inl.h @@ -78,7 +78,7 @@ void MetisIndex::augment(const FactorGraph& factors) // 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()); + xadj_.push_back((idx_t)adj_.size()); } } From 96e649b1a49aabf4ca66cabafdfab4d9fc90fd24 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 13:33:36 -0500 Subject: [PATCH 27/32] Formatting --- gtsam/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index d08ded7e8..ada7ae12d 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -5,7 +5,7 @@ set (gtsam_subdirs base geometry inference - symbolic + symbolic discrete linear nonlinear @@ -69,7 +69,7 @@ set(gtsam_srcs ${base_srcs} ${geometry_srcs} ${inference_srcs} - ${symbolic_srcs} + ${symbolic_srcs} ${discrete_srcs} ${linear_srcs} ${nonlinear_srcs} From c5cee669b130dd57f2626c900020b3cbaa4b995c Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 13:41:08 -0500 Subject: [PATCH 28/32] Formatting --- gtsam/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index ada7ae12d..b58a5b4b8 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -10,7 +10,7 @@ set (gtsam_subdirs linear nonlinear slam - navigation + navigation ) set(gtsam_srcs) @@ -74,8 +74,8 @@ set(gtsam_srcs ${linear_srcs} ${nonlinear_srcs} ${slam_srcs} - ${navigation_srcs} - ${gtsam_core_headers} + ${navigation_srcs} + ${gtsam_core_headers} ) # Generate and install config and dllexport files From 9d3aa9c61820c37b8adba4dd8e6a9ba40bff24b5 Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 13:43:29 -0500 Subject: [PATCH 29/32] Remove version info from metis folder name --- .../{metis-5.1.0 => metis}/BUILD-Windows.txt | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/BUILD.txt | 0 .../3rdparty/{metis-5.1.0 => metis}/CMakeLists.txt | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/Changelog | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/BUILD.txt | 0 .../{metis-5.1.0 => metis}/GKlib/CMakeLists.txt | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/GKlib.h | 0 .../{metis-5.1.0 => metis}/GKlib/GKlibSystem.cmake | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/Makefile | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/b64.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/blas.c | 0 .../GKlib/conf/check_thread_storage.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/csr.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/error.c | 0 .../{metis-5.1.0 => metis}/GKlib/evaluate.c | 0 .../{metis-5.1.0 => metis}/GKlib/fkvkselect.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/fs.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/getopt.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/gk_arch.h | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/gk_defs.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_externs.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_getopt.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_macros.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkblas.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkmemory.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkpqueue.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkpqueue2.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkrandom.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mksort.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_mkutils.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_proto.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_struct.h | 0 .../{metis-5.1.0 => metis}/GKlib/gk_types.h | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/gkregex.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/gkregex.h | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/graph.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/htable.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/io.c | 0 .../{metis-5.1.0 => metis}/GKlib/itemsets.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/mcore.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/memory.c | 0 .../{metis-5.1.0 => metis}/GKlib/ms_inttypes.h | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/ms_stat.h | 0 .../{metis-5.1.0 => metis}/GKlib/ms_stdint.h | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/omp.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/pdb.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/pqueue.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/random.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/rw.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/seq.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/sort.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/string.c | 0 .../GKlib/test/CMakeLists.txt | 0 .../GKlib/test/Makefile.in.old | 0 .../{metis-5.1.0 => metis}/GKlib/test/Makefile.old | 0 .../{metis-5.1.0 => metis}/GKlib/test/fis.c | 0 .../{metis-5.1.0 => metis}/GKlib/test/gkgraph.c | 0 .../{metis-5.1.0 => metis}/GKlib/test/gksort.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/test/rw.c | 0 .../{metis-5.1.0 => metis}/GKlib/test/strings.c | 0 .../3rdparty/{metis-5.1.0 => metis}/GKlib/timers.c | 0 .../{metis-5.1.0 => metis}/GKlib/tokenizer.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/util.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/Install.txt | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/LICENSE.txt | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/Makefile | 0 .../{metis-5.1.0 => metis}/graphs/4elt.graph | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/README | 0 .../{metis-5.1.0 => metis}/graphs/copter2.graph | 0 .../{metis-5.1.0 => metis}/graphs/mdual.graph | 0 .../{metis-5.1.0 => metis}/graphs/metis.mesh | 0 .../{metis-5.1.0 => metis}/graphs/test.mgraph | 0 .../{metis-5.1.0 => metis}/include/CMakeLists.txt | 0 .../3rdparty/{metis-5.1.0 => metis}/include/metis.h | 0 .../{metis-5.1.0 => metis}/libmetis/CMakeLists.txt | 0 .../{metis-5.1.0 => metis}/libmetis/auxapi.c | 0 .../{metis-5.1.0 => metis}/libmetis/balance.c | 0 .../{metis-5.1.0 => metis}/libmetis/bucketsort.c | 0 .../{metis-5.1.0 => metis}/libmetis/checkgraph.c | 0 .../{metis-5.1.0 => metis}/libmetis/coarsen.c | 0 .../{metis-5.1.0 => metis}/libmetis/compress.c | 0 .../{metis-5.1.0 => metis}/libmetis/contig.c | 0 .../{metis-5.1.0 => metis}/libmetis/debug.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/defs.h | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/fm.c | 0 .../{metis-5.1.0 => metis}/libmetis/fortran.c | 0 .../{metis-5.1.0 => metis}/libmetis/frename.c | 0 .../{metis-5.1.0 => metis}/libmetis/gklib.c | 0 .../{metis-5.1.0 => metis}/libmetis/gklib_defs.h | 0 .../{metis-5.1.0 => metis}/libmetis/gklib_rename.h | 0 .../{metis-5.1.0 => metis}/libmetis/graph.c | 0 .../{metis-5.1.0 => metis}/libmetis/initpart.c | 0 .../{metis-5.1.0 => metis}/libmetis/kmetis.c | 0 .../{metis-5.1.0 => metis}/libmetis/kwayfm.c | 0 .../{metis-5.1.0 => metis}/libmetis/kwayrefine.c | 0 .../{metis-5.1.0 => metis}/libmetis/macros.h | 0 .../{metis-5.1.0 => metis}/libmetis/mcutil.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/mesh.c | 0 .../{metis-5.1.0 => metis}/libmetis/meshpart.c | 0 .../{metis-5.1.0 => metis}/libmetis/metislib.h | 0 .../{metis-5.1.0 => metis}/libmetis/minconn.c | 0 .../{metis-5.1.0 => metis}/libmetis/mincover.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/mmd.c | 0 .../{metis-5.1.0 => metis}/libmetis/ometis.c | 0 .../{metis-5.1.0 => metis}/libmetis/options.c | 0 .../{metis-5.1.0 => metis}/libmetis/parmetis.c | 0 .../{metis-5.1.0 => metis}/libmetis/pmetis.c | 0 .../{metis-5.1.0 => metis}/libmetis/proto.h | 0 .../{metis-5.1.0 => metis}/libmetis/refine.c | 0 .../{metis-5.1.0 => metis}/libmetis/rename.h | 0 .../{metis-5.1.0 => metis}/libmetis/separator.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/sfm.c | 0 .../{metis-5.1.0 => metis}/libmetis/srefine.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/stat.c | 0 .../{metis-5.1.0 => metis}/libmetis/stdheaders.h | 0 .../{metis-5.1.0 => metis}/libmetis/struct.h | 0 .../{metis-5.1.0 => metis}/libmetis/timing.c | 0 .../3rdparty/{metis-5.1.0 => metis}/libmetis/util.c | 0 .../{metis-5.1.0 => metis}/libmetis/wspace.c | 0 .../{metis-5.1.0 => metis}/manual/manual.pdf | Bin .../{metis-5.1.0 => metis}/programs/CMakeLists.txt | 0 .../programs/cmdline_gpmetis.c | 0 .../programs/cmdline_m2gmetis.c | 0 .../programs/cmdline_mpmetis.c | 0 .../programs/cmdline_ndmetis.c | 0 .../{metis-5.1.0 => metis}/programs/cmpfillin.c | 0 .../3rdparty/{metis-5.1.0 => metis}/programs/defs.h | 0 .../{metis-5.1.0 => metis}/programs/gpmetis.c | 0 .../{metis-5.1.0 => metis}/programs/graphchk.c | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/programs/io.c | 0 .../{metis-5.1.0 => metis}/programs/m2gmetis.c | 0 .../{metis-5.1.0 => metis}/programs/metisbin.h | 0 .../{metis-5.1.0 => metis}/programs/mpmetis.c | 0 .../{metis-5.1.0 => metis}/programs/ndmetis.c | 0 .../{metis-5.1.0 => metis}/programs/proto.h | 0 .../{metis-5.1.0 => metis}/programs/smbfactor.c | 0 .../3rdparty/{metis-5.1.0 => metis}/programs/stat.c | 0 .../{metis-5.1.0 => metis}/programs/struct.h | 0 gtsam/3rdparty/{metis-5.1.0 => metis}/vsgen.bat | 0 139 files changed, 0 insertions(+), 0 deletions(-) rename gtsam/3rdparty/{metis-5.1.0 => metis}/BUILD-Windows.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/BUILD.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/Changelog (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/BUILD.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/GKlib.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/GKlibSystem.cmake (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/Makefile (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/b64.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/blas.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/conf/check_thread_storage.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/csr.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/error.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/evaluate.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/fkvkselect.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/fs.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/getopt.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_arch.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_defs.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_externs.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_getopt.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_macros.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkblas.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkmemory.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkpqueue.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkpqueue2.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkrandom.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mksort.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_mkutils.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_proto.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_struct.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gk_types.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gkregex.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/gkregex.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/graph.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/htable.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/io.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/itemsets.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/mcore.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/memory.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/ms_inttypes.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/ms_stat.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/ms_stdint.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/omp.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/pdb.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/pqueue.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/random.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/rw.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/seq.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/sort.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/string.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/Makefile.in.old (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/Makefile.old (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/fis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/gkgraph.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/gksort.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/rw.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/test/strings.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/timers.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/tokenizer.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/GKlib/util.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/Install.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/LICENSE.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/Makefile (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/4elt.graph (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/README (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/copter2.graph (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/mdual.graph (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/metis.mesh (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/graphs/test.mgraph (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/include/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/include/metis.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/auxapi.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/balance.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/bucketsort.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/checkgraph.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/coarsen.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/compress.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/contig.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/debug.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/defs.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/fm.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/fortran.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/frename.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/gklib.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/gklib_defs.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/gklib_rename.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/graph.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/initpart.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/kmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/kwayfm.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/kwayrefine.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/macros.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/mcutil.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/mesh.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/meshpart.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/metislib.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/minconn.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/mincover.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/mmd.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/ometis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/options.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/parmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/pmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/proto.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/refine.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/rename.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/separator.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/sfm.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/srefine.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/stat.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/stdheaders.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/struct.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/timing.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/util.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/libmetis/wspace.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/manual/manual.pdf (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/CMakeLists.txt (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/cmdline_gpmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/cmdline_m2gmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/cmdline_mpmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/cmdline_ndmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/cmpfillin.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/defs.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/gpmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/graphchk.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/io.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/m2gmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/metisbin.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/mpmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/ndmetis.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/proto.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/smbfactor.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/stat.c (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/programs/struct.h (100%) rename gtsam/3rdparty/{metis-5.1.0 => metis}/vsgen.bat (100%) diff --git a/gtsam/3rdparty/metis-5.1.0/BUILD-Windows.txt b/gtsam/3rdparty/metis/BUILD-Windows.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/BUILD-Windows.txt rename to gtsam/3rdparty/metis/BUILD-Windows.txt diff --git a/gtsam/3rdparty/metis-5.1.0/BUILD.txt b/gtsam/3rdparty/metis/BUILD.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/BUILD.txt rename to gtsam/3rdparty/metis/BUILD.txt diff --git a/gtsam/3rdparty/metis-5.1.0/CMakeLists.txt b/gtsam/3rdparty/metis/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/CMakeLists.txt rename to gtsam/3rdparty/metis/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/Changelog b/gtsam/3rdparty/metis/Changelog similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/Changelog rename to gtsam/3rdparty/metis/Changelog diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/BUILD.txt b/gtsam/3rdparty/metis/GKlib/BUILD.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/BUILD.txt rename to gtsam/3rdparty/metis/GKlib/BUILD.txt diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/CMakeLists.txt b/gtsam/3rdparty/metis/GKlib/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/CMakeLists.txt rename to gtsam/3rdparty/metis/GKlib/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/GKlib.h b/gtsam/3rdparty/metis/GKlib/GKlib.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/GKlib.h rename to gtsam/3rdparty/metis/GKlib/GKlib.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/GKlibSystem.cmake b/gtsam/3rdparty/metis/GKlib/GKlibSystem.cmake similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/GKlibSystem.cmake rename to gtsam/3rdparty/metis/GKlib/GKlibSystem.cmake diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/Makefile b/gtsam/3rdparty/metis/GKlib/Makefile similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/Makefile rename to gtsam/3rdparty/metis/GKlib/Makefile diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/b64.c b/gtsam/3rdparty/metis/GKlib/b64.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/b64.c rename to gtsam/3rdparty/metis/GKlib/b64.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/blas.c b/gtsam/3rdparty/metis/GKlib/blas.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/blas.c rename to gtsam/3rdparty/metis/GKlib/blas.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/conf/check_thread_storage.c b/gtsam/3rdparty/metis/GKlib/conf/check_thread_storage.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/conf/check_thread_storage.c rename to gtsam/3rdparty/metis/GKlib/conf/check_thread_storage.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/csr.c b/gtsam/3rdparty/metis/GKlib/csr.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/csr.c rename to gtsam/3rdparty/metis/GKlib/csr.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/error.c b/gtsam/3rdparty/metis/GKlib/error.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/error.c rename to gtsam/3rdparty/metis/GKlib/error.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/evaluate.c b/gtsam/3rdparty/metis/GKlib/evaluate.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/evaluate.c rename to gtsam/3rdparty/metis/GKlib/evaluate.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/fkvkselect.c b/gtsam/3rdparty/metis/GKlib/fkvkselect.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/fkvkselect.c rename to gtsam/3rdparty/metis/GKlib/fkvkselect.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/fs.c b/gtsam/3rdparty/metis/GKlib/fs.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/fs.c rename to gtsam/3rdparty/metis/GKlib/fs.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/getopt.c b/gtsam/3rdparty/metis/GKlib/getopt.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/getopt.c rename to gtsam/3rdparty/metis/GKlib/getopt.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h b/gtsam/3rdparty/metis/GKlib/gk_arch.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_arch.h rename to gtsam/3rdparty/metis/GKlib/gk_arch.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_defs.h b/gtsam/3rdparty/metis/GKlib/gk_defs.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_defs.h rename to gtsam/3rdparty/metis/GKlib/gk_defs.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_externs.h b/gtsam/3rdparty/metis/GKlib/gk_externs.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_externs.h rename to gtsam/3rdparty/metis/GKlib/gk_externs.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_getopt.h b/gtsam/3rdparty/metis/GKlib/gk_getopt.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_getopt.h rename to gtsam/3rdparty/metis/GKlib/gk_getopt.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_macros.h b/gtsam/3rdparty/metis/GKlib/gk_macros.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_macros.h rename to gtsam/3rdparty/metis/GKlib/gk_macros.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkblas.h b/gtsam/3rdparty/metis/GKlib/gk_mkblas.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkblas.h rename to gtsam/3rdparty/metis/GKlib/gk_mkblas.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkmemory.h b/gtsam/3rdparty/metis/GKlib/gk_mkmemory.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkmemory.h rename to gtsam/3rdparty/metis/GKlib/gk_mkmemory.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkpqueue.h b/gtsam/3rdparty/metis/GKlib/gk_mkpqueue.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkpqueue.h rename to gtsam/3rdparty/metis/GKlib/gk_mkpqueue.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkpqueue2.h b/gtsam/3rdparty/metis/GKlib/gk_mkpqueue2.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkpqueue2.h rename to gtsam/3rdparty/metis/GKlib/gk_mkpqueue2.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkrandom.h b/gtsam/3rdparty/metis/GKlib/gk_mkrandom.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkrandom.h rename to gtsam/3rdparty/metis/GKlib/gk_mkrandom.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mksort.h b/gtsam/3rdparty/metis/GKlib/gk_mksort.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mksort.h rename to gtsam/3rdparty/metis/GKlib/gk_mksort.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkutils.h b/gtsam/3rdparty/metis/GKlib/gk_mkutils.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_mkutils.h rename to gtsam/3rdparty/metis/GKlib/gk_mkutils.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_proto.h b/gtsam/3rdparty/metis/GKlib/gk_proto.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_proto.h rename to gtsam/3rdparty/metis/GKlib/gk_proto.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_struct.h b/gtsam/3rdparty/metis/GKlib/gk_struct.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_struct.h rename to gtsam/3rdparty/metis/GKlib/gk_struct.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gk_types.h b/gtsam/3rdparty/metis/GKlib/gk_types.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gk_types.h rename to gtsam/3rdparty/metis/GKlib/gk_types.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gkregex.c b/gtsam/3rdparty/metis/GKlib/gkregex.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gkregex.c rename to gtsam/3rdparty/metis/GKlib/gkregex.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/gkregex.h b/gtsam/3rdparty/metis/GKlib/gkregex.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/gkregex.h rename to gtsam/3rdparty/metis/GKlib/gkregex.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/graph.c b/gtsam/3rdparty/metis/GKlib/graph.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/graph.c rename to gtsam/3rdparty/metis/GKlib/graph.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/htable.c b/gtsam/3rdparty/metis/GKlib/htable.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/htable.c rename to gtsam/3rdparty/metis/GKlib/htable.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/io.c b/gtsam/3rdparty/metis/GKlib/io.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/io.c rename to gtsam/3rdparty/metis/GKlib/io.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/itemsets.c b/gtsam/3rdparty/metis/GKlib/itemsets.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/itemsets.c rename to gtsam/3rdparty/metis/GKlib/itemsets.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/mcore.c b/gtsam/3rdparty/metis/GKlib/mcore.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/mcore.c rename to gtsam/3rdparty/metis/GKlib/mcore.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/memory.c b/gtsam/3rdparty/metis/GKlib/memory.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/memory.c rename to gtsam/3rdparty/metis/GKlib/memory.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/ms_inttypes.h b/gtsam/3rdparty/metis/GKlib/ms_inttypes.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/ms_inttypes.h rename to gtsam/3rdparty/metis/GKlib/ms_inttypes.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stat.h b/gtsam/3rdparty/metis/GKlib/ms_stat.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/ms_stat.h rename to gtsam/3rdparty/metis/GKlib/ms_stat.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h b/gtsam/3rdparty/metis/GKlib/ms_stdint.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/ms_stdint.h rename to gtsam/3rdparty/metis/GKlib/ms_stdint.h diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/omp.c b/gtsam/3rdparty/metis/GKlib/omp.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/omp.c rename to gtsam/3rdparty/metis/GKlib/omp.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/pdb.c b/gtsam/3rdparty/metis/GKlib/pdb.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/pdb.c rename to gtsam/3rdparty/metis/GKlib/pdb.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/pqueue.c b/gtsam/3rdparty/metis/GKlib/pqueue.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/pqueue.c rename to gtsam/3rdparty/metis/GKlib/pqueue.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/random.c b/gtsam/3rdparty/metis/GKlib/random.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/random.c rename to gtsam/3rdparty/metis/GKlib/random.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/rw.c b/gtsam/3rdparty/metis/GKlib/rw.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/rw.c rename to gtsam/3rdparty/metis/GKlib/rw.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/seq.c b/gtsam/3rdparty/metis/GKlib/seq.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/seq.c rename to gtsam/3rdparty/metis/GKlib/seq.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/sort.c b/gtsam/3rdparty/metis/GKlib/sort.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/sort.c rename to gtsam/3rdparty/metis/GKlib/sort.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/string.c b/gtsam/3rdparty/metis/GKlib/string.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/string.c rename to gtsam/3rdparty/metis/GKlib/string.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/CMakeLists.txt b/gtsam/3rdparty/metis/GKlib/test/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/CMakeLists.txt rename to gtsam/3rdparty/metis/GKlib/test/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/Makefile.in.old b/gtsam/3rdparty/metis/GKlib/test/Makefile.in.old similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/Makefile.in.old rename to gtsam/3rdparty/metis/GKlib/test/Makefile.in.old diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/Makefile.old b/gtsam/3rdparty/metis/GKlib/test/Makefile.old similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/Makefile.old rename to gtsam/3rdparty/metis/GKlib/test/Makefile.old diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/fis.c b/gtsam/3rdparty/metis/GKlib/test/fis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/fis.c rename to gtsam/3rdparty/metis/GKlib/test/fis.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/gkgraph.c b/gtsam/3rdparty/metis/GKlib/test/gkgraph.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/gkgraph.c rename to gtsam/3rdparty/metis/GKlib/test/gkgraph.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/gksort.c b/gtsam/3rdparty/metis/GKlib/test/gksort.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/gksort.c rename to gtsam/3rdparty/metis/GKlib/test/gksort.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/rw.c b/gtsam/3rdparty/metis/GKlib/test/rw.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/rw.c rename to gtsam/3rdparty/metis/GKlib/test/rw.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/test/strings.c b/gtsam/3rdparty/metis/GKlib/test/strings.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/test/strings.c rename to gtsam/3rdparty/metis/GKlib/test/strings.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/timers.c b/gtsam/3rdparty/metis/GKlib/timers.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/timers.c rename to gtsam/3rdparty/metis/GKlib/timers.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/tokenizer.c b/gtsam/3rdparty/metis/GKlib/tokenizer.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/tokenizer.c rename to gtsam/3rdparty/metis/GKlib/tokenizer.c diff --git a/gtsam/3rdparty/metis-5.1.0/GKlib/util.c b/gtsam/3rdparty/metis/GKlib/util.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/GKlib/util.c rename to gtsam/3rdparty/metis/GKlib/util.c diff --git a/gtsam/3rdparty/metis-5.1.0/Install.txt b/gtsam/3rdparty/metis/Install.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/Install.txt rename to gtsam/3rdparty/metis/Install.txt diff --git a/gtsam/3rdparty/metis-5.1.0/LICENSE.txt b/gtsam/3rdparty/metis/LICENSE.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/LICENSE.txt rename to gtsam/3rdparty/metis/LICENSE.txt diff --git a/gtsam/3rdparty/metis-5.1.0/Makefile b/gtsam/3rdparty/metis/Makefile similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/Makefile rename to gtsam/3rdparty/metis/Makefile diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/4elt.graph b/gtsam/3rdparty/metis/graphs/4elt.graph similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/4elt.graph rename to gtsam/3rdparty/metis/graphs/4elt.graph diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/README b/gtsam/3rdparty/metis/graphs/README similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/README rename to gtsam/3rdparty/metis/graphs/README diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/copter2.graph b/gtsam/3rdparty/metis/graphs/copter2.graph similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/copter2.graph rename to gtsam/3rdparty/metis/graphs/copter2.graph diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/mdual.graph b/gtsam/3rdparty/metis/graphs/mdual.graph similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/mdual.graph rename to gtsam/3rdparty/metis/graphs/mdual.graph diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/metis.mesh b/gtsam/3rdparty/metis/graphs/metis.mesh similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/metis.mesh rename to gtsam/3rdparty/metis/graphs/metis.mesh diff --git a/gtsam/3rdparty/metis-5.1.0/graphs/test.mgraph b/gtsam/3rdparty/metis/graphs/test.mgraph similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/graphs/test.mgraph rename to gtsam/3rdparty/metis/graphs/test.mgraph diff --git a/gtsam/3rdparty/metis-5.1.0/include/CMakeLists.txt b/gtsam/3rdparty/metis/include/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/include/CMakeLists.txt rename to gtsam/3rdparty/metis/include/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/include/metis.h b/gtsam/3rdparty/metis/include/metis.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/include/metis.h rename to gtsam/3rdparty/metis/include/metis.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis/libmetis/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/CMakeLists.txt rename to gtsam/3rdparty/metis/libmetis/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/auxapi.c b/gtsam/3rdparty/metis/libmetis/auxapi.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/auxapi.c rename to gtsam/3rdparty/metis/libmetis/auxapi.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/balance.c b/gtsam/3rdparty/metis/libmetis/balance.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/balance.c rename to gtsam/3rdparty/metis/libmetis/balance.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/bucketsort.c b/gtsam/3rdparty/metis/libmetis/bucketsort.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/bucketsort.c rename to gtsam/3rdparty/metis/libmetis/bucketsort.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/checkgraph.c b/gtsam/3rdparty/metis/libmetis/checkgraph.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/checkgraph.c rename to gtsam/3rdparty/metis/libmetis/checkgraph.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/coarsen.c b/gtsam/3rdparty/metis/libmetis/coarsen.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/coarsen.c rename to gtsam/3rdparty/metis/libmetis/coarsen.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/compress.c b/gtsam/3rdparty/metis/libmetis/compress.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/compress.c rename to gtsam/3rdparty/metis/libmetis/compress.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/contig.c b/gtsam/3rdparty/metis/libmetis/contig.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/contig.c rename to gtsam/3rdparty/metis/libmetis/contig.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/debug.c b/gtsam/3rdparty/metis/libmetis/debug.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/debug.c rename to gtsam/3rdparty/metis/libmetis/debug.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/defs.h b/gtsam/3rdparty/metis/libmetis/defs.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/defs.h rename to gtsam/3rdparty/metis/libmetis/defs.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/fm.c b/gtsam/3rdparty/metis/libmetis/fm.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/fm.c rename to gtsam/3rdparty/metis/libmetis/fm.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/fortran.c b/gtsam/3rdparty/metis/libmetis/fortran.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/fortran.c rename to gtsam/3rdparty/metis/libmetis/fortran.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/frename.c b/gtsam/3rdparty/metis/libmetis/frename.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/frename.c rename to gtsam/3rdparty/metis/libmetis/frename.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/gklib.c b/gtsam/3rdparty/metis/libmetis/gklib.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/gklib.c rename to gtsam/3rdparty/metis/libmetis/gklib.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/gklib_defs.h b/gtsam/3rdparty/metis/libmetis/gklib_defs.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/gklib_defs.h rename to gtsam/3rdparty/metis/libmetis/gklib_defs.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/gklib_rename.h b/gtsam/3rdparty/metis/libmetis/gklib_rename.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/gklib_rename.h rename to gtsam/3rdparty/metis/libmetis/gklib_rename.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/graph.c b/gtsam/3rdparty/metis/libmetis/graph.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/graph.c rename to gtsam/3rdparty/metis/libmetis/graph.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/initpart.c b/gtsam/3rdparty/metis/libmetis/initpart.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/initpart.c rename to gtsam/3rdparty/metis/libmetis/initpart.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/kmetis.c b/gtsam/3rdparty/metis/libmetis/kmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/kmetis.c rename to gtsam/3rdparty/metis/libmetis/kmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/kwayfm.c b/gtsam/3rdparty/metis/libmetis/kwayfm.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/kwayfm.c rename to gtsam/3rdparty/metis/libmetis/kwayfm.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/kwayrefine.c b/gtsam/3rdparty/metis/libmetis/kwayrefine.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/kwayrefine.c rename to gtsam/3rdparty/metis/libmetis/kwayrefine.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/macros.h b/gtsam/3rdparty/metis/libmetis/macros.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/macros.h rename to gtsam/3rdparty/metis/libmetis/macros.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/mcutil.c b/gtsam/3rdparty/metis/libmetis/mcutil.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/mcutil.c rename to gtsam/3rdparty/metis/libmetis/mcutil.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/mesh.c b/gtsam/3rdparty/metis/libmetis/mesh.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/mesh.c rename to gtsam/3rdparty/metis/libmetis/mesh.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/meshpart.c b/gtsam/3rdparty/metis/libmetis/meshpart.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/meshpart.c rename to gtsam/3rdparty/metis/libmetis/meshpart.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/metislib.h b/gtsam/3rdparty/metis/libmetis/metislib.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/metislib.h rename to gtsam/3rdparty/metis/libmetis/metislib.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/minconn.c b/gtsam/3rdparty/metis/libmetis/minconn.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/minconn.c rename to gtsam/3rdparty/metis/libmetis/minconn.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/mincover.c b/gtsam/3rdparty/metis/libmetis/mincover.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/mincover.c rename to gtsam/3rdparty/metis/libmetis/mincover.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/mmd.c b/gtsam/3rdparty/metis/libmetis/mmd.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/mmd.c rename to gtsam/3rdparty/metis/libmetis/mmd.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/ometis.c b/gtsam/3rdparty/metis/libmetis/ometis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/ometis.c rename to gtsam/3rdparty/metis/libmetis/ometis.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/options.c b/gtsam/3rdparty/metis/libmetis/options.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/options.c rename to gtsam/3rdparty/metis/libmetis/options.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/parmetis.c b/gtsam/3rdparty/metis/libmetis/parmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/parmetis.c rename to gtsam/3rdparty/metis/libmetis/parmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/pmetis.c b/gtsam/3rdparty/metis/libmetis/pmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/pmetis.c rename to gtsam/3rdparty/metis/libmetis/pmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/proto.h b/gtsam/3rdparty/metis/libmetis/proto.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/proto.h rename to gtsam/3rdparty/metis/libmetis/proto.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/refine.c b/gtsam/3rdparty/metis/libmetis/refine.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/refine.c rename to gtsam/3rdparty/metis/libmetis/refine.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/rename.h b/gtsam/3rdparty/metis/libmetis/rename.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/rename.h rename to gtsam/3rdparty/metis/libmetis/rename.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/separator.c b/gtsam/3rdparty/metis/libmetis/separator.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/separator.c rename to gtsam/3rdparty/metis/libmetis/separator.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/sfm.c b/gtsam/3rdparty/metis/libmetis/sfm.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/sfm.c rename to gtsam/3rdparty/metis/libmetis/sfm.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/srefine.c b/gtsam/3rdparty/metis/libmetis/srefine.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/srefine.c rename to gtsam/3rdparty/metis/libmetis/srefine.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/stat.c b/gtsam/3rdparty/metis/libmetis/stat.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/stat.c rename to gtsam/3rdparty/metis/libmetis/stat.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/stdheaders.h b/gtsam/3rdparty/metis/libmetis/stdheaders.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/stdheaders.h rename to gtsam/3rdparty/metis/libmetis/stdheaders.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/struct.h b/gtsam/3rdparty/metis/libmetis/struct.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/struct.h rename to gtsam/3rdparty/metis/libmetis/struct.h diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/timing.c b/gtsam/3rdparty/metis/libmetis/timing.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/timing.c rename to gtsam/3rdparty/metis/libmetis/timing.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/util.c b/gtsam/3rdparty/metis/libmetis/util.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/util.c rename to gtsam/3rdparty/metis/libmetis/util.c diff --git a/gtsam/3rdparty/metis-5.1.0/libmetis/wspace.c b/gtsam/3rdparty/metis/libmetis/wspace.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/libmetis/wspace.c rename to gtsam/3rdparty/metis/libmetis/wspace.c diff --git a/gtsam/3rdparty/metis-5.1.0/manual/manual.pdf b/gtsam/3rdparty/metis/manual/manual.pdf similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/manual/manual.pdf rename to gtsam/3rdparty/metis/manual/manual.pdf diff --git a/gtsam/3rdparty/metis-5.1.0/programs/CMakeLists.txt b/gtsam/3rdparty/metis/programs/CMakeLists.txt similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/CMakeLists.txt rename to gtsam/3rdparty/metis/programs/CMakeLists.txt diff --git a/gtsam/3rdparty/metis-5.1.0/programs/cmdline_gpmetis.c b/gtsam/3rdparty/metis/programs/cmdline_gpmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/cmdline_gpmetis.c rename to gtsam/3rdparty/metis/programs/cmdline_gpmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/cmdline_m2gmetis.c b/gtsam/3rdparty/metis/programs/cmdline_m2gmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/cmdline_m2gmetis.c rename to gtsam/3rdparty/metis/programs/cmdline_m2gmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/cmdline_mpmetis.c b/gtsam/3rdparty/metis/programs/cmdline_mpmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/cmdline_mpmetis.c rename to gtsam/3rdparty/metis/programs/cmdline_mpmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/cmdline_ndmetis.c b/gtsam/3rdparty/metis/programs/cmdline_ndmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/cmdline_ndmetis.c rename to gtsam/3rdparty/metis/programs/cmdline_ndmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/cmpfillin.c b/gtsam/3rdparty/metis/programs/cmpfillin.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/cmpfillin.c rename to gtsam/3rdparty/metis/programs/cmpfillin.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/defs.h b/gtsam/3rdparty/metis/programs/defs.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/defs.h rename to gtsam/3rdparty/metis/programs/defs.h diff --git a/gtsam/3rdparty/metis-5.1.0/programs/gpmetis.c b/gtsam/3rdparty/metis/programs/gpmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/gpmetis.c rename to gtsam/3rdparty/metis/programs/gpmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/graphchk.c b/gtsam/3rdparty/metis/programs/graphchk.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/graphchk.c rename to gtsam/3rdparty/metis/programs/graphchk.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/io.c b/gtsam/3rdparty/metis/programs/io.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/io.c rename to gtsam/3rdparty/metis/programs/io.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/m2gmetis.c b/gtsam/3rdparty/metis/programs/m2gmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/m2gmetis.c rename to gtsam/3rdparty/metis/programs/m2gmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/metisbin.h b/gtsam/3rdparty/metis/programs/metisbin.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/metisbin.h rename to gtsam/3rdparty/metis/programs/metisbin.h diff --git a/gtsam/3rdparty/metis-5.1.0/programs/mpmetis.c b/gtsam/3rdparty/metis/programs/mpmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/mpmetis.c rename to gtsam/3rdparty/metis/programs/mpmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/ndmetis.c b/gtsam/3rdparty/metis/programs/ndmetis.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/ndmetis.c rename to gtsam/3rdparty/metis/programs/ndmetis.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/proto.h b/gtsam/3rdparty/metis/programs/proto.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/proto.h rename to gtsam/3rdparty/metis/programs/proto.h diff --git a/gtsam/3rdparty/metis-5.1.0/programs/smbfactor.c b/gtsam/3rdparty/metis/programs/smbfactor.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/smbfactor.c rename to gtsam/3rdparty/metis/programs/smbfactor.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/stat.c b/gtsam/3rdparty/metis/programs/stat.c similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/stat.c rename to gtsam/3rdparty/metis/programs/stat.c diff --git a/gtsam/3rdparty/metis-5.1.0/programs/struct.h b/gtsam/3rdparty/metis/programs/struct.h similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/programs/struct.h rename to gtsam/3rdparty/metis/programs/struct.h diff --git a/gtsam/3rdparty/metis-5.1.0/vsgen.bat b/gtsam/3rdparty/metis/vsgen.bat similarity index 100% rename from gtsam/3rdparty/metis-5.1.0/vsgen.bat rename to gtsam/3rdparty/metis/vsgen.bat From 2bc381dbb44c28a7820ffa2828f08645aa93648e Mon Sep 17 00:00:00 2001 From: Andrew Melim Date: Mon, 24 Nov 2014 17:12:41 -0500 Subject: [PATCH 30/32] Rename corrections --- CMakeLists.txt | 6 +++--- gtsam/3rdparty/CMakeLists.txt | 2 +- gtsam/inference/MetisIndex.h | 2 +- gtsam/inference/Ordering.cpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b2e7aa3d9..62bf4eb71 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -266,9 +266,9 @@ include_directories(BEFORE ${Boost_INCLUDE_DIR}) include_directories(BEFORE gtsam/3rdparty/UFconfig gtsam/3rdparty/CCOLAMD/Include - gtsam/3rdparty/metis-5.1.0/include - gtsam/3rdparty/metis-5.1.0/libmetis - gtsam/3rdparty/metis-5.1.0/GKlib + gtsam/3rdparty/metis/include + gtsam/3rdparty/metis/libmetis + gtsam/3rdparty/metis/GKlib ${PROJECT_SOURCE_DIR} ${PROJECT_BINARY_DIR} # So we can include generated config header files CppUnitLite) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 38c084e25..64636d262 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -45,7 +45,7 @@ endif() option(GTSAM_BUILD_METIS "Build metis library" ON) option(GTSAM_BUILD_METIS_EXECUTABLES "Build metis library executables" OFF) if(GTSAM_BUILD_METIS) - add_subdirectory(metis-5.1.0) + add_subdirectory(metis) endif(GTSAM_BUILD_METIS) ############ NOTE: When updating GeographicLib be sure to disable building their examples ############ and unit tests by commenting out their lines: diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index 684755895..ff67a5e21 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -25,7 +25,7 @@ #include #include #include -#include +#include #include namespace gtsam { diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 81f9ddb5c..5ae25d543 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -23,7 +23,7 @@ #include #include -#include +#include using namespace std; From 00d1d8cead166d522399e3b1e3cedd47c589c8d9 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 24 Nov 2014 17:53:52 -0500 Subject: [PATCH 31/32] Remove option to build metis. Now required. --- gtsam/3rdparty/CMakeLists.txt | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 64636d262..49d5a2fbb 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -42,11 +42,9 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) FILES_MATCHING PATTERN "*.h") endif() -option(GTSAM_BUILD_METIS "Build metis library" ON) option(GTSAM_BUILD_METIS_EXECUTABLES "Build metis library executables" OFF) -if(GTSAM_BUILD_METIS) - add_subdirectory(metis) -endif(GTSAM_BUILD_METIS) +add_subdirectory(metis) + ############ NOTE: When updating GeographicLib be sure to disable building their examples ############ and unit tests by commenting out their lines: # add_subdirectory (examples) From 3fed3c7cbb99bd783f5939560b3759f1ff3150a0 Mon Sep 17 00:00:00 2001 From: cbeall3 Date: Mon, 24 Nov 2014 17:54:50 -0500 Subject: [PATCH 32/32] match installed header location to source location --- gtsam/3rdparty/metis/metis.h | 13 +++++++++++++ gtsam/inference/MetisIndex.h | 2 +- 2 files changed, 14 insertions(+), 1 deletion(-) create mode 100644 gtsam/3rdparty/metis/metis.h diff --git a/gtsam/3rdparty/metis/metis.h b/gtsam/3rdparty/metis/metis.h new file mode 100644 index 000000000..a1ba08684 --- /dev/null +++ b/gtsam/3rdparty/metis/metis.h @@ -0,0 +1,13 @@ +/* + * metis.h + * Dummy header, not installed! + * Created on: Nov 24, 2014 + * Author: cbeall3 + */ + +#ifndef GTSAM_3RDPARTY_METIS_METIS_H_ +#define GTSAM_3RDPARTY_METIS_METIS_H_ + +#include + +#endif /* GTSAM_3RDPARTY_METIS_METIS_H_ */ diff --git a/gtsam/inference/MetisIndex.h b/gtsam/inference/MetisIndex.h index ff67a5e21..3eef4739c 100644 --- a/gtsam/inference/MetisIndex.h +++ b/gtsam/inference/MetisIndex.h @@ -25,7 +25,7 @@ #include #include #include -#include +#include #include namespace gtsam {