release/4.3a0
parent
0d597082f2
commit
b0c91d2fcf
|
|
@ -48,7 +48,7 @@ void DoglegOptimizer::iterate(void) {
|
|||
GaussianBayesNet::shared_ptr bn = EliminationTree<GaussianFactor>::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 {
|
||||
|
|
|
|||
|
|
@ -41,7 +41,7 @@ void GaussNewtonOptimizer::iterate() {
|
|||
else if ( params_.isSequential() ) {
|
||||
delta = gtsam::optimize(*EliminationTree<GaussianFactor>::Create(*linear)->eliminate(params_.getEliminationFunction()));
|
||||
}
|
||||
else if ( params_.isSPCG() ) {
|
||||
else if ( params_.isCG() ) {
|
||||
throw runtime_error("todo: ");
|
||||
}
|
||||
else {
|
||||
|
|
|
|||
|
|
@ -70,7 +70,7 @@ void LevenbergMarquardtOptimizer::iterate() {
|
|||
else if ( params_.isSequential() ) {
|
||||
delta = gtsam::optimize(*EliminationTree<GaussianFactor>::Create(dampedSystem)->eliminate(params_.getEliminationFunction()));
|
||||
}
|
||||
else if ( params_.isSPCG() ) {
|
||||
else if ( params_.isCG() ) {
|
||||
throw runtime_error("todo: ");
|
||||
}
|
||||
else {
|
||||
|
|
|
|||
|
|
@ -19,6 +19,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||
#include <gtsam/linear/IterativeOptimizationParameters.h>
|
||||
|
||||
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> ordering; ///< The variable elimination ordering, or empty to use COLAMD (default: empty)
|
||||
boost::optional<IterativeOptimizationParameters::shared_ptr> 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() {
|
||||
|
|
|
|||
Loading…
Reference in New Issue