Replaced gettimeofday with boost posix time for compatibility on windows
parent
5defdbe73f
commit
f262801932
|
|
@ -24,7 +24,6 @@
|
|||
#include <boost/algorithm/string.hpp>
|
||||
#include <string>
|
||||
#include <cmath>
|
||||
#include <ctime>
|
||||
#include <fstream>
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -19,7 +19,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||
#include <ctime>
|
||||
#include <boost/date_time/posix_time/posix_time.hpp>
|
||||
|
||||
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() {
|
||||
|
|
|
|||
Loading…
Reference in New Issue