LM optimizer use boost raw timer

release/4.3a0
Jing Dong 2015-10-19 19:08:29 -04:00
parent 9628b9b165
commit 42d07a99ff
1 changed files with 13 additions and 5 deletions

View File

@ -240,7 +240,13 @@ void LevenbergMarquardtOptimizer::iterate() {
// Keep increasing lambda until we make make progress // Keep increasing lambda until we make make progress
while (true) { while (true) {
gttic_(lm_iteration); #ifdef GTSAM_USING_NEW_BOOST_TIMERS
boost::timer::cpu_timer lamda_iteration_timer;
lamda_iteration_timer.start();
#else
boost::timer lamda_iteration_timer;
lamda_iteration_timer.restart();
#endif
if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
cout << "trying lambda = " << state_.lambda << endl; cout << "trying lambda = " << state_.lambda << endl;
@ -324,14 +330,16 @@ void LevenbergMarquardtOptimizer::iterate() {
} }
} }
gttoc_(lm_iteration);
if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) { if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) {
// do timing // do timing
tictoc_getNode(iteration_timer, lm_iteration); #ifdef GTSAM_USING_NEW_BOOST_TIMERS
double iterationTime = iteration_timer->secs(); double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall;
#else
double iterationTime = lamda_iteration_timer.elapsed();
#endif
if (state_.iterations == 0) if (state_.iterations == 0)
cout << "iter cost cost_change lambda success iter_time" << endl; cout << "iter cost cost_change lambda success iter_time" << endl;
cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % 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 % iterationTime << endl; systemSolvedSuccessfully % iterationTime << endl;