Formatting changes
parent
c520bf2b47
commit
f00f8d1d7a
|
@ -9,7 +9,6 @@
|
||||||
|
|
||||||
* -------------------------------------------------------------------------- */
|
* -------------------------------------------------------------------------- */
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @file MetisIndex.h
|
* @file MetisIndex.h
|
||||||
* @author Andrew Melim
|
* @author Andrew Melim
|
||||||
|
@ -28,26 +27,26 @@
|
||||||
#include <gtsam/inference/FactorGraph.h>
|
#include <gtsam/inference/FactorGraph.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* The MetisIndex class converts a factor graph into the Compressed Sparse Row format for use in
|
* 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
|
* 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
|
* fromt a factor graph prior to elimination, and stores the list of factors
|
||||||
* that involve each variable.
|
* that involve each variable.
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class GTSAM_EXPORT MetisIndex
|
class GTSAM_EXPORT MetisIndex
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
typedef boost::shared_ptr<MetisIndex> shared_ptr;
|
typedef boost::shared_ptr<MetisIndex> shared_ptr;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
FastVector<int> xadj_; // Index of node's adjacency list in adj
|
FastVector<int> xadj_; // Index of node's adjacency list in adj
|
||||||
FastVector<int> adj_; // Stores ajacency lists of all nodes, appended into a single vector
|
FastVector<int> adj_; // Stores ajacency lists of all nodes, appended into a single vector
|
||||||
size_t nFactors_; // Number of factors in the original factor graph
|
size_t nFactors_; // Number of factors in the original factor graph
|
||||||
size_t nKeys_; //
|
size_t nKeys_; //
|
||||||
size_t minKey_;
|
size_t minKey_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @name Standard Constructors
|
/// @name Standard Constructors
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
|
@ -76,7 +75,7 @@ namespace gtsam {
|
||||||
size_t minKey() const { return minKey_; }
|
size_t minKey() const { return minKey_; }
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -340,11 +340,12 @@ void LevenbergMarquardtOptimizer::iterate() {
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering(
|
LevenbergMarquardtParams LevenbergMarquardtOptimizer::ensureHasOrdering(
|
||||||
LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const {
|
LevenbergMarquardtParams params, const NonlinearFactorGraph& graph) const {
|
||||||
if (!params.ordering)
|
if (!params.ordering){
|
||||||
if (params.orderingType = Ordering::Type::METIS_)
|
if (params.orderingType = Ordering::Type::METIS_)
|
||||||
params.ordering = Ordering::METIS(graph);
|
params.ordering = Ordering::METIS(graph);
|
||||||
else
|
else
|
||||||
params.ordering = Ordering::COLAMD(graph);
|
params.ordering = Ordering::COLAMD(graph);
|
||||||
|
}
|
||||||
return params;
|
return params;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -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) {
|
switch (type) {
|
||||||
case Ordering::Type::METIS_:
|
case Ordering::Type::METIS_:
|
||||||
return "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")
|
if (type == "METIS")
|
||||||
return Ordering::Type::METIS_;
|
return Ordering::Type::METIS_;
|
||||||
if (type == "COLAMD")
|
if (type == "COLAMD")
|
||||||
|
|
Loading…
Reference in New Issue