fix iteration timer in LM

release/4.3a0
Jing Dong 2015-10-19 00:07:23 -04:00
parent 971d2e519f
commit 9628b9b165
1 changed files with 9 additions and 5 deletions

View File

@ -239,7 +239,8 @@ void LevenbergMarquardtOptimizer::iterate() {
// Keep increasing lambda until we make make progress // Keep increasing lambda until we make make progress
while (true) { while (true) {
gttic(iteration);
gttic_(lm_iteration);
if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
cout << "trying lambda = " << state_.lambda << endl; cout << "trying lambda = " << state_.lambda << endl;
@ -323,14 +324,17 @@ void LevenbergMarquardtOptimizer::iterate() {
} }
} }
gttoc(iteration); gttoc_(lm_iteration);
if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) { if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) {
// do timing
tictoc_getNode(iteration_timer, lm_iteration);
double iterationTime = iteration_timer->secs();
if (state_.iterations == 0) if (state_.iterations == 0)
cout << "iter cost cost_change lambda success" << endl; cout << "iter cost cost_change lambda success iter_time" << endl;
cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d") % cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") %
state_.iterations % newError % costChange % state_.lambda % state_.iterations % newError % costChange % state_.lambda %
systemSolvedSuccessfully << endl; systemSolvedSuccessfully % iterationTime << endl;
} }
++state_.totalNumberInnerIterations; ++state_.totalNumberInnerIterations;