Corrected scoped enum issue for non c++11 compilers
parent
f00f8d1d7a
commit
ffae14d42e
|
@ -87,7 +87,7 @@ int main(int argc, char** argv) {
|
||||||
|
|
||||||
// optimize using Levenberg-Marquardt optimization
|
// optimize using Levenberg-Marquardt optimization
|
||||||
LevenbergMarquardtParams params;
|
LevenbergMarquardtParams params;
|
||||||
params.orderingType = Ordering::Type::METIS_;
|
params.orderingType = OrderingType::METIS;
|
||||||
LevenbergMarquardtOptimizer optimizer(graph, initial, params);
|
LevenbergMarquardtOptimizer optimizer(graph, initial, params);
|
||||||
Values result = optimizer.optimize();
|
Values result = optimizer.optimize();
|
||||||
result.print("Final Result:\n");
|
result.print("Final Result:\n");
|
||||||
|
|
|
@ -54,7 +54,7 @@ namespace gtsam {
|
||||||
// If no Ordering provided, compute one and call this function again. We are guaranteed to
|
// 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'
|
// have a VariableIndex already here because we computed one if needed in the previous 'else'
|
||||||
// block.
|
// block.
|
||||||
if (orderingType == Ordering::Type::METIS_)
|
if (orderingType == OrderingType::METIS)
|
||||||
return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType);
|
return eliminateSequential(Ordering::METIS(asDerived()), function, variableIndex, orderingType);
|
||||||
else
|
else
|
||||||
return eliminateSequential(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType);
|
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
|
// 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'
|
// have a VariableIndex already here because we computed one if needed in the previous 'else'
|
||||||
// block.
|
// block.
|
||||||
if (orderingType == Ordering::Type::METIS_)
|
if (orderingType == OrderingType::METIS)
|
||||||
return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType);
|
return eliminateMultifrontal(Ordering::METIS(asDerived()), function, variableIndex, orderingType);
|
||||||
else
|
else
|
||||||
return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType);
|
return eliminateMultifrontal(Ordering::COLAMD(*variableIndex), function, variableIndex, orderingType);
|
||||||
|
|
|
@ -95,7 +95,7 @@ namespace gtsam {
|
||||||
typedef boost::optional<const VariableIndex&> OptionalVariableIndex;
|
typedef boost::optional<const VariableIndex&> OptionalVariableIndex;
|
||||||
|
|
||||||
/// Typedef for an optional ordering type
|
/// Typedef for an optional ordering type
|
||||||
typedef boost::optional<Ordering::Type> OptionalOrderingType;
|
typedef boost::optional<OrderingType> OptionalOrderingType;
|
||||||
|
|
||||||
/** Do sequential elimination of all variables to produce a Bayes net. If an ordering is not
|
/** 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.
|
* provided, the ordering provided by COLAMD will be used.
|
||||||
|
@ -107,7 +107,7 @@ namespace gtsam {
|
||||||
*
|
*
|
||||||
* <b> Example - METIS ordering for elimination
|
* <b> Example - METIS ordering for elimination
|
||||||
* \code
|
* \code
|
||||||
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(Ordering::Type::METIS_);
|
* boost::shared_ptr<GaussianBayesNet> result = graph.eliminateSequential(OrderingType::METIS);
|
||||||
*
|
*
|
||||||
* <b> Example - Full QR elimination in specified order:
|
* <b> Example - Full QR elimination in specified order:
|
||||||
* \code
|
* \code
|
||||||
|
|
|
@ -29,6 +29,11 @@
|
||||||
#include <gtsam/inference/FactorGraph.h>
|
#include <gtsam/inference/FactorGraph.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
enum OrderingType {
|
||||||
|
COLAMD, METIS, CUSTOM
|
||||||
|
};
|
||||||
|
|
||||||
class Ordering : public std::vector<Key> {
|
class Ordering : public std::vector<Key> {
|
||||||
protected:
|
protected:
|
||||||
typedef std::vector<Key> Base;
|
typedef std::vector<Key> Base;
|
||||||
|
@ -37,12 +42,6 @@ namespace gtsam {
|
||||||
typedef Ordering This; ///< Typedef to this class
|
typedef Ordering This; ///< Typedef to this class
|
||||||
typedef boost::shared_ptr<This> shared_ptr; ///< shared_ptr 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
|
/// Create an empty ordering
|
||||||
GTSAM_EXPORT Ordering() {}
|
GTSAM_EXPORT Ordering() {}
|
||||||
|
|
||||||
|
|
|
@ -341,7 +341,7 @@ 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 = OrderingType::METIS)
|
||||||
params.ordering = Ordering::METIS(graph);
|
params.ordering = Ordering::METIS(graph);
|
||||||
else
|
else
|
||||||
params.ordering = Ordering::COLAMD(graph);
|
params.ordering = Ordering::COLAMD(graph);
|
||||||
|
|
|
@ -109,10 +109,10 @@ void NonlinearOptimizerParams::print(const std::string& str) const {
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (orderingType){
|
switch (orderingType){
|
||||||
case Ordering::Type::COLAMD_:
|
case OrderingType::COLAMD:
|
||||||
std::cout << " ordering: COLAMD\n";
|
std::cout << " ordering: COLAMD\n";
|
||||||
break;
|
break;
|
||||||
case Ordering::Type::METIS_:
|
case OrderingType::METIS:
|
||||||
std::cout << " ordering: METIS\n";
|
std::cout << " ordering: METIS\n";
|
||||||
break;
|
break;
|
||||||
default:
|
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) {
|
switch (type) {
|
||||||
case Ordering::Type::METIS_:
|
case OrderingType::METIS:
|
||||||
return "METIS";
|
return "METIS";
|
||||||
case Ordering::Type::COLAMD_:
|
case OrderingType::COLAMD:
|
||||||
return "COLAMD";
|
return "COLAMD";
|
||||||
default:
|
default:
|
||||||
if (ordering)
|
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")
|
if (type == "METIS")
|
||||||
return Ordering::Type::METIS_;
|
return OrderingType::METIS;
|
||||||
if (type == "COLAMD")
|
if (type == "COLAMD")
|
||||||
return Ordering::Type::COLAMD_;
|
return OrderingType::COLAMD;
|
||||||
throw std::invalid_argument(
|
throw std::invalid_argument(
|
||||||
"Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering");
|
"Invalid ordering type: You must provide an ordering for a custom ordering type. See setOrdering");
|
||||||
}
|
}
|
||||||
|
|
|
@ -43,11 +43,11 @@ public:
|
||||||
double absoluteErrorTol; ///< The maximum absolute 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)
|
double errorTol; ///< The maximum total error to stop iterating (default 0.0)
|
||||||
Verbosity verbosity; ///< The printing verbosity during optimization (default SILENT)
|
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() :
|
NonlinearOptimizerParams() :
|
||||||
maxIterations(100), relativeErrorTol(1e-5), absoluteErrorTol(1e-5), errorTol(
|
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() {
|
virtual ~NonlinearOptimizerParams() {
|
||||||
|
@ -154,7 +154,7 @@ public:
|
||||||
|
|
||||||
void setOrdering(const Ordering& ordering) {
|
void setOrdering(const Ordering& ordering) {
|
||||||
this->ordering = ordering;
|
this->ordering = ordering;
|
||||||
this->orderingType = Ordering::Type::CUSTOM_;
|
this->orderingType = OrderingType::CUSTOM;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string getOrderingType() const {
|
std::string getOrderingType() const {
|
||||||
|
@ -171,9 +171,9 @@ private:
|
||||||
|
|
||||||
LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const;
|
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;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue