From 951377c80f3cd2dc7cc0311ecb33e0298d88f8d0 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Fri, 16 Oct 2015 14:18:13 -0400 Subject: [PATCH] fix type errors and timer issue in LM optimizer --- gtsam/base/timing.h | 1 + gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp | 15 ++++++++------- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/gtsam/base/timing.h b/gtsam/base/timing.h index d0bca4a9d..d1e90f63a 100644 --- a/gtsam/base/timing.h +++ b/gtsam/base/timing.h @@ -18,6 +18,7 @@ #pragma once #include +#include #include #include // for GTSAM_USE_TBB diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index ace35e530..ad976119a 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -22,11 +22,11 @@ #include #include #include +#include #include #include #include -#include #include #include @@ -239,7 +239,8 @@ void LevenbergMarquardtOptimizer::iterate() { // Keep increasing lambda until we make make progress while (true) { - boost::timer::cpu_timer timer; + gttic(iteration); + if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA) cout << "trying lambda = " << state_.lambda << endl; @@ -322,14 +323,14 @@ void LevenbergMarquardtOptimizer::iterate() { } } + gttoc(iteration); + if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) { - // do timing - double iterationTime = 1e-9 * timer.elapsed().wall; if (state_.iterations == 0) - cout << "iter cost cost_change lambda success iter_time" << endl; - cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % + cout << "iter cost cost_change lambda success" << endl; + cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d") % state_.iterations % newError % costChange % state_.lambda % - systemSolvedSuccessfully % iterationTime << endl; + systemSolvedSuccessfully << endl; } ++state_.totalNumberInnerIterations;