diff --git a/gtsam/nonlinear/EasyFactorGraph.cpp b/gtsam/nonlinear/EasyFactorGraph.cpp index 4f3765dec..28e344efe 100644 --- a/gtsam/nonlinear/EasyFactorGraph.cpp +++ b/gtsam/nonlinear/EasyFactorGraph.cpp @@ -33,14 +33,14 @@ namespace gtsam { return LevenbergMarquardtOptimizer((*this), initialEstimate, p); } - const Values& EasyFactorGraph::optimize(const Values& initialEstimate, + Values EasyFactorGraph::optimize(const Values& initialEstimate, size_t verbosity) const { LevenbergMarquardtParams p; p.verbosity = (NonlinearOptimizerParams::Verbosity) verbosity; return optimizer(initialEstimate, p).optimizeSafely(); } - const Values& EasyFactorGraph::optimizeSPCG(const Values& initialEstimate, + Values EasyFactorGraph::optimizeSPCG(const Values& initialEstimate, size_t verbosity) const { LevenbergMarquardtParams p; p.verbosity = (NonlinearOptimizerParams::Verbosity) verbosity; diff --git a/gtsam/nonlinear/EasyFactorGraph.h b/gtsam/nonlinear/EasyFactorGraph.h index 131e6a06a..2629cb409 100644 --- a/gtsam/nonlinear/EasyFactorGraph.h +++ b/gtsam/nonlinear/EasyFactorGraph.h @@ -49,14 +49,14 @@ namespace gtsam { * @param initialEstimate initial estimate of all variables in the graph * @param verbosity unsigned specifying verbosity level */ - const Values& optimize(const Values& initialEstimate, size_t verbosity = 0) const; + Values optimize(const Values& initialEstimate, size_t verbosity = 0) const; /** * Safely optimize using subgraph preconditioning * @param initialEstimate initial estimate of all variables in the graph * @param verbosity unsigned specifying verbosity level */ - const Values& optimizeSPCG(const Values& initialEstimate, size_t verbosity = 0) const; + Values optimizeSPCG(const Values& initialEstimate, size_t verbosity = 0) const; /** * Return a Marginals object, so you can query marginals