Updating nonlinear params to allow selection of orderings
parent
103ec596d7
commit
8cd17f6a30
|
@ -12,6 +12,7 @@
|
|||
/**
|
||||
* @file Ordering.cpp
|
||||
* @author Richard Roberts
|
||||
* @author Andrew Melim
|
||||
* @date Sep 2, 2010
|
||||
*/
|
||||
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
/**
|
||||
* @file Ordering.h
|
||||
* @author Richard Roberts
|
||||
* @author Andrew Melim
|
||||
* @date Sep 2, 2010
|
||||
*/
|
||||
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
/**
|
||||
* @file testOrdering
|
||||
* @author Alex Cunningham
|
||||
* @author Andrew Melim
|
||||
*/
|
||||
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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:
|
||||
|
|
Loading…
Reference in New Issue