From f262801932781e7313ec70c4015cbf04d173c7f8 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Tue, 5 Nov 2013 16:06:12 +0000 Subject: [PATCH] Replaced gettimeofday with boost posix time for compatibility on windows --- gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp | 7 ++----- gtsam/nonlinear/LevenbergMarquardtOptimizer.h | 8 +++----- 2 files changed, 5 insertions(+), 10 deletions(-) diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index bb895dc27..7498ae759 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -24,7 +24,6 @@ #include #include #include -#include #include using namespace std; @@ -118,11 +117,9 @@ void LevenbergMarquardtOptimizer::iterate() { if (!params_.logFile.empty()) { ofstream os(params_.logFile.c_str(), ios::app); - timeval rawtime; - gettimeofday(&rawtime, NULL); - double currentTime = rawtime.tv_sec + rawtime.tv_usec / 1000000.0; + boost::posix_time::ptime currentTime = boost::posix_time::microsec_clock::universal_time(); - os << state_.iterations << "," << currentTime - state_.startTime << "," + os << state_.iterations << "," << 1e-6 * (currentTime - state_.startTime).total_microseconds() << "," << state_.error << "," << state_.lambda << endl; } diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index 1b5b39fc8..303702cca 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -19,7 +19,7 @@ #pragma once #include -#include +#include namespace gtsam { @@ -100,16 +100,14 @@ class GTSAM_EXPORT LevenbergMarquardtState: public NonlinearOptimizerState { public: double lambda; int totalNumberInnerIterations; // The total number of inner iterations in the optimization (for each iteration, LM may try multiple iterations with different lambdas) - double startTime; + boost::posix_time::ptime startTime; LevenbergMarquardtState() { initTime(); } void initTime() { - timeval tod; - gettimeofday(&tod, NULL); - startTime = tod.tv_sec + tod.tv_usec / 1000000.0; + startTime = boost::posix_time::microsec_clock::universal_time(); } virtual ~LevenbergMarquardtState() {