diff --git a/gtsam.h b/gtsam.h index b80ddd26e..a78c6901b 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1011,7 +1011,6 @@ class Marginals { #include class LevenbergMarquardtParams { LevenbergMarquardtParams(); - LevenbergMarquardtParams(double initial, double factor, double bound, size_t verbose); void print(string s) const; double getMaxIterations() const; diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index f5e4195da..5677f6c08 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -46,13 +46,9 @@ public: double lambdaUpperBound; ///< The maximum lambda to try before assuming the optimization has failed (default: 1e5) VerbosityLM verbosityLM; ///< The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::verbosity - LevenbergMarquardtParams() : - lambdaInitial(1e-5), lambdaFactor(10.0), lambdaUpperBound(1e5), verbosityLM(SILENT) {} - - LevenbergMarquardtParams(double initial, double factor, double bound, size_t verbose) : - lambdaInitial(initial), lambdaFactor(factor), lambdaUpperBound(bound), verbosityLM(VerbosityLM(verbose)) {} - + LevenbergMarquardtParams() : lambdaInitial(1e-5), lambdaFactor(10.0), lambdaUpperBound(1e5), verbosityLM(SILENT) {} virtual ~LevenbergMarquardtParams() {} + virtual void print(const std::string& str = "") const; inline double getlambdaInitial() const { return lambdaInitial; } diff --git a/matlab/examples/SFMExample.m b/matlab/examples/SFMExample.m index 34682e1e6..277f31648 100644 --- a/matlab/examples/SFMExample.m +++ b/matlab/examples/SFMExample.m @@ -63,7 +63,7 @@ initialEstimate.print(sprintf('\nInitial estimate:\n ')); %% Fine grain optimization, allowing user to iterate step by step -parameters = gtsamLevenbergMarquardtParams(1e-5, 1e-5, 0, 0); +parameters = gtsamLevenbergMarquardtParams; parameters.setlambdaInitial(1.0); parameters.setVerbosityLM('trylambda'); diff --git a/matlab/tests/testSFMExample.m b/matlab/tests/testSFMExample.m index ebda9535e..ef27a7e4b 100644 --- a/matlab/tests/testSFMExample.m +++ b/matlab/tests/testSFMExample.m @@ -48,7 +48,7 @@ for j=1:size(truth.points,2) end %% Optimization -parameters = gtsamLevenbergMarquardtParams(1e-5, 1e-5, 0, 0); +parameters = gtsamLevenbergMarquardtParams; optimizer = graph.optimizer(initialEstimate, parameters); for i=1:5 optimizer.iterate();