From 75bd3dc52cb48126f84df1f7822f5b46278b8a69 Mon Sep 17 00:00:00 2001 From: lcarlone Date: Mon, 21 Dec 2020 20:32:21 -0500 Subject: [PATCH] templating on params is still problematic --- gtsam/nonlinear/GaussNewtonOptimizer.h | 2 ++ gtsam/nonlinear/GncOptimizer.h | 14 ++++++++++---- gtsam/nonlinear/LevenbergMarquardtParams.h | 3 +++ 3 files changed, 15 insertions(+), 4 deletions(-) diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.h b/gtsam/nonlinear/GaussNewtonOptimizer.h index a436597e5..3ef4dfdeb 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.h +++ b/gtsam/nonlinear/GaussNewtonOptimizer.h @@ -28,6 +28,8 @@ class GaussNewtonOptimizer; * NonlinearOptimizationParams. */ class GTSAM_EXPORT GaussNewtonParams : public NonlinearOptimizerParams { +public: + typedef GaussNewtonOptimizer OptimizerType; }; /** diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index 811487779..730c1aa43 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -36,6 +36,9 @@ namespace gtsam { template class GncParams { public: + //typedef BaseOptimizerParameters::OptimizerType GncOptimizerType; + typedef BaseOptimizerParameters::OptimizerType OptimizerType; + /** Verbosity levels */ enum VerbosityGNC { SILENT = 0, SUMMARY, VALUES @@ -46,8 +49,6 @@ public: GM /*Geman McClure*/, TLS /*Truncated least squares*/ }; - using BaseOptimizer = GaussNewtonOptimizer; // BaseOptimizerParameters::OptimizerType; - /// Constructor GncParams(const BaseOptimizerParameters& baseOptimizerParams) : baseOptimizerParams(baseOptimizerParams) { @@ -145,6 +146,11 @@ template class GncOptimizer { public: // types etc +// typedef BaseOptimizerParameters::OptimizerType GncOptimizerType; + // typedef GncParameters::BaseOptimizerParameters::OptimizerType BaseOptimizer; // + //typedef BaseOptimizerParameters::OptimizerType BaseOptimizer; + //typedef GaussNewtonOptimizer BaseOptimizer; + typedef GncParameters::OptimizerType BaseOptimizer; private: NonlinearFactorGraph nfg_; @@ -198,7 +204,7 @@ public: Values optimize() { // start by assuming all measurements are inliers weights_ = Vector::Ones(nfg_.size()); - GaussNewtonOptimizer baseOptimizer(nfg_, state_); + BaseOptimizer baseOptimizer(nfg_, state_); Values result = baseOptimizer.optimize(); double mu = initializeMu(); double mu_prev = mu; @@ -229,7 +235,7 @@ public: // variable/values update NonlinearFactorGraph graph_iter = this->makeWeightedGraph(weights_); - GaussNewtonOptimizer baseOptimizer_iter(graph_iter, state_); + BaseOptimizer baseOptimizer_iter(graph_iter, state_); result = baseOptimizer_iter.optimize(); // update mu diff --git a/gtsam/nonlinear/LevenbergMarquardtParams.h b/gtsam/nonlinear/LevenbergMarquardtParams.h index 4962ad366..20a8eb4c1 100644 --- a/gtsam/nonlinear/LevenbergMarquardtParams.h +++ b/gtsam/nonlinear/LevenbergMarquardtParams.h @@ -25,6 +25,8 @@ namespace gtsam { +class LevenbergMarquardtOptimizer; + /** Parameters for Levenberg-Marquardt optimization. Note that this parameters * class inherits from NonlinearOptimizerParams, which specifies the parameters * common to all nonlinear optimization algorithms. This class also contains @@ -40,6 +42,7 @@ public: static VerbosityLM verbosityLMTranslator(const std::string &s); static std::string verbosityLMTranslator(VerbosityLM value); + typedef LevenbergMarquardtOptimizer OptimizerType; public: