remove the optional

release/4.3a0
Yong-Dian Jian 2012-06-04 17:23:45 +00:00
parent f7d7c5b9c8
commit 74322b0764
7 changed files with 28 additions and 26 deletions

View File

@ -68,7 +68,6 @@ int main(void) {
LevenbergMarquardtParams param;
param.linearSolverType = SuccessiveLinearizationParams::CG;
param.iterativeParams = boost::make_shared<IterativeOptimizationParameters>();
LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, param);
Values result = optimizer.optimize();
cout << "final error = " << graph.error(result) << endl;

View File

@ -113,7 +113,9 @@ struct PreconditionerParameters {
std::cout << "PreconditionerParameters: "
<< "kernel = " << kernelStr[kernel_]
<< ", type = " << typeStr[type_] << std::endl;
<< ", type = " << typeStr[type_]
<< ", verbosity = " << verbosity_
<< std::endl;
combinatorial_.print();
}
};
@ -167,6 +169,7 @@ struct ConjugateGradientParameters {
<< ", eps_rel = " << epsilon_rel_
<< ", eps_abs = " << epsilon_abs_
<< ", degree = " << degree_
<< ", verbosity = " << verbosity_
<< std::endl;
}
};
@ -180,8 +183,8 @@ public:
PreconditionerParameters preconditioner_;
ConjugateGradientParameters cg_;
enum Kernel { PCG = 0, LSPCG } kernel_ ; /* Iterative Method Kernel */
enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; /* Verbosity */
enum Kernel { PCG = 0, LSPCG = 1 } kernel_ ; ///< Iterative Method Kernel
enum Verbosity { SILENT = 0, COMPLEXITY = 1, ERROR = 2} verbosity_ ; ///< Verbosity
public:
@ -221,7 +224,8 @@ public:
const std::string kernelStr[2] = {"pcg", "lspcg"};
std::cout << s << std::endl
<< "IterativeOptimizationParameters: "
<< "kernel = " << kernelStr[kernel_] << std::endl;
<< "kernel = " << kernelStr[kernel_]
<< ", verbosity = " << verbosity_ << std::endl;
cg_.print();
preconditioner_.print();

View File

@ -11,9 +11,8 @@
#pragma once
#include <gtsam/linear/VectorValues.h>
#include <gtsam/linear/IterativeOptimizationParameters.h>
#include <boost/shared_ptr.hpp>
#include <gtsam/linear/VectorValues.h>
namespace gtsam {
@ -21,25 +20,23 @@ class IterativeSolver {
public:
typedef boost::shared_ptr<IterativeSolver> shared_ptr;
typedef IterativeOptimizationParameters Parameters;
protected:
Parameters::shared_ptr parameters_ ;
Parameters parameters_ ;
public:
IterativeSolver(): parameters_(new Parameters()) {}
IterativeSolver(): parameters_() {}
IterativeSolver(const IterativeSolver &solver) : parameters_(solver.parameters_) {}
IterativeSolver(const Parameters::shared_ptr& parameters) : parameters_(parameters) {}
IterativeSolver(const Parameters &parameters) : parameters_(new Parameters(parameters)) {}
IterativeSolver(const Parameters &parameters) : parameters_(parameters) {}
virtual ~IterativeSolver() {}
virtual VectorValues::shared_ptr optimize () = 0;
inline Parameters::shared_ptr parameters() { return parameters_ ; }
inline const Parameters& parameters() const { return parameters_ ; }
};
}

View File

@ -42,7 +42,7 @@ std::vector<size_t> extractColSpec_(const FactorGraph<GaussianFactor>& gfg, cons
return spec;
}
SimpleSPCGSolver::SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters::shared_ptr &parameters)
SimpleSPCGSolver::SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters &parameters)
: Base(parameters)
{
std::vector<size_t> colSpec = extractColSpec_(gfg, VariableIndex(gfg));
@ -97,13 +97,14 @@ VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial
double gamma = s.vector().squaredNorm(), new_gamma = 0.0, alpha = 0.0, beta = 0.0 ;
const double threshold =
::max(parameters_->epsilon_abs(),
parameters_->epsilon() * parameters_->epsilon() * gamma);
const size_t iMaxIterations = parameters_->maxIterations();
::max(parameters_.epsilon_abs(),
parameters_.epsilon() * parameters_.epsilon() * gamma);
const size_t iMaxIterations = parameters_.maxIterations();
const ConjugateGradientParameters::Verbosity verbosity = parameters_.cg_.verbosity();
if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR )
cout << "[SimpleSPCGSolver] epsilon = " << parameters_->epsilon()
<< ", max = " << parameters_->maxIterations()
if ( verbosity >= ConjugateGradientParameters::ERROR )
cout << "[SimpleSPCGSolver] epsilon = " << parameters_.epsilon()
<< ", max = " << parameters_.maxIterations()
<< ", ||r0|| = " << std::sqrt(gamma)
<< ", threshold = " << threshold << std::endl;
@ -120,14 +121,14 @@ VectorValues::shared_ptr SimpleSPCGSolver::optimize (const VectorValues &initial
p.vector() = s.vector() + beta * p.vector();
gamma = new_gamma ;
if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR) {
if ( verbosity >= ConjugateGradientParameters::ERROR) {
cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl;
}
if ( gamma < threshold ) break ;
} // k
if ( parameters_->verbosity() >= IterativeOptimizationParameters::ERROR )
if ( verbosity >= ConjugateGradientParameters::ERROR )
cout << "[SimpleSPCGSolver] iteration " << k << ": a = " << alpha << ": b = " << beta << ", ||r|| = " << std::sqrt(gamma) << endl;
/* transform y back to x */

View File

@ -55,7 +55,7 @@ protected:
public:
SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters::shared_ptr &parameters);
SimpleSPCGSolver(const GaussianFactorGraph &gfg, const Parameters &parameters);
virtual ~SimpleSPCGSolver() {}
virtual VectorValues::shared_ptr optimize () {return optimize(*y0_);}

View File

@ -72,7 +72,8 @@ void LevenbergMarquardtOptimizer::iterate() {
delta = gtsam::optimize(*EliminationTree<GaussianFactor>::Create(dampedSystem)->eliminate(params_.getEliminationFunction()));
}
else if ( params_.isCG() ) {
SimpleSPCGSolver solver(dampedSystem, *params_.iterativeParams);
IterativeOptimizationParameters::shared_ptr params(!params_.iterativeParams ? boost::make_shared<IterativeOptimizationParameters>() : params_.iterativeParams);
SimpleSPCGSolver solver(dampedSystem, *params);
delta = *solver.optimize();
}
else {

View File

@ -31,13 +31,13 @@ public:
MULTIFRONTAL_QR,
SEQUENTIAL_CHOLESKY,
SEQUENTIAL_QR,
CHOLMOD, /* Experimental Flag */
CG, /* Experimental Flag */
CHOLMOD, /* Experimental Flag */
};
LinearSolverType linearSolverType; ///< The type of linear solver to use in the nonlinear optimizer
boost::optional<Ordering> ordering; ///< The variable elimination ordering, or empty to use COLAMD (default: empty)
boost::optional<IterativeOptimizationParameters::shared_ptr> iterativeParams; ///< The container for iterativeOptimization parameters.
IterativeOptimizationParameters::shared_ptr iterativeParams; ///< The container for iterativeOptimization parameters. used in CG Solvers.
SuccessiveLinearizationParams() : linearSolverType(MULTIFRONTAL_CHOLESKY) {}