31 #include <boost/format.hpp> 32 #include <boost/optional.hpp> 33 #include <boost/range/adaptor/map.hpp> 45 using boost::adaptors::map_values;
46 typedef internal::LevenbergMarquardtState
State;
50 const Values& initialValues,
53 graph,
std::unique_ptr<State>(new State(initialValues, graph.
error(initialValues),
54 params.lambdaInitial, params.lambdaFactor))),
58 const Values& initialValues,
62 graph,
std::unique_ptr<State>(new State(initialValues, graph.
error(initialValues),
63 params.lambdaInitial, params.lambdaFactor))),
68 startTime_ = boost::posix_time::microsec_clock::universal_time();
73 auto currentState =
static_cast<const State*
>(
state_.get());
74 return currentState->lambda;
79 auto currentState =
static_cast<const State*
>(
state_.get());
80 return currentState->totalNumberInnerIterations;
92 auto currentState =
static_cast<const State*
>(
state_.get());
95 std::cout <<
"building damped system with lambda " << currentState->lambda << std::endl;
98 return currentState->buildDampedSystem(linear, sqrtHessianDiagonal);
100 return currentState->buildDampedSystem(linear);
106 auto currentState =
static_cast<const State*
>(
state_.get());
110 boost::posix_time::ptime currentTime = boost::posix_time::microsec_clock::universal_time();
111 os << currentState->totalNumberInnerIterations <<
"," 112 << 1
e-6 * (currentTime -
startTime_).total_microseconds() <<
"," 113 << currentError <<
"," << currentState->lambda <<
"," 114 << currentState->iterations << endl;
121 auto currentState =
static_cast<const State*
>(
state_.get());
124 #ifdef GTSAM_USING_NEW_BOOST_TIMERS 125 boost::timer::cpu_timer lamda_iteration_timer;
126 lamda_iteration_timer.start();
129 lamda_iteration_timer.restart();
133 cout <<
"trying lambda = " << currentState->lambda << endl;
139 double modelFidelity = 0.0;
140 bool step_is_successful =
false;
141 bool stopSearchingLambda =
false;
142 double newError = numeric_limits<double>::infinity(), costChange;
146 bool systemSolvedSuccessfully;
150 systemSolvedSuccessfully =
true;
152 systemSolvedSuccessfully =
false;
155 if (systemSolvedSuccessfully) {
157 cout <<
"linear delta norm = " << delta.
norm() << endl;
159 delta.
print(
"delta");
164 double newlinearizedError = linear.
error(delta);
167 double linearizedCostChange = oldLinearizedError - newlinearizedError;
169 cout <<
"newlinearizedError = " << newlinearizedError
170 <<
" linearizedCostChange = " << linearizedCostChange << endl;
172 if (linearizedCostChange >= 0) {
176 newValues = currentState->values.
retract(delta);
181 gttic(compute_error);
183 cout <<
"calculating error:" << endl;
185 gttoc(compute_error);
188 cout <<
"old error (" << currentState->error <<
") new (tentative) error (" << newError
192 costChange = currentState->error - newError;
197 modelFidelity = costChange / linearizedCostChange;
201 cout <<
"modelFidelity: " << modelFidelity << endl;
207 if (
std::abs(costChange) < minAbsoluteTolerance) {
209 cout <<
"abs(costChange)=" <<
std::abs(costChange)
210 <<
" minAbsoluteTolerance=" << minAbsoluteTolerance
212 stopSearchingLambda =
true;
219 #ifdef GTSAM_USING_NEW_BOOST_TIMERS 220 double iterationTime = 1
e-9 * lamda_iteration_timer.elapsed().wall;
222 double iterationTime = lamda_iteration_timer.elapsed();
224 if (currentState->iterations == 0)
225 cout <<
"iter cost cost_change lambda success iter_time" << endl;
227 cout << boost::format(
"% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % currentState->iterations %
228 newError % costChange % currentState->lambda % systemSolvedSuccessfully %
229 iterationTime << endl;
232 if (step_is_successful) {
236 state_ = currentState->decreaseLambda(
params_, modelFidelity, std::move(newValues), newError);
238 }
else if (!stopSearchingLambda) {
240 cout <<
"increasing lambda" << endl;
241 State* modifiedState =
static_cast<State*
>(
state_.get());
242 modifiedState->increaseLambda(
params_);
248 cout <<
"Warning: Levenberg-Marquardt giving up because " 249 "cannot decrease error with maximum lambda" << endl;
256 cout <<
"Levenberg-Marquardt: stopping as relative cost reduction is small" << endl;
263 auto currentState =
static_cast<const State*
>(
state_.get());
269 cout <<
"linearizing = " << endl;
272 if(currentState->totalNumberInnerIterations==0) {
276 cout <<
"Initial error: " << currentState->error
277 <<
", values: " << currentState->values.size() << std::endl;
284 sqrtHessianDiagonal = linear->hessianDiagonal();
285 for (
Vector&
v : sqrtHessianDiagonal | map_values) {
291 while (!
tryLambda(*linear, sqrtHessianDiagonal)) {
292 auto newState =
static_cast<const State*
>(
state_.get());
void writeLogFile(double currentError)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
bool tryLambda(const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal)
boost::posix_time::ptime startTime_
const NonlinearFactorGraph & graph() const
return the graph with nonlinear factors
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
double maxDiagonal
when using diagonal damping saturates the maximum diagonal entries (default: 1e32) ...
A LevenbergMarquardtState class containing most of the logic for Levenberg-Marquardt.
Values retract(const VectorValues &delta) const
double minModelFidelity
Lower bound for the modelFidelity to accept the result of an LM iteration.
NonlinearFactorGraph graph
double error(const VectorValues &x) const
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
static VectorValues Zero(const VectorValues &other)
std::unique_ptr< internal::NonlinearOptimizerState > state_
PIMPL'd state.
LevenbergMarquardtOptimizer(const NonlinearFactorGraph &graph, const Values &initialValues, const LevenbergMarquardtParams ¶ms=LevenbergMarquardtParams())
std::string logFile
an optional CSV log file, with [iteration, time, error, lambda]
const LevenbergMarquardtParams params_
LM parameters.
const LevenbergMarquardtParams & params() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double lambda() const
Access the current damping value.
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
GaussianFactorGraph buildDampedSystem(const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal) const
Exceptions that may be thrown by linear solver components.
int getInnerIterations() const
Access the current number of inner iterations.
internal::DoglegState State
typedef and functions to augment Eigen's VectorXd
bool diagonalDamping
if true, use diagonal of Hessian
virtual GaussianFactorGraph::shared_ptr linearize() const
ofstream os("timeSchurFactors.csv")
double minDiagonal
when using diagonal damping saturates the minimum diagonal entries (default: 1e-6) ...
NonlinearFactorGraph graph_
The graph with nonlinear factors.
virtual VectorValues solve(const GaussianFactorGraph &gfg, const NonlinearOptimizerParams ¶ms) const
GaussianFactorGraph::shared_ptr iterate() override
double error(const Values &values) const
void print(const std::string &str="VectorValues", const KeyFormatter &formatter=DefaultKeyFormatter) const
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::ver...
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.