fix timing flag

release/4.3a0
kartik arcot 2023-01-23 17:33:22 -08:00 committed by Frank Dellaert
parent 89338a3230
commit 0ab76abe93
2 changed files with 15 additions and 15 deletions

View File

@ -56,7 +56,7 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) {
TimingOutline::TimingOutline(const std::string& label, size_t id) : 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_( id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_(
0), lastChildOrder_(0), label_(label) { 0), lastChildOrder_(0), label_(label) {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
#ifdef GTSAM_USING_NEW_BOOST_TIMERS #ifdef GTSAM_USING_NEW_BOOST_TIMERS
timer_.stop(); timer_.stop();
#endif #endif
@ -65,7 +65,7 @@ TimingOutline::TimingOutline(const std::string& label, size_t id) :
/* ************************************************************************* */ /* ************************************************************************* */
size_t TimingOutline::time() const { size_t TimingOutline::time() const {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
size_t time = 0; size_t time = 0;
bool hasChildren = false; bool hasChildren = false;
for(const ChildMap::value_type& child: children_) { for(const ChildMap::value_type& child: children_) {
@ -83,7 +83,7 @@ size_t TimingOutline::time() const {
/* ************************************************************************* */ /* ************************************************************************* */
void TimingOutline::print(const std::string& outline) const { void TimingOutline::print(const std::string& outline) const {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
std::string formattedLabel = label_; std::string formattedLabel = label_;
std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' '); std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' ');
std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU (" std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU ("
@ -107,7 +107,7 @@ void TimingOutline::print(const std::string& outline) const {
void TimingOutline::print2(const std::string& outline, void TimingOutline::print2(const std::string& outline,
const double parentTotal) const { const double parentTotal) const {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2; const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2;
const double selfTotal = self(), selfMean = selfTotal / double(n_); const double selfTotal = self(), selfMean = selfTotal / double(n_);
const double childTotal = secs(); const double childTotal = secs();
@ -152,7 +152,7 @@ void TimingOutline::print2(const std::string& outline,
/* ************************************************************************* */ /* ************************************************************************* */
const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) { const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
assert(thisPtr.lock().get() == this); assert(thisPtr.lock().get() == this);
std::shared_ptr<TimingOutline>& result = children_[child]; std::shared_ptr<TimingOutline>& result = children_[child];
if (!result) { if (!result) {
@ -171,7 +171,7 @@ const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
/* ************************************************************************* */ /* ************************************************************************* */
void TimingOutline::tic() { void TimingOutline::tic() {
// Disable this entire function if we are not using boost // Disable this entire function if we are not using boost
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
#ifdef GTSAM_USING_NEW_BOOST_TIMERS #ifdef GTSAM_USING_NEW_BOOST_TIMERS
assert(timer_.is_stopped()); assert(timer_.is_stopped());
timer_.start(); timer_.start();
@ -190,7 +190,7 @@ void TimingOutline::tic() {
/* ************************************************************************* */ /* ************************************************************************* */
void TimingOutline::toc() { void TimingOutline::toc() {
// Disable this entire function if we are not using boost // Disable this entire function if we are not using boost
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
#ifdef GTSAM_USING_NEW_BOOST_TIMERS #ifdef GTSAM_USING_NEW_BOOST_TIMERS
@ -224,7 +224,7 @@ void TimingOutline::toc() {
/* ************************************************************************* */ /* ************************************************************************* */
void TimingOutline::finishedIteration() { void TimingOutline::finishedIteration() {
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
if (tIt_ > tMax_) if (tIt_ > tMax_)
tMax_ = tIt_; tMax_ = tIt_;
if (tMin_ == 0 || tIt_ < tMin_) if (tMin_ == 0 || tIt_ < tMin_)
@ -239,7 +239,7 @@ void TimingOutline::finishedIteration() {
/* ************************************************************************* */ /* ************************************************************************* */
size_t getTicTocID(const char *descriptionC) { size_t getTicTocID(const char *descriptionC) {
// disable anything which refers to TimingOutline as well, for good measure // disable anything which refers to TimingOutline as well, for good measure
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
const std::string description(descriptionC); const std::string description(descriptionC);
// Global (static) map from strings to ID numbers and current next ID number // Global (static) map from strings to ID numbers and current next ID number
static size_t nextId = 0; static size_t nextId = 0;
@ -262,7 +262,7 @@ size_t getTicTocID(const char *descriptionC) {
/* ************************************************************************* */ /* ************************************************************************* */
void tic(size_t id, const char *labelC) { void tic(size_t id, const char *labelC) {
// disable anything which refers to TimingOutline as well, for good measure // disable anything which refers to TimingOutline as well, for good measure
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
const std::string label(labelC); const std::string label(labelC);
std::shared_ptr<TimingOutline> node = // std::shared_ptr<TimingOutline> node = //
gCurrentTimer.lock()->child(id, label, gCurrentTimer); gCurrentTimer.lock()->child(id, label, gCurrentTimer);
@ -274,7 +274,7 @@ void tic(size_t id, const char *labelC) {
/* ************************************************************************* */ /* ************************************************************************* */
void toc(size_t id, const char *label) { void toc(size_t id, const char *label) {
// disable anything which refers to TimingOutline as well, for good measure // disable anything which refers to TimingOutline as well, for good measure
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
std::shared_ptr<TimingOutline> current(gCurrentTimer.lock()); std::shared_ptr<TimingOutline> current(gCurrentTimer.lock());
if (id != current->id_) { if (id != current->id_) {
gTimingRoot->print(); gTimingRoot->print();

View File

@ -21,7 +21,7 @@
#include <gtsam/dllexport.h> #include <gtsam/dllexport.h>
#include <gtsam/config.h> // for GTSAM_USE_TBB #include <gtsam/config.h> // for GTSAM_USE_TBB
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
#include <boost/version.hpp> #include <boost/version.hpp>
#endif #endif
@ -107,7 +107,7 @@
// have matching gttic/gttoc statments. You may want to consider reorganizing your timing // have matching gttic/gttoc statments. You may want to consider reorganizing your timing
// outline to match the scope of your code. // outline to match the scope of your code.
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
// Automatically use the new Boost timers if version is recent enough. // Automatically use the new Boost timers if version is recent enough.
#if BOOST_VERSION >= 104800 #if BOOST_VERSION >= 104800
# ifndef GTSAM_DISABLE_NEW_TIMERS # ifndef GTSAM_DISABLE_NEW_TIMERS
@ -165,7 +165,7 @@ namespace gtsam {
ChildMap children_; ///< subtrees ChildMap children_; ///< subtrees
// disable all timers if not using boost // disable all timers if not using boost
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
#ifdef GTSAM_USING_NEW_BOOST_TIMERS #ifdef GTSAM_USING_NEW_BOOST_TIMERS
boost::timer::cpu_timer timer_; boost::timer::cpu_timer timer_;
#else #else
@ -183,7 +183,7 @@ namespace gtsam {
GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId); GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId);
GTSAM_EXPORT size_t time() const; ///< time taken, including children GTSAM_EXPORT size_t time() const; ///< time taken, including children
double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children
#ifdef GTSAM_USE_BOOST #ifdef GTSAM_USE_BOOST_FEATURES
double self() const { return double(t_) / 1000000.0;} ///< self time only, in seconds 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 wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds
double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds