use chrono instead of ptime

release/4.3a0
kartik arcot 2023-01-23 09:55:49 -08:00 committed by Frank Dellaert
parent 9929649092
commit a611d607b3
2 changed files with 11 additions and 5 deletions

View File

@ -61,7 +61,8 @@ LevenbergMarquardtOptimizer::LevenbergMarquardtOptimizer(const NonlinearFactorGr
/* ************************************************************************* */
void LevenbergMarquardtOptimizer::initTime() {
startTime_ = boost::posix_time::microsec_clock::universal_time();
// use chrono to measure time in microseconds
startTime_ = std::chrono::high_resolution_clock::now();
}
/* ************************************************************************* */
@ -103,9 +104,12 @@ inline void LevenbergMarquardtOptimizer::writeLogFile(double currentError){
if (!params_.logFile.empty()) {
ofstream os(params_.logFile.c_str(), ios::app);
boost::posix_time::ptime currentTime = boost::posix_time::microsec_clock::universal_time();
// use chrono to measure time in microseconds
auto currentTime = std::chrono::high_resolution_clock::now();
// Get the time spent in seconds and print it
double timeSpent = std::chrono::duration_cast<std::chrono::microseconds>(currentTime - startTime_).count() / 1e6;
os << /*inner iterations*/ currentState->totalNumberInnerIterations << ","
<< 1e-6 * (currentTime - startTime_).total_microseconds() << ","
<< timeSpent << ","
<< /*current error*/ currentError << "," << currentState->lambda << ","
<< /*outer iterations*/ currentState->iterations << endl;
}

View File

@ -23,7 +23,7 @@
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/LevenbergMarquardtParams.h>
#include <gtsam/linear/VectorValues.h>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <chrono>
class NonlinearOptimizerMoreOptimizationTest;
@ -36,7 +36,9 @@ class GTSAM_EXPORT LevenbergMarquardtOptimizer: public NonlinearOptimizer {
protected:
const LevenbergMarquardtParams params_; ///< LM parameters
boost::posix_time::ptime startTime_;
// startTime_ is a chrono time point
std::chrono::time_point<std::chrono::high_resolution_clock> startTime_; ///< time when optimization started
void initTime();