fix type errors and timer issue in LM optimizer
parent
c829e52c95
commit
951377c80f
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/base/FastMap.h>
|
#include <gtsam/base/FastMap.h>
|
||||||
|
#include <gtsam/base/types.h>
|
||||||
#include <gtsam/dllexport.h>
|
#include <gtsam/dllexport.h>
|
||||||
#include <gtsam/config.h> // for GTSAM_USE_TBB
|
#include <gtsam/config.h> // for GTSAM_USE_TBB
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -22,11 +22,11 @@
|
||||||
#include <gtsam/linear/GaussianFactorGraph.h>
|
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||||
#include <gtsam/linear/VectorValues.h>
|
#include <gtsam/linear/VectorValues.h>
|
||||||
#include <gtsam/linear/Errors.h>
|
#include <gtsam/linear/Errors.h>
|
||||||
|
#include <gtsam/base/timing.h>
|
||||||
|
|
||||||
#include <boost/algorithm/string.hpp>
|
#include <boost/algorithm/string.hpp>
|
||||||
#include <boost/range/adaptor/map.hpp>
|
#include <boost/range/adaptor/map.hpp>
|
||||||
#include <boost/format.hpp>
|
#include <boost/format.hpp>
|
||||||
#include <boost/timer/timer.hpp>
|
|
||||||
|
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
|
@ -239,7 +239,8 @@ void LevenbergMarquardtOptimizer::iterate() {
|
||||||
|
|
||||||
// Keep increasing lambda until we make make progress
|
// Keep increasing lambda until we make make progress
|
||||||
while (true) {
|
while (true) {
|
||||||
boost::timer::cpu_timer timer;
|
gttic(iteration);
|
||||||
|
|
||||||
if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
|
if (lmVerbosity >= LevenbergMarquardtParams::TRYLAMBDA)
|
||||||
cout << "trying lambda = " << state_.lambda << endl;
|
cout << "trying lambda = " << state_.lambda << endl;
|
||||||
|
|
||||||
|
|
@ -322,14 +323,14 @@ void LevenbergMarquardtOptimizer::iterate() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
gttoc(iteration);
|
||||||
|
|
||||||
if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) {
|
if (lmVerbosity == LevenbergMarquardtParams::SUMMARY) {
|
||||||
// do timing
|
|
||||||
double iterationTime = 1e-9 * timer.elapsed().wall;
|
|
||||||
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" << endl;
|
||||||
cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") %
|
cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d") %
|
||||||
state_.iterations % newError % costChange % state_.lambda %
|
state_.iterations % newError % costChange % state_.lambda %
|
||||||
systemSolvedSuccessfully % iterationTime << endl;
|
systemSolvedSuccessfully << endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
++state_.totalNumberInnerIterations;
|
++state_.totalNumberInnerIterations;
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue