Ordering type enum
parent
8cd17f6a30
commit
1d7bcb301a
|
|
@ -37,6 +37,12 @@ namespace gtsam {
|
|||
typedef Ordering This; ///< Typedef to this class
|
||||
typedef boost::shared_ptr<This> 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() {}
|
||||
|
||||
|
|
|
|||
|
|
@ -5,6 +5,7 @@
|
|||
* @author Yong-Dian Jian
|
||||
* @author Richard Roberts
|
||||
* @author Frank Dellaert
|
||||
* @author Andrew Melim
|
||||
*/
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearOptimizerParams.h>
|
||||
|
|
@ -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");
|
||||
}
|
||||
|
|
|
|||
|
|
@ -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;
|
||||
|
||||
};
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue