From b0c91d2fcf8bd8e315082ba6769be4da2f5ca340 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Sun, 27 May 2012 18:26:25 +0000 Subject: [PATCH] --- gtsam/nonlinear/DoglegOptimizer.cpp | 2 +- gtsam/nonlinear/GaussNewtonOptimizer.cpp | 2 +- .../nonlinear/LevenbergMarquardtOptimizer.cpp | 2 +- .../SuccessiveLinearizationOptimizer.h | 24 +++++++++++++++---- 4 files changed, 22 insertions(+), 8 deletions(-) diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 91b3c92fd..3edb35a76 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -48,7 +48,7 @@ void DoglegOptimizer::iterate(void) { GaussianBayesNet::shared_ptr bn = EliminationTree::Create(*linear)->eliminate(params_.getEliminationFunction()); result = DoglegOptimizerImpl::Iterate(state_.Delta, DoglegOptimizerImpl::ONE_STEP_PER_ITERATION, *bn, graph_, state_.values, ordering, state_.error, dlVerbose); } - else if ( params_.isSPCG() ) { + else if ( params_.isCG() ) { throw runtime_error("todo: "); } else { diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.cpp b/gtsam/nonlinear/GaussNewtonOptimizer.cpp index 8d09b3edc..c81369299 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.cpp +++ b/gtsam/nonlinear/GaussNewtonOptimizer.cpp @@ -41,7 +41,7 @@ void GaussNewtonOptimizer::iterate() { else if ( params_.isSequential() ) { delta = gtsam::optimize(*EliminationTree::Create(*linear)->eliminate(params_.getEliminationFunction())); } - else if ( params_.isSPCG() ) { + else if ( params_.isCG() ) { throw runtime_error("todo: "); } else { diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 3ad26cb3a..f1f5ab1df 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -70,7 +70,7 @@ void LevenbergMarquardtOptimizer::iterate() { else if ( params_.isSequential() ) { delta = gtsam::optimize(*EliminationTree::Create(dampedSystem)->eliminate(params_.getEliminationFunction())); } - else if ( params_.isSPCG() ) { + else if ( params_.isCG() ) { throw runtime_error("todo: "); } else { diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h index 2b3bfd3b6..387a550db 100644 --- a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h @@ -19,6 +19,7 @@ #pragma once #include +#include namespace gtsam { @@ -30,11 +31,14 @@ public: MULTIFRONTAL_QR, SEQUENTIAL_CHOLESKY, SEQUENTIAL_QR, - SPCG + CHOLMOD, /* Experimental Flag */ + PCG, /* Experimental Flag */ + LSPCG /* Experimental Flag */ }; LinearSolverType linearSolverType; ///< The type of linear solver to use in the nonlinear optimizer boost::optional ordering; ///< The variable elimination ordering, or empty to use COLAMD (default: empty) + boost::optional iterativeParams; ///< The container for iterativeOptimization parameters. SuccessiveLinearizationParams() : linearSolverType(MULTIFRONTAL_CHOLESKY) {} @@ -55,8 +59,14 @@ public: case SEQUENTIAL_QR: std::cout << " linear solver type: SEQUENTIAL QR\n"; break; - case SPCG: - std::cout << " linear solver type: SPCG\n"; + case CHOLMOD: + std::cout << " linear solver type: CHOLMOD\n"; + break; + case PCG: + std::cout << " linear solver type: PCG\n"; + break; + case LSPCG: + std::cout << " linear solver type: LSPCG\n"; break; default: std::cout << " linear solver type: (invalid)\n"; @@ -79,8 +89,12 @@ public: return (linearSolverType == SEQUENTIAL_CHOLESKY) || (linearSolverType == SEQUENTIAL_QR); } - inline bool isSPCG() const { - return (linearSolverType == SPCG); + inline bool isCholmod() const { + return (linearSolverType == CHOLMOD); + } + + inline bool isCG() const { + return (linearSolverType == PCG || linearSolverType == LSPCG); } GaussianFactorGraph::Eliminate getEliminationFunction() {