diff --git a/gtsam.h b/gtsam.h index bc44bc543..70f7cdcf1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1740,6 +1740,7 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor { //************************************************************************* #include +#include virtual class NonlinearOptimizerParams { NonlinearOptimizerParams(); void print(string s) const; @@ -1755,15 +1756,6 @@ virtual class NonlinearOptimizerParams { void setAbsoluteErrorTol(double value); void setErrorTol(double value); void setVerbosity(string s); -}; - -bool checkConvergence(double relativeErrorTreshold, - double absoluteErrorTreshold, double errorThreshold, - double currentError, double newError); - -#include -virtual class NonlinearSolverParams : gtsam::NonlinearOptimizerParams { - NonlinearSolverParams(); string getLinearSolverType() const; @@ -1777,13 +1769,24 @@ virtual class NonlinearSolverParams : gtsam::NonlinearOptimizerParams { bool isCG() const; }; +bool checkConvergence(double relativeErrorTreshold, + double absoluteErrorTreshold, double errorThreshold, + double currentError, double newError); + +//#include +//virtual class NonlinearSolverParams : gtsam::NonlinearOptimizerParams { +// NonlinearSolverParams(); +// +// +//}; + #include -virtual class GaussNewtonParams : gtsam::NonlinearSolverParams { +virtual class GaussNewtonParams : gtsam::NonlinearOptimizerParams { GaussNewtonParams(); }; #include -virtual class LevenbergMarquardtParams : gtsam::NonlinearSolverParams { +virtual class LevenbergMarquardtParams : gtsam::NonlinearOptimizerParams { LevenbergMarquardtParams(); double getlambdaInitial() const; @@ -1798,7 +1801,7 @@ virtual class LevenbergMarquardtParams : gtsam::NonlinearSolverParams { }; #include -virtual class DoglegParams : gtsam::NonlinearSolverParams { +virtual class DoglegParams : gtsam::NonlinearOptimizerParams { DoglegParams(); double getDeltaInitial() const; diff --git a/gtsam/linear/SubgraphSolver.h b/gtsam/linear/SubgraphSolver.h index a635efcd2..f6557a2c2 100644 --- a/gtsam/linear/SubgraphSolver.h +++ b/gtsam/linear/SubgraphSolver.h @@ -45,7 +45,7 @@ public: * To use it in nonlinear optimization, please see the following example * * LevenbergMarquardtParams parameters; - * parameters.linearSolverType = NonlinearSolverParams::CONJUGATE_GRADIENT; + * parameters.linearSolverType = NonlinearOptimizerParams::CONJUGATE_GRADIENT; * parameters.iterativeParams = boost::make_shared(); * LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); * Values result = optimizer.optimize(); diff --git a/gtsam/nonlinear/NonlinearOptimizerParams.h b/gtsam/nonlinear/NonlinearOptimizerParams.h index 6e0faa1f1..42fce2fed 100644 --- a/gtsam/nonlinear/NonlinearOptimizerParams.h +++ b/gtsam/nonlinear/NonlinearOptimizerParams.h @@ -92,7 +92,7 @@ private: public: - /** See NonlinearSolverParams::linearSolverType */ + /** See NonlinearOptimizerParams::linearSolverType */ enum LinearSolverType { MULTIFRONTAL_CHOLESKY,