From fd8ec0a605e499526af87e908677909119de1b57 Mon Sep 17 00:00:00 2001 From: Yong-Dian Jian Date: Sun, 3 Jun 2012 02:53:17 +0000 Subject: [PATCH] fix a switch bug --- .../nonlinear/SuccessiveLinearizationOptimizer.h | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h index 387a550db..ea54dd344 100644 --- a/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h +++ b/gtsam/nonlinear/SuccessiveLinearizationOptimizer.h @@ -32,8 +32,7 @@ public: SEQUENTIAL_CHOLESKY, SEQUENTIAL_QR, CHOLMOD, /* Experimental Flag */ - PCG, /* Experimental Flag */ - LSPCG /* Experimental Flag */ + CG, /* Experimental Flag */ }; LinearSolverType linearSolverType; ///< The type of linear solver to use in the nonlinear optimizer @@ -62,11 +61,8 @@ public: 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"; + case CG: + std::cout << " linear solver type: CG\n"; break; default: std::cout << " linear solver type: (invalid)\n"; @@ -94,16 +90,16 @@ public: } inline bool isCG() const { - return (linearSolverType == PCG || linearSolverType == LSPCG); + return (linearSolverType == CG); } GaussianFactorGraph::Eliminate getEliminationFunction() { switch (linearSolverType) { case MULTIFRONTAL_CHOLESKY: - case MULTIFRONTAL_QR: + case SEQUENTIAL_CHOLESKY: return EliminatePreferCholesky; - case SEQUENTIAL_CHOLESKY: + case MULTIFRONTAL_QR: case SEQUENTIAL_QR: return EliminateQR;