commit
9db9ad7a03
|
@ -8,7 +8,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/concept_check.hpp>
|
||||
#include <boost/concept/assert.hpp>
|
||||
#include <boost/concept/requires.hpp>
|
||||
|
|
|
@ -1151,7 +1151,7 @@ TEST(Matrix, Matrix24IsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Matrix, RowMajorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double, 2, 3, Eigen::RowMajor> RowMajor;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowMajor>);
|
||||
#endif
|
||||
|
@ -1166,7 +1166,7 @@ TEST(Matrix, VectorIsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Matrix, RowVectorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double, 1, -1> RowVector;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<Vector5>);
|
||||
|
|
|
@ -272,7 +272,7 @@ TEST(Vector, VectorIsVectorSpace) {
|
|||
}
|
||||
|
||||
TEST(Vector, RowVectorIsVectorSpace) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
typedef Eigen::Matrix<double,1,-1> RowVector;
|
||||
GTSAM_CONCEPT_ASSERT(IsVectorSpace<RowVector>);
|
||||
#endif
|
||||
|
|
|
@ -57,7 +57,7 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) {
|
|||
TimingOutline::TimingOutline(const std::string& label, size_t id) :
|
||||
id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_(
|
||||
0), lastChildOrder_(0), label_(label) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
timer_.stop();
|
||||
#endif
|
||||
|
@ -66,7 +66,7 @@ TimingOutline::TimingOutline(const std::string& label, size_t id) :
|
|||
|
||||
/* ************************************************************************* */
|
||||
size_t TimingOutline::time() const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
size_t time = 0;
|
||||
bool hasChildren = false;
|
||||
for(const ChildMap::value_type& child: children_) {
|
||||
|
@ -84,7 +84,7 @@ size_t TimingOutline::time() const {
|
|||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::print(const std::string& outline) const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
std::string formattedLabel = label_;
|
||||
std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' ');
|
||||
std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU ("
|
||||
|
@ -108,7 +108,7 @@ void TimingOutline::print(const std::string& outline) const {
|
|||
|
||||
void TimingOutline::print2(const std::string& outline,
|
||||
const double parentTotal) const {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2;
|
||||
const double selfTotal = self(), selfMean = selfTotal / double(n_);
|
||||
const double childTotal = secs();
|
||||
|
@ -153,7 +153,7 @@ void TimingOutline::print2(const std::string& outline,
|
|||
/* ************************************************************************* */
|
||||
const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
|
||||
const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
assert(thisPtr.lock().get() == this);
|
||||
std::shared_ptr<TimingOutline>& result = children_[child];
|
||||
if (!result) {
|
||||
|
@ -172,7 +172,7 @@ const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
|
|||
/* ************************************************************************* */
|
||||
void TimingOutline::tic() {
|
||||
// Disable this entire function if we are not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
assert(timer_.is_stopped());
|
||||
timer_.start();
|
||||
|
@ -191,7 +191,7 @@ void TimingOutline::tic() {
|
|||
/* ************************************************************************* */
|
||||
void TimingOutline::toc() {
|
||||
// Disable this entire function if we are not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
|
||||
|
@ -225,7 +225,7 @@ void TimingOutline::toc() {
|
|||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::finishedIteration() {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
if (tIt_ > tMax_)
|
||||
tMax_ = tIt_;
|
||||
if (tMin_ == 0 || tIt_ < tMin_)
|
||||
|
@ -240,7 +240,7 @@ void TimingOutline::finishedIteration() {
|
|||
/* ************************************************************************* */
|
||||
size_t getTicTocID(const char *descriptionC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string description(descriptionC);
|
||||
// Global (static) map from strings to ID numbers and current next ID number
|
||||
static size_t nextId = 0;
|
||||
|
@ -263,7 +263,7 @@ size_t getTicTocID(const char *descriptionC) {
|
|||
/* ************************************************************************* */
|
||||
void tic(size_t id, const char *labelC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string label(labelC);
|
||||
std::shared_ptr<TimingOutline> node = //
|
||||
gCurrentTimer.lock()->child(id, label, gCurrentTimer);
|
||||
|
@ -275,7 +275,7 @@ void tic(size_t id, const char *labelC) {
|
|||
/* ************************************************************************* */
|
||||
void toc(size_t id, const char *labelC) {
|
||||
// disable anything which refers to TimingOutline as well, for good measure
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
const std::string label(labelC);
|
||||
std::shared_ptr<TimingOutline> current(gCurrentTimer.lock());
|
||||
if (id != current->id_) {
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
#include <gtsam/dllexport.h>
|
||||
#include <gtsam/config.h> // for GTSAM_USE_TBB
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <boost/version.hpp>
|
||||
#endif
|
||||
|
||||
|
@ -107,7 +107,7 @@
|
|||
// have matching gttic/gttoc statments. You may want to consider reorganizing your timing
|
||||
// outline to match the scope of your code.
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
// Automatically use the new Boost timers if version is recent enough.
|
||||
#if BOOST_VERSION >= 104800
|
||||
# ifndef GTSAM_DISABLE_NEW_TIMERS
|
||||
|
@ -165,7 +165,7 @@ namespace gtsam {
|
|||
ChildMap children_; ///< subtrees
|
||||
|
||||
// disable all timers if not using boost
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
boost::timer::cpu_timer timer_;
|
||||
#else
|
||||
|
@ -183,7 +183,7 @@ namespace gtsam {
|
|||
GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId);
|
||||
GTSAM_EXPORT size_t time() const; ///< time taken, including children
|
||||
double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
double self() const { return double(t_) / 1000000.0;} ///< self time only, in seconds
|
||||
double wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds
|
||||
double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#include <gtsam/linear/linearExceptions.h>
|
||||
#include <gtsam/inference/Ordering.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#include <gtsam/base/timing.h>
|
||||
#endif
|
||||
|
||||
|
@ -123,7 +123,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
|
|||
auto currentState = static_cast<const State*>(state_.get());
|
||||
bool verbose = (params_.verbosityLM >= LevenbergMarquardtParams::TRYLAMBDA);
|
||||
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
boost::timer::cpu_timer lamda_iteration_timer;
|
||||
lamda_iteration_timer.start();
|
||||
|
@ -222,7 +222,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear,
|
|||
} // if (systemSolvedSuccessfully)
|
||||
|
||||
if (params_.verbosityLM == LevenbergMarquardtParams::SUMMARY) {
|
||||
#ifdef GTSAM_USE_BOOST_FEATURES
|
||||
#if GTSAM_USE_BOOST_FEATURES
|
||||
// do timing
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall;
|
||||
|
|
Loading…
Reference in New Issue