From a0c77dcc1ca8584a4a1b5c3fb4fd31076edbf92a Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Tue, 3 Jun 2014 23:52:35 -0400 Subject: [PATCH] remove unused variables in iterative solvers and rename accordingly. --- examples/Pose2SLAMwSPCG.cpp | 2 +- gtsam.h | 4 +--- gtsam/linear/IterativeSolver.cpp | 21 +++++++++----------- gtsam/linear/IterativeSolver.h | 16 ++++----------- gtsam/nonlinear/DoglegOptimizer.cpp | 2 +- gtsam/nonlinear/NonlinearOptimizer.cpp | 2 +- gtsam/nonlinear/NonlinearOptimizerParams.cpp | 12 +++++------ gtsam/nonlinear/NonlinearOptimizerParams.h | 6 +++--- 8 files changed, 26 insertions(+), 39 deletions(-) diff --git a/examples/Pose2SLAMwSPCG.cpp b/examples/Pose2SLAMwSPCG.cpp index 2b2f63064..8e8e28570 100644 --- a/examples/Pose2SLAMwSPCG.cpp +++ b/examples/Pose2SLAMwSPCG.cpp @@ -104,7 +104,7 @@ int main(int argc, char** argv) { LevenbergMarquardtParams parameters; parameters.verbosity = NonlinearOptimizerParams::ERROR; parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA; - parameters.linearSolverType = NonlinearOptimizerParams::CONJUGATE_GRADIENT; + parameters.linearSolverType = NonlinearOptimizerParams::Iterative; { parameters.iterativeParams = boost::make_shared(); diff --git a/gtsam.h b/gtsam.h index b7178d534..2cd6415a6 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1481,9 +1481,7 @@ class GaussianISAM { #include virtual class IterativeOptimizationParameters { - string getKernel() const ; string getVerbosity() const; - void setKernel(string s) ; void setVerbosity(string s) ; void print() const; }; @@ -1860,7 +1858,7 @@ virtual class NonlinearOptimizerParams { bool isMultifrontal() const; bool isSequential() const; bool isCholmod() const; - bool isCG() const; + bool isIterative() const; }; bool checkConvergence(double relativeErrorTreshold, diff --git a/gtsam/linear/IterativeSolver.cpp b/gtsam/linear/IterativeSolver.cpp index 2bba3e12b..b022a26d8 100644 --- a/gtsam/linear/IterativeSolver.cpp +++ b/gtsam/linear/IterativeSolver.cpp @@ -11,18 +11,19 @@ namespace gtsam { -std::string IterativeOptimizationParameters::getKernel() const { return kernelTranslator(kernel_); } +/*****************************************************************************/ std::string IterativeOptimizationParameters::getVerbosity() const { return verbosityTranslator(verbosity_); } -void IterativeOptimizationParameters::setKernel(const std::string &src) { kernel_ = kernelTranslator(src); } + +/*****************************************************************************/ void IterativeOptimizationParameters::setVerbosity(const std::string &src) { verbosity_ = verbosityTranslator(src); } -IterativeOptimizationParameters::Kernel IterativeOptimizationParameters::kernelTranslator(const std::string &src) { - std::string s = src; boost::algorithm::to_upper(s); - if (s == "CG") return IterativeOptimizationParameters::CG; - /* default is cg */ - else return IterativeOptimizationParameters::CG; +/*****************************************************************************/ +void IterativeOptimizationParameters::print() const { + std::cout << "IterativeOptimizationParameters" << std::endl + << "verbosity: " << verbosityTranslator(verbosity_) << std::endl; } +/*****************************************************************************/ IterativeOptimizationParameters::Verbosity IterativeOptimizationParameters::verbosityTranslator(const std::string &src) { std::string s = src; boost::algorithm::to_upper(s); if (s == "SILENT") return IterativeOptimizationParameters::SILENT; @@ -32,11 +33,7 @@ IterativeOptimizationParameters::Verbosity IterativeOptimizationParameters::verb else return IterativeOptimizationParameters::SILENT; } -std::string IterativeOptimizationParameters::kernelTranslator(IterativeOptimizationParameters::Kernel k) { - if ( k == CG ) return "CG"; - else return "UNKNOWN"; -} - +/*****************************************************************************/ std::string IterativeOptimizationParameters::verbosityTranslator(IterativeOptimizationParameters::Verbosity verbosity) { if (verbosity == SILENT) return "SILENT"; else if (verbosity == COMPLEXITY) return "COMPLEXITY"; diff --git a/gtsam/linear/IterativeSolver.h b/gtsam/linear/IterativeSolver.h index 988293a4f..b4e2e6d49 100644 --- a/gtsam/linear/IterativeSolver.h +++ b/gtsam/linear/IterativeSolver.h @@ -30,21 +30,19 @@ namespace gtsam { public: typedef boost::shared_ptr shared_ptr; - enum Kernel { CG = 0 } kernel_ ; ///< Iterative Method Kernel enum Verbosity { SILENT = 0, COMPLEXITY, ERROR } verbosity_; public: IterativeOptimizationParameters(const IterativeOptimizationParameters &p) - : kernel_(p.kernel_), verbosity_(p.verbosity_) {} + : verbosity_(p.verbosity_) {} - IterativeOptimizationParameters(const Kernel kernel = CG, const Verbosity verbosity = SILENT) - : kernel_(kernel), verbosity_(verbosity) {} + IterativeOptimizationParameters(const Verbosity verbosity = SILENT) + : verbosity_(verbosity) {} virtual ~IterativeOptimizationParameters() {} /* general interface */ - inline Kernel kernel() const { return kernel_; } inline Verbosity verbosity() const { return verbosity_; } /* matlab interface */ @@ -53,15 +51,9 @@ namespace gtsam { void setKernel(const std::string &s) ; void setVerbosity(const std::string &s) ; - virtual void print() const { - std::cout << "IterativeOptimizationParameters" << std::endl - << "kernel: " << kernelTranslator(kernel_) << std::endl - << "verbosity: " << verbosityTranslator(verbosity_) << std::endl; - } + virtual void print() const ; - static Kernel kernelTranslator(const std::string &s); static Verbosity verbosityTranslator(const std::string &s); - static std::string kernelTranslator(Kernel k); static std::string verbosityTranslator(Verbosity v); }; diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 03da76eb6..082cc66c8 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -76,7 +76,7 @@ void DoglegOptimizer::iterate(void) { result = DoglegOptimizerImpl::Iterate(state_.Delta, DoglegOptimizerImpl::ONE_STEP_PER_ITERATION, dx_u, dx_n, bn, graph_, state_.values, state_.error, dlVerbose); } - else if ( params_.isCG() ) { + else if ( params_.isIterative() ) { throw runtime_error("Dogleg is not currently compatible with the linear conjugate gradient solver"); } else { diff --git a/gtsam/nonlinear/NonlinearOptimizer.cpp b/gtsam/nonlinear/NonlinearOptimizer.cpp index 54e5cb9e3..678cac6b4 100644 --- a/gtsam/nonlinear/NonlinearOptimizer.cpp +++ b/gtsam/nonlinear/NonlinearOptimizer.cpp @@ -102,7 +102,7 @@ VectorValues NonlinearOptimizer::solve(const GaussianFactorGraph &gfg, } else if (params.isSequential()) { delta = gfg.eliminateSequential(*params.ordering, params.getEliminationFunction())->optimize(); - } else if (params.isCG()) { + } else if (params.isIterative()) { if (!params.iterativeParams) throw std::runtime_error( "NonlinearOptimizer::solve: cg parameter has to be assigned ..."); diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.cpp b/gtsam/nonlinear/NonlinearOptimizerParams.cpp index 7b0e73985..e0b6e0c6c 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.cpp +++ b/gtsam/nonlinear/NonlinearOptimizerParams.cpp @@ -99,8 +99,8 @@ void NonlinearOptimizerParams::print(const std::string& str) const { case CHOLMOD: std::cout << " linear solver type: CHOLMOD\n"; break; - case CONJUGATE_GRADIENT: - std::cout << " linear solver type: CONJUGATE GRADIENT\n"; + case Iterative: + std::cout << " linear solver type: ITERATIVE\n"; break; default: std::cout << " linear solver type: (invalid)\n"; @@ -127,8 +127,8 @@ std::string NonlinearOptimizerParams::linearSolverTranslator( return "SEQUENTIAL_CHOLESKY"; case SEQUENTIAL_QR: return "SEQUENTIAL_QR"; - case CONJUGATE_GRADIENT: - return "CONJUGATE_GRADIENT"; + case Iterative: + return "ITERATIVE"; case CHOLMOD: return "CHOLMOD"; default: @@ -148,8 +148,8 @@ NonlinearOptimizerParams::LinearSolverType NonlinearOptimizerParams::linearSolve return SEQUENTIAL_CHOLESKY; if (linearSolverType == "SEQUENTIAL_QR") return SEQUENTIAL_QR; - if (linearSolverType == "CONJUGATE_GRADIENT") - return CONJUGATE_GRADIENT; + if (linearSolverType == "ITERATIVE") + return Iterative; if (linearSolverType == "CHOLMOD") return CHOLMOD; throw std::invalid_argument( diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index 10d468384..641c6da24 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -99,7 +99,7 @@ public: MULTIFRONTAL_QR, SEQUENTIAL_CHOLESKY, SEQUENTIAL_QR, - CONJUGATE_GRADIENT, /* Experimental Flag */ + Iterative, /* Experimental Flag */ CHOLMOD, /* Experimental Flag */ }; @@ -121,8 +121,8 @@ public: return (linearSolverType == CHOLMOD); } - inline bool isCG() const { - return (linearSolverType == CONJUGATE_GRADIENT); + inline bool isIterative() const { + return (linearSolverType == Iterative); } GaussianFactorGraph::Eliminate getEliminationFunction() const {